From 360b87131bb9767beb3b8e82f7897234c695a23a Mon Sep 17 00:00:00 2001 From: Martin Guenther Date: Fri, 22 Apr 2016 14:46:11 +0200 Subject: [PATCH] Fix handling of unorganized input in convert_pointcloud_to_image Without this patch, convert_pointcloud_to_image doesn't correctly recognize unorganized point clouds and outputs garbage that crashes image_view. --- pcl_ros/tools/convert_pointcloud_to_image.cpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/pcl_ros/tools/convert_pointcloud_to_image.cpp b/pcl_ros/tools/convert_pointcloud_to_image.cpp index 0fdd5e87..678bf0e4 100644 --- a/pcl_ros/tools/convert_pointcloud_to_image.cpp +++ b/pcl_ros/tools/convert_pointcloud_to_image.cpp @@ -56,18 +56,21 @@ public: void cloud_cb (const sensor_msgs::PointCloud2ConstPtr& cloud) { - if ((cloud->width * cloud->height) == 0) - return; //return if the cloud is not dense! + if (cloud->height <= 1) + { + ROS_ERROR("Input point cloud is not organized, ignoring!"); + return; + } try { pcl::toROSMsg (*cloud, image_); //convert the cloud + image_pub_.publish (image_); //publish our cloud image } catch (std::runtime_error &e) { ROS_ERROR_STREAM("Error in converting cloud to image message: " << e.what()); } - image_pub_.publish (image_); //publish our cloud image } PointCloudToImage () : cloud_topic_("input"),image_topic_("output") {