Skip to content

Commit

Permalink
add ament_lint_auto test and adjust code style
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Ye <chris.ye@intel.com>
  • Loading branch information
yechun1 committed Oct 22, 2018
1 parent 4cb2f83 commit 958052d
Show file tree
Hide file tree
Showing 25 changed files with 1,059 additions and 1,190 deletions.
5 changes: 5 additions & 0 deletions depth_image_proc/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -85,4 +85,9 @@ install(DIRECTORY examples/launch
DESTINATION share/${PROJECT_NAME}/
)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
endif()

ament_package()
6 changes: 2 additions & 4 deletions depth_image_proc/examples/launch/convert_metric.launch.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,8 @@
#!/usr/bin/env python
#
# Software License Agreement (BSD License)
#
# Copyright (c) 2008, Willow Garage, Inc.
# All rights reserved.
#
# Software License Agreement (BSD License 2.0)
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
Expand Down
6 changes: 2 additions & 4 deletions depth_image_proc/examples/launch/crop_foremost.launch.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,8 @@
#!/usr/bin/env python
#
# Software License Agreement (BSD License)
#
# Copyright (c) 2008, Willow Garage, Inc.
# All rights reserved.
#
# Software License Agreement (BSD License 2.0)
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
Expand Down
6 changes: 2 additions & 4 deletions depth_image_proc/examples/launch/disparity.launch.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,8 @@
#!/usr/bin/env python
#
# Software License Agreement (BSD License)
#
# Copyright (c) 2008, Willow Garage, Inc.
# All rights reserved.
#
# Software License Agreement (BSD License 2.0)
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
Expand Down
6 changes: 2 additions & 4 deletions depth_image_proc/examples/launch/point_cloud_xyz.launch.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,8 @@
#!/usr/bin/env python
#
# Software License Agreement (BSD License)
#
# Copyright (c) 2008, Willow Garage, Inc.
# All rights reserved.
#
# Software License Agreement (BSD License 2.0)
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
Expand Down
Original file line number Diff line number Diff line change
@@ -1,10 +1,8 @@
#!/usr/bin/env python
#
# Software License Agreement (BSD License)
#
# Copyright (c) 2008, Willow Garage, Inc.
# All rights reserved.
#
# Software License Agreement (BSD License 2.0)
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
Expand Down
6 changes: 2 additions & 4 deletions depth_image_proc/examples/launch/point_cloud_xyzi.launch.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,8 @@
#!/usr/bin/env python
#
# Software License Agreement (BSD License)
#
# Copyright (c) 2008, Willow Garage, Inc.
# All rights reserved.
#
# Software License Agreement (BSD License 2.0)
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
Expand Down
Original file line number Diff line number Diff line change
@@ -1,10 +1,8 @@
#!/usr/bin/env python
#
# Software License Agreement (BSD License)
#
# Copyright (c) 2008, Willow Garage, Inc.
# All rights reserved.
#
# Software License Agreement (BSD License 2.0)
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
Expand Down
9 changes: 4 additions & 5 deletions depth_image_proc/examples/launch/point_cloud_xyzrgb.launch.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,8 @@
#!/usr/bin/env python
#
# Software License Agreement (BSD License)
#
# Copyright (c) 2008, Willow Garage, Inc.
# All rights reserved.
#
# Software License Agreement (BSD License 2.0)
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
Expand Down Expand Up @@ -44,7 +42,8 @@ def generate_launch_description():
package='composition', node_executable='api_composition', output='screen',
remappings=[('rgb/camera_info', '/camera/color/camera_info'),
('rgb/image_rect_color/raw', '/camera/color/image_raw/raw'),
('depth_registered/image_rect/raw', '/camera/aligned_depth_to_color/image_raw/raw')]),
('depth_registered/image_rect/raw',
'/camera/aligned_depth_to_color/image_raw/raw')]),
launch_ros.actions.Node(
package='composition', node_executable='api_composition_cli', output='screen',
arguments=['depth_image_proc', 'depth_image_proc::PointCloudXyzrgbNode']),
Expand Down
9 changes: 4 additions & 5 deletions depth_image_proc/examples/launch/register.launch.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,8 @@
#!/usr/bin/env python
#
# Software License Agreement (BSD License)
#
# Copyright (c) 2008, Willow Garage, Inc.
# All rights reserved.
#
# Software License Agreement (BSD License 2.0)
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
Expand Down Expand Up @@ -45,7 +43,8 @@ def generate_launch_description():
remappings=[('depth/image_rect/raw', '/camera/depth/image_rect_raw/raw'),
('depth/camera_info', '/camera/depth/camera_info'),
('rgb/camera_info', '/camera/color/camera_info'),
('depth_registered/image_rect/raw', '/camera/depth_registered/image_rect/raw'),
('depth_registered/image_rect/raw',
'/camera/depth_registered/image_rect/raw'),
('depth_registered/camera_info', '/camera/depth_registered/camera_info')]),
launch_ros.actions.Node(
package='composition', node_executable='api_composition_cli', output='screen',
Expand Down
101 changes: 0 additions & 101 deletions depth_image_proc/include/depth_image_proc/depth_conversions.h

This file was deleted.

94 changes: 94 additions & 0 deletions depth_image_proc/include/depth_image_proc/depth_conversions.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,94 @@
// Copyright (c) 2008, Willow Garage, Inc.
// All rights reserved.
//
// Software License Agreement (BSD License 2.0)
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above
// copyright notice, this list of conditions and the following
// disclaimer in the documentation and/or other materials provided
// with the distribution.
// * Neither the name of the Willow Garage nor the names of its
// contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.
#ifndef DEPTH_IMAGE_PROC__DEPTH_CONVERSIONS_HPP_
#define DEPTH_IMAGE_PROC__DEPTH_CONVERSIONS_HPP_

#include <sensor_msgs/msg/image.h>
#include <sensor_msgs/point_cloud2_iterator.hpp>
#include <image_geometry/pinhole_camera_model.h>
#include <depth_image_proc/depth_traits.hpp>

#include <limits>

namespace depth_image_proc
{

using PointCloud = sensor_msgs::msg::PointCloud2;

// Handles float or uint16 depths
template<typename T>
void convert(
const sensor_msgs::msg::Image::ConstSharedPtr & depth_msg,
PointCloud::SharedPtr & cloud_msg,
const image_geometry::PinholeCameraModel & model,
double range_max = 0.0)
{
// Use correct principal point from calibration
float center_x = model.cx();
float center_y = model.cy();

// Combine unit conversion (if necessary) with scaling by focal length for computing (X,Y)
double unit_scaling = DepthTraits<T>::toMeters(T(1) );
float constant_x = unit_scaling / model.fx();
float constant_y = unit_scaling / model.fy();
float bad_point = std::numeric_limits<float>::quiet_NaN();

sensor_msgs::PointCloud2Iterator<float> iter_x(*cloud_msg, "x");
sensor_msgs::PointCloud2Iterator<float> iter_y(*cloud_msg, "y");
sensor_msgs::PointCloud2Iterator<float> iter_z(*cloud_msg, "z");
const T * depth_row = reinterpret_cast<const T *>(&depth_msg->data[0]);
int row_step = depth_msg->step / sizeof(T);
for (int v = 0; v < static_cast<int>(cloud_msg->height); ++v, depth_row += row_step) {
for (int u = 0; u < static_cast<int>(cloud_msg->width); ++u, ++iter_x, ++iter_y, ++iter_z) {
T depth = depth_row[u];

// Missing points denoted by NaNs
if (!DepthTraits<T>::valid(depth)) {
if (range_max != 0.0) {
depth = DepthTraits<T>::fromMeters(range_max);
} else {
*iter_x = *iter_y = *iter_z = bad_point;
continue;
}
}

// Fill in XYZ
*iter_x = (u - center_x) * depth * constant_x;
*iter_y = (v - center_y) * depth * constant_y;
*iter_z = DepthTraits<T>::toMeters(depth);
}
}
}

} // namespace depth_image_proc

#endif // DEPTH_IMAGE_PROC__DEPTH_CONVERSIONS_HPP_
Loading

0 comments on commit 958052d

Please sign in to comment.