@@ -666,8 +666,6 @@ k4a_result_t K4AROSDevice::getPointCloud(const k4a::capture& capture, sensor_msg
666666k4a_result_t K4AROSDevice::fillColorPointCloud (const k4a::image& pointcloud_image, const k4a::image& color_image,
667667 sensor_msgs::PointCloud2Ptr& point_cloud)
668668{
669- point_cloud->height = pointcloud_image.get_height_pixels ();
670- point_cloud->width = pointcloud_image.get_width_pixels ();
671669 point_cloud->is_dense = false ;
672670 point_cloud->is_bigendian = false ;
673671
@@ -692,6 +690,11 @@ k4a_result_t K4AROSDevice::fillColorPointCloud(const k4a::image& pointcloud_imag
692690
693691 pcd_modifier.resize (point_count);
694692
693+ // Restore actual dimensions as pcd_modifier.resize(n) sets the cloud size to n x 1
694+ point_cloud->height = pointcloud_image.get_height_pixels ();
695+ point_cloud->width = pointcloud_image.get_width_pixels ();
696+ point_cloud->row_step = pointcloud_image.get_width_pixels () * point_cloud->point_step ;
697+
695698 const int16_t * point_cloud_buffer = reinterpret_cast <const int16_t *>(pointcloud_image.get_buffer ());
696699 const uint8_t * color_buffer = color_image.get_buffer ();
697700
@@ -724,8 +727,6 @@ k4a_result_t K4AROSDevice::fillColorPointCloud(const k4a::image& pointcloud_imag
724727
725728k4a_result_t K4AROSDevice::fillPointCloud (const k4a::image& pointcloud_image, sensor_msgs::PointCloud2Ptr& point_cloud)
726729{
727- point_cloud->height = pointcloud_image.get_height_pixels ();
728- point_cloud->width = pointcloud_image.get_width_pixels ();
729730 point_cloud->is_dense = false ;
730731 point_cloud->is_bigendian = false ;
731732
@@ -740,6 +741,11 @@ k4a_result_t K4AROSDevice::fillPointCloud(const k4a::image& pointcloud_image, se
740741
741742 pcd_modifier.resize (point_count);
742743
744+ // Set actual dimensions as pcd_modifier.resize(n) sets the cloud size to n x 1
745+ point_cloud->height = pointcloud_image.get_height_pixels ();
746+ point_cloud->width = pointcloud_image.get_width_pixels ();
747+ point_cloud->row_step = pointcloud_image.get_width_pixels () * point_cloud->point_step ;
748+
743749 const int16_t * point_cloud_buffer = reinterpret_cast <const int16_t *>(pointcloud_image.get_buffer ());
744750
745751 for (size_t i = 0 ; i < point_count; i++, ++iter_x, ++iter_y, ++iter_z)
0 commit comments