From 281b7fc6550d4467dd8e8d6279aa0556379f9d3d Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Mon, 3 Jun 2024 13:20:02 +0900 Subject: [PATCH] chore: refactor Signed-off-by: badai-nguyen --- .../src/segmentation_pointcloud_fusion/node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp b/perception/image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp index 5b0399e728104..0096b91f7a3b6 100644 --- a/perception/image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp @@ -96,6 +96,8 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage( output_cloud.header = input_pointcloud_msg.header; output_cloud.height = input_pointcloud_msg.height; output_cloud.point_step = input_pointcloud_msg.point_step; + output_cloud.is_bigendian = input_pointcloud_msg.is_bigendian; + output_cloud.is_dense = input_pointcloud_msg.is_dense; for (size_t global_offset = 0; global_offset < transformed_cloud.data.size(); global_offset += point_step) { float transformed_x = @@ -142,8 +144,6 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage( output_cloud.data.resize(output_pointcloud_size); output_cloud.row_step = output_pointcloud_size / output_cloud.height; - output_cloud.is_bigendian = input_pointcloud_msg.is_bigendian; - output_cloud.is_dense = input_pointcloud_msg.is_dense; output_cloud.width = output_pointcloud_size / output_cloud.point_step / output_cloud.height; }