From aa251dadf2053a9447cc11265eec43db18a17d50 Mon Sep 17 00:00:00 2001 From: "philipp.polterauer" <45892981+PhilippPolterauer@users.noreply.github.com> Date: Wed, 21 Feb 2024 01:18:01 +0100 Subject: [PATCH] add invalid_depth param (#943) Add option to set all invalid depth pixels to a specified value, typically the maximum range. * Updates convertDepth parameter name and optimizes use of the parameter. * Updates PointCloudXYZ, PointCloudXYZI, and PointCloudXYZRGB with new invalid_depth parameter --- .gitignore | 2 +- depth_image_proc/doc/components.rst | 6 ++++ .../include/depth_image_proc/conversions.hpp | 29 ++++++++++++------- .../depth_image_proc/point_cloud_xyz.hpp | 3 ++ .../depth_image_proc/point_cloud_xyzi.hpp | 3 ++ .../depth_image_proc/point_cloud_xyzrgb.hpp | 3 ++ depth_image_proc/src/conversions.cpp | 6 ++-- depth_image_proc/src/point_cloud_xyz.cpp | 9 ++++-- depth_image_proc/src/point_cloud_xyzi.cpp | 7 +++-- depth_image_proc/src/point_cloud_xyzrgb.cpp | 7 +++-- 10 files changed, 53 insertions(+), 22 deletions(-) diff --git a/.gitignore b/.gitignore index 9d93f2973..189be055b 100644 --- a/.gitignore +++ b/.gitignore @@ -1,3 +1,3 @@ *pyc -.vscode/settings.json +.vscode/ */doc/generated diff --git a/depth_image_proc/doc/components.rst b/depth_image_proc/doc/components.rst index c0a783c60..19d870a73 100644 --- a/depth_image_proc/doc/components.rst +++ b/depth_image_proc/doc/components.rst @@ -116,6 +116,8 @@ Parameters for the depth topic subscriber. * **queue_size** (int, default: 5): Size of message queue for synchronizing subscribed topics. + * **invalid_depth** (double, default: 0.0): Value used for replacing invalid depth + values (if 0.0 the parameter has no effect). depth_image_proc::PointCloudXyzRadialNode ----------------------------------------- @@ -165,6 +167,8 @@ Parameters the intensity image subscriber. * **queue_size** (int, default: 5): Size of message queue for synchronizing subscribed topics. + * **invalid_depth** (double, default: 0.0): Value used for replacing invalid depth + values (if 0.0 the parameter has no effect). depth_image_proc::PointCloudXyziRadialNode ------------------------------------------ @@ -235,6 +239,8 @@ Parameters * **exact_sync** (bool, default: False): Whether to use exact synchronizer. * **queue_size** (int, default: 5): Size of message queue for synchronizing subscribed topics. + * **invalid_depth** (double, default: 0.0): Value used for replacing invalid depth + values (if 0.0 the parameter has no effect). depth_image_proc::PointCloudXyzrgbRadialNode -------------------------------------------- diff --git a/depth_image_proc/include/depth_image_proc/conversions.hpp b/depth_image_proc/include/depth_image_proc/conversions.hpp index 11496320f..8af177bd0 100644 --- a/depth_image_proc/include/depth_image_proc/conversions.hpp +++ b/depth_image_proc/include/depth_image_proc/conversions.hpp @@ -51,9 +51,9 @@ namespace depth_image_proc template void convertDepth( const sensor_msgs::msg::Image::ConstSharedPtr & depth_msg, - sensor_msgs::msg::PointCloud2::SharedPtr & cloud_msg, + const sensor_msgs::msg::PointCloud2::SharedPtr & cloud_msg, const image_geometry::PinholeCameraModel & model, - double range_max = 0.0) + double invalid_depth = 0.0) { // Use correct principal point from calibration float center_x = model.cx(); @@ -65,19 +65,26 @@ void convertDepth( float constant_y = unit_scaling / model.fy(); float bad_point = std::numeric_limits::quiet_NaN(); + // ensure that the computation only happens in case we have a default depth + T invalid_depth_cvt = T(0); + bool use_invalid_depth = invalid_depth != 0.0; + if (use_invalid_depth) { + invalid_depth_cvt = DepthTraits::fromMeters(invalid_depth); + } sensor_msgs::PointCloud2Iterator iter_x(*cloud_msg, "x"); sensor_msgs::PointCloud2Iterator iter_y(*cloud_msg, "y"); sensor_msgs::PointCloud2Iterator iter_z(*cloud_msg, "z"); + const T * depth_row = reinterpret_cast(&depth_msg->data[0]); - int row_step = depth_msg->step / sizeof(T); - for (int v = 0; v < static_cast(cloud_msg->height); ++v, depth_row += row_step) { - for (int u = 0; u < static_cast(cloud_msg->width); ++u, ++iter_x, ++iter_y, ++iter_z) { + uint32_t row_step = depth_msg->step / sizeof(T); + for (uint32_t v = 0; v < cloud_msg->height; ++v, depth_row += row_step) { + for (uint32_t u = 0; u < cloud_msg->width; ++u, ++iter_x, ++iter_y, ++iter_z) { T depth = depth_row[u]; // Missing points denoted by NaNs if (!DepthTraits::valid(depth)) { - if (range_max != 0.0) { - depth = DepthTraits::fromMeters(range_max); + if (use_invalid_depth) { + depth = invalid_depth_cvt; } else { *iter_x = *iter_y = *iter_z = bad_point; continue; @@ -96,8 +103,8 @@ void convertDepth( template void convertDepthRadial( const sensor_msgs::msg::Image::ConstSharedPtr & depth_msg, - sensor_msgs::msg::PointCloud2::SharedPtr & cloud_msg, - cv::Mat & transform) + const sensor_msgs::msg::PointCloud2::SharedPtr & cloud_msg, + const cv::Mat & transform) { // Combine unit conversion (if necessary) with scaling by focal length for computing (X,Y) float bad_point = std::numeric_limits::quiet_NaN(); @@ -129,7 +136,7 @@ void convertDepthRadial( template void convertIntensity( const sensor_msgs::msg::Image::ConstSharedPtr & intensity_msg, - sensor_msgs::msg::PointCloud2::SharedPtr & cloud_msg) + const sensor_msgs::msg::PointCloud2::SharedPtr & cloud_msg) { sensor_msgs::PointCloud2Iterator iter_i(*cloud_msg, "intensity"); const T * inten_row = reinterpret_cast(&intensity_msg->data[0]); @@ -145,7 +152,7 @@ void convertIntensity( // Handles RGB8, BGR8, and MONO8 void convertRgb( const sensor_msgs::msg::Image::ConstSharedPtr & rgb_msg, - sensor_msgs::msg::PointCloud2::SharedPtr & cloud_msg, + sensor_msgs::msg::PointCloud2::SharedPtr cloud_msg, int red_offset, int green_offset, int blue_offset, int color_step); cv::Mat initMatrix(cv::Mat cameraMatrix, cv::Mat distCoeffs, int width, int height, bool radial); diff --git a/depth_image_proc/include/depth_image_proc/point_cloud_xyz.hpp b/depth_image_proc/include/depth_image_proc/point_cloud_xyz.hpp index c5fc4bfd2..6818e8cd8 100644 --- a/depth_image_proc/include/depth_image_proc/point_cloud_xyz.hpp +++ b/depth_image_proc/include/depth_image_proc/point_cloud_xyz.hpp @@ -67,6 +67,9 @@ class PointCloudXyzNode : public rclcpp::Node image_transport::CameraSubscriber sub_depth_; int queue_size_; + // Parameters + double invalid_depth_; + // Publications std::mutex connect_mutex_; rclcpp::Publisher::SharedPtr pub_point_cloud_; diff --git a/depth_image_proc/include/depth_image_proc/point_cloud_xyzi.hpp b/depth_image_proc/include/depth_image_proc/point_cloud_xyzi.hpp index 1a9e754a2..cb079cc1d 100644 --- a/depth_image_proc/include/depth_image_proc/point_cloud_xyzi.hpp +++ b/depth_image_proc/include/depth_image_proc/point_cloud_xyzi.hpp @@ -71,6 +71,9 @@ class PointCloudXyziNode : public rclcpp::Node using Synchronizer = message_filters::Synchronizer; std::shared_ptr sync_; + // parameters + float invalid_depth_; + // Publications std::mutex connect_mutex_; rclcpp::Publisher::SharedPtr pub_point_cloud_; diff --git a/depth_image_proc/include/depth_image_proc/point_cloud_xyzrgb.hpp b/depth_image_proc/include/depth_image_proc/point_cloud_xyzrgb.hpp index f2b99c165..47c7e0cba 100644 --- a/depth_image_proc/include/depth_image_proc/point_cloud_xyzrgb.hpp +++ b/depth_image_proc/include/depth_image_proc/point_cloud_xyzrgb.hpp @@ -75,6 +75,9 @@ class PointCloudXyzrgbNode : public rclcpp::Node std::shared_ptr sync_; std::shared_ptr exact_sync_; + // parameters + float invalid_depth_; + // Publications std::mutex connect_mutex_; rclcpp::Publisher::SharedPtr pub_point_cloud_; diff --git a/depth_image_proc/src/conversions.cpp b/depth_image_proc/src/conversions.cpp index ba462323f..697734414 100644 --- a/depth_image_proc/src/conversions.cpp +++ b/depth_image_proc/src/conversions.cpp @@ -79,7 +79,7 @@ cv::Mat initMatrix( void convertRgb( const sensor_msgs::msg::Image::ConstSharedPtr & rgb_msg, - sensor_msgs::msg::PointCloud2::SharedPtr & cloud_msg, + const sensor_msgs::msg::PointCloud2::SharedPtr & cloud_msg, int red_offset, int green_offset, int blue_offset, int color_step) { sensor_msgs::PointCloud2Iterator iter_r(*cloud_msg, "r"); @@ -101,8 +101,8 @@ void convertRgb( // force template instantiation template void convertDepth( const sensor_msgs::msg::Image::ConstSharedPtr & depth_msg, - sensor_msgs::msg::PointCloud2::SharedPtr & cloud_msg, + const sensor_msgs::msg::PointCloud2::SharedPtr & cloud_msg, const image_geometry::PinholeCameraModel & model, - double range_max); + double invalid_depth); } // namespace depth_image_proc diff --git a/depth_image_proc/src/point_cloud_xyz.cpp b/depth_image_proc/src/point_cloud_xyz.cpp index 0175d929a..227a4100b 100644 --- a/depth_image_proc/src/point_cloud_xyz.cpp +++ b/depth_image_proc/src/point_cloud_xyz.cpp @@ -58,6 +58,9 @@ PointCloudXyzNode::PointCloudXyzNode(const rclcpp::NodeOptions & options) // Read parameters queue_size_ = this->declare_parameter("queue_size", 5); + // values used for invalid points for pcd conversion + invalid_depth_ = this->declare_parameter("invalid_depth", 0.0); + // Create publisher with connect callback rclcpp::PublisherOptions pub_options; pub_options.event_callbacks.matched_callback = @@ -94,7 +97,7 @@ void PointCloudXyzNode::depthCb( const Image::ConstSharedPtr & depth_msg, const CameraInfo::ConstSharedPtr & info_msg) { - auto cloud_msg = std::make_shared(); + const PointCloud2::SharedPtr cloud_msg = std::make_shared(); cloud_msg->header = depth_msg->header; cloud_msg->height = depth_msg->height; cloud_msg->width = depth_msg->width; @@ -109,9 +112,9 @@ void PointCloudXyzNode::depthCb( // Convert Depth Image to Pointcloud if (depth_msg->encoding == enc::TYPE_16UC1 || depth_msg->encoding == enc::MONO16) { - convertDepth(depth_msg, cloud_msg, model_); + convertDepth(depth_msg, cloud_msg, model_, invalid_depth_); } else if (depth_msg->encoding == enc::TYPE_32FC1) { - convertDepth(depth_msg, cloud_msg, model_); + convertDepth(depth_msg, cloud_msg, model_, invalid_depth_); } else { RCLCPP_ERROR( get_logger(), "Depth image has unsupported encoding [%s]", depth_msg->encoding.c_str()); diff --git a/depth_image_proc/src/point_cloud_xyzi.cpp b/depth_image_proc/src/point_cloud_xyzi.cpp index 9b373d86d..0abc0ff8c 100644 --- a/depth_image_proc/src/point_cloud_xyzi.cpp +++ b/depth_image_proc/src/point_cloud_xyzi.cpp @@ -58,6 +58,9 @@ PointCloudXyziNode::PointCloudXyziNode(const rclcpp::NodeOptions & options) this->declare_parameter("image_transport", "raw"); this->declare_parameter("depth_image_transport", "raw"); + // value used for invalid points for pcd conversion + invalid_depth_ = this->declare_parameter("invalid_depth", 0.0); + // Read parameters int queue_size = this->declare_parameter("queue_size", 5); @@ -202,9 +205,9 @@ void PointCloudXyziNode::imageCb( // Convert Depth Image to Pointcloud if (depth_msg->encoding == enc::TYPE_16UC1) { - convertDepth(depth_msg, cloud_msg, model_); + convertDepth(depth_msg, cloud_msg, model_, invalid_depth_); } else if (depth_msg->encoding == enc::TYPE_32FC1) { - convertDepth(depth_msg, cloud_msg, model_); + convertDepth(depth_msg, cloud_msg, model_, invalid_depth_); } else { RCLCPP_ERROR( get_logger(), "Depth image has unsupported encoding [%s]", depth_msg->encoding.c_str()); diff --git a/depth_image_proc/src/point_cloud_xyzrgb.cpp b/depth_image_proc/src/point_cloud_xyzrgb.cpp index 3347b11e1..5ef736d96 100644 --- a/depth_image_proc/src/point_cloud_xyzrgb.cpp +++ b/depth_image_proc/src/point_cloud_xyzrgb.cpp @@ -55,6 +55,9 @@ PointCloudXyzrgbNode::PointCloudXyzrgbNode(const rclcpp::NodeOptions & options) this->declare_parameter("image_transport", "raw"); this->declare_parameter("depth_image_transport", "raw"); + // value used for invalid points for pcd conversion + invalid_depth_ = this->declare_parameter("invalid_depth", 0.0); + // Read parameters int queue_size = this->declare_parameter("queue_size", 5); bool use_exact_sync = this->declare_parameter("exact_sync", false); @@ -256,9 +259,9 @@ void PointCloudXyzrgbNode::imageCb( // Convert Depth Image to Pointcloud if (depth_msg->encoding == sensor_msgs::image_encodings::TYPE_16UC1) { - convertDepth(depth_msg, cloud_msg, model_); + convertDepth(depth_msg, cloud_msg, model_, invalid_depth_); } else if (depth_msg->encoding == sensor_msgs::image_encodings::TYPE_32FC1) { - convertDepth(depth_msg, cloud_msg, model_); + convertDepth(depth_msg, cloud_msg, model_, invalid_depth_); } else { RCLCPP_ERROR( get_logger(), "Depth image has unsupported encoding [%s]", depth_msg->encoding.c_str());