@@ -692,6 +692,11 @@ k4a_result_t K4AROSDevice::fillColorPointCloud(const k4a::image& pointcloud_imag
692692
693693 pcd_modifier.resize (point_count);
694694
695+ // Restore actual dimensions as pcd_modifier.resize(n) sets the cloud size to n x 1
696+ point_cloud->height = pointcloud_image.get_height_pixels ();
697+ point_cloud->width = pointcloud_image.get_width_pixels ();
698+ point_cloud->row_step = pointcloud_image.get_width_pixels () * point_cloud->point_step ;
699+
695700 const int16_t * point_cloud_buffer = reinterpret_cast <const int16_t *>(pointcloud_image.get_buffer ());
696701 const uint8_t * color_buffer = color_image.get_buffer ();
697702
@@ -724,8 +729,6 @@ k4a_result_t K4AROSDevice::fillColorPointCloud(const k4a::image& pointcloud_imag
724729
725730k4a_result_t K4AROSDevice::fillPointCloud (const k4a::image& pointcloud_image, sensor_msgs::PointCloud2Ptr& point_cloud)
726731{
727- point_cloud->height = pointcloud_image.get_height_pixels ();
728- point_cloud->width = pointcloud_image.get_width_pixels ();
729732 point_cloud->is_dense = false ;
730733 point_cloud->is_bigendian = false ;
731734
@@ -740,6 +743,11 @@ k4a_result_t K4AROSDevice::fillPointCloud(const k4a::image& pointcloud_image, se
740743
741744 pcd_modifier.resize (point_count);
742745
746+ // Set actual dimensions as pcd_modifier.resize(n) sets the cloud size to n x 1
747+ point_cloud->height = pointcloud_image.get_height_pixels ();
748+ point_cloud->width = pointcloud_image.get_width_pixels ();
749+ point_cloud->row_step = pointcloud_image.get_width_pixels () * point_cloud->point_step ;
750+
743751 const int16_t * point_cloud_buffer = reinterpret_cast <const int16_t *>(pointcloud_image.get_buffer ());
744752
745753 for (size_t i = 0 ; i < point_count; i++, ++iter_x, ++iter_y, ++iter_z)
0 commit comments