@@ -680,6 +680,11 @@ k4a_result_t K4AROSDevice::fillColorPointCloud(const k4a::image& pointcloud_imag
680
680
sensor_msgs::PointCloud2Modifier pcd_modifier (*point_cloud);
681
681
pcd_modifier.setPointCloud2FieldsByString (2 , " xyz" , " rgb" );
682
682
683
+ point_cloud->height = pointcloud_image.get_height_pixels ();
684
+ point_cloud->width = pointcloud_image.get_width_pixels ();
685
+ point_cloud->row_step = pointcloud_image.get_width_pixels () * point_cloud->point_step ;
686
+ point_cloud->data .resize (point_cloud->height * point_cloud->width * point_cloud->point_step );
687
+
683
688
sensor_msgs::PointCloud2Iterator<float > iter_x (*point_cloud, " x" );
684
689
sensor_msgs::PointCloud2Iterator<float > iter_y (*point_cloud, " y" );
685
690
sensor_msgs::PointCloud2Iterator<float > iter_z (*point_cloud, " z" );
@@ -688,13 +693,6 @@ k4a_result_t K4AROSDevice::fillColorPointCloud(const k4a::image& pointcloud_imag
688
693
sensor_msgs::PointCloud2Iterator<uint8_t > iter_g (*point_cloud, " g" );
689
694
sensor_msgs::PointCloud2Iterator<uint8_t > iter_b (*point_cloud, " b" );
690
695
691
- pcd_modifier.resize (point_count);
692
-
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
-
698
696
const int16_t * point_cloud_buffer = reinterpret_cast <const int16_t *>(pointcloud_image.get_buffer ());
699
697
const uint8_t * color_buffer = color_image.get_buffer ();
700
698
@@ -735,16 +733,14 @@ k4a_result_t K4AROSDevice::fillPointCloud(const k4a::image& pointcloud_image, se
735
733
sensor_msgs::PointCloud2Modifier pcd_modifier (*point_cloud);
736
734
pcd_modifier.setPointCloud2FieldsByString (1 , " xyz" );
737
735
738
- sensor_msgs::PointCloud2Iterator<float > iter_x (*point_cloud, " x" );
739
- sensor_msgs::PointCloud2Iterator<float > iter_y (*point_cloud, " y" );
740
- sensor_msgs::PointCloud2Iterator<float > iter_z (*point_cloud, " z" );
741
-
742
- pcd_modifier.resize (point_count);
743
-
744
- // Set actual dimensions as pcd_modifier.resize(n) sets the cloud size to n x 1
745
736
point_cloud->height = pointcloud_image.get_height_pixels ();
746
737
point_cloud->width = pointcloud_image.get_width_pixels ();
747
738
point_cloud->row_step = pointcloud_image.get_width_pixels () * point_cloud->point_step ;
739
+ point_cloud->data .resize (point_cloud->height * point_cloud->width * point_cloud->point_step );
740
+
741
+ sensor_msgs::PointCloud2Iterator<float > iter_x (*point_cloud, " x" );
742
+ sensor_msgs::PointCloud2Iterator<float > iter_y (*point_cloud, " y" );
743
+ sensor_msgs::PointCloud2Iterator<float > iter_z (*point_cloud, " z" );
748
744
749
745
const int16_t * point_cloud_buffer = reinterpret_cast <const int16_t *>(pointcloud_image.get_buffer ());
750
746
0 commit comments