diff --git a/pcl_ros/tools/convert_pointcloud_to_image.cpp b/pcl_ros/tools/convert_pointcloud_to_image.cpp index 678bf0e4..a7a4e1c1 100644 --- a/pcl_ros/tools/convert_pointcloud_to_image.cpp +++ b/pcl_ros/tools/convert_pointcloud_to_image.cpp @@ -64,6 +64,7 @@ public: try { pcl::toROSMsg (*cloud, image_); //convert the cloud + image_.header = cloud->header; image_pub_.publish (image_); //publish our cloud image } catch (std::runtime_error &e)