Skip to content

Commit a1b1ec7

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

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
@@ -65,6 +65,10 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage(
6565
if (mask.cols == 0 || mask.rows == 0) {
6666
return;
6767
}
68+
const int orig_width = camera_info.width;
69+
const int orig_height = camera_info.height;
70+
// resize mask to the same size as the camera image
71+
cv::resize(mask, mask, cv::Size(orig_width, orig_height), 0, 0, cv::INTER_NEAREST);
6872
image_geometry::PinholeCameraModel pinhole_camera_model;
6973
pinhole_camera_model.fromCameraInfo(camera_info);
7074

0 commit comments

Comments
 (0)