Skip to content

Commit 5b8eebf

Browse files
committed
fix(image_projection_based_fusion): resize sematic segmentation mask as input image size (autowarefoundation#7635)
Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>
1 parent 7843903 commit 5b8eebf

File tree

1 file changed

+4
-0
lines changed
  • perception/image_projection_based_fusion/src/segmentation_pointcloud_fusion

1 file changed

+4
-0
lines changed

perception/image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp

+4
Original file line numberDiff line numberDiff line change
@@ -70,6 +70,10 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage(
7070
camera_info.p.at(4), camera_info.p.at(5), camera_info.p.at(6), camera_info.p.at(7),
7171
camera_info.p.at(8), camera_info.p.at(9), camera_info.p.at(10), camera_info.p.at(11), 0.0, 0.0,
7272
0.0, 1.0;
73+
const int orig_width = camera_info.width;
74+
const int orig_height = camera_info.height;
75+
// resize mask to the same size as the camera image
76+
cv::resize(mask, mask, cv::Size(orig_width, orig_height), 0, 0, cv::INTER_NEAREST);
7377
geometry_msgs::msg::TransformStamped transform_stamped;
7478
// transform pointcloud from frame id to camera optical frame id
7579
{

0 commit comments

Comments
 (0)