Skip to content

Commit f27a0c3

Browse files
badai-nguyenpre-commit-ci[bot]kminoda
committed
fix(image_projection_based_fusion): add run length decoding for segmentation_pointcloud_fusion (autowarefoundation#7909)
* fix: add rle decompress Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * style(pre-commit): autofix * fix: use rld in tensorrt utils Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: rebase error Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: dependency Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: skip publish debug mask Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * Update perception/autoware_image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com> * style(pre-commit): autofix * Revert "fix: skip publish debug mask" This reverts commit 30fa9ae. --------- Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com>
1 parent c3c49e0 commit f27a0c3

File tree

5 files changed

+31
-12
lines changed

5 files changed

+31
-12
lines changed

perception/image_projection_based_fusion/config/segmentation_pointcloud_fusion.param.yaml

+3
Original file line numberDiff line numberDiff line change
@@ -22,3 +22,6 @@
2222

2323
# the maximum distance of pointcloud to be applied filter
2424
filter_distance_threshold: 60.0
25+
26+
# Avoid using debug mask in case of multiple camera semantic segmentation fusion
27+
is_publish_debug_mask: false

perception/image_projection_based_fusion/include/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp

+4
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616
#define IMAGE_PROJECTION_BASED_FUSION__SEGMENTATION_POINTCLOUD_FUSION__NODE_HPP_
1717

1818
#include "image_projection_based_fusion/fusion_node.hpp"
19+
#include <image_transport/image_transport.hpp>
1920

2021
#include <string>
2122
#include <utility>
@@ -42,6 +43,9 @@ class SegmentPointCloudFusionNode : public FusionNode<PointCloud2, PointCloud2,
4243
{"BIKE", false}, {"ROAD", false}, {"SIDEWALK", false}, {"ROAD_PAINT", false},
4344
{"CURBSTONE", false}, {"CROSSWALK", false}, {"VEGETATION", false}, {"SKY", false}};
4445

46+
image_transport::Publisher pub_debug_mask_ptr_;
47+
bool is_publish_debug_mask_;
48+
4549
public:
4650
explicit SegmentPointCloudFusionNode(const rclcpp::NodeOptions & options);
4751

perception/image_projection_based_fusion/package.xml

+1-2
Original file line numberDiff line numberDiff line change
@@ -25,8 +25,7 @@
2525
<depend>lidar_centerpoint</depend>
2626
<depend>message_filters</depend>
2727
<depend>object_recognition_utils</depend>
28-
<depend>pcl_conversions</depend>
29-
<depend>pcl_ros</depend>
28+
<depend>perception_utils</depend>
3029
<depend>rclcpp</depend>
3130
<depend>rclcpp_components</depend>
3231
<depend>sensor_msgs</depend>

perception/image_projection_based_fusion/schema/segmentation_pointcloud_fusion.schema.json

+10-1
Original file line numberDiff line numberDiff line change
@@ -114,9 +114,18 @@
114114
"description": "A maximum distance of pointcloud to apply filter [m].",
115115
"default": 60.0,
116116
"minimum": 0.0
117+
},
118+
"is_publish_debug_mask": {
119+
"type": "boolean",
120+
"description": "If true, debug mask image will be published.",
121+
"default": false
117122
}
118123
},
119-
"required": ["filter_semantic_label_target", "filter_distance_threshold"]
124+
"required": [
125+
"filter_semantic_label_target",
126+
"filter_distance_threshold",
127+
"is_publish_debug_mask"
128+
]
120129
}
121130
},
122131
"properties": {

perception/image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp

+13-9
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,8 @@
1717
#include "image_projection_based_fusion/utils/geometry.hpp"
1818
#include "image_projection_based_fusion/utils/utils.hpp"
1919

20+
#include <perception_utils/run_length_encoder.hpp>
21+
2022
#ifdef ROS_DISTRO_GALACTIC
2123
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
2224
#include <tf2_sensor_msgs/tf2_sensor_msgs.h>
@@ -38,6 +40,8 @@ SegmentPointCloudFusionNode::SegmentPointCloudFusionNode(const rclcpp::NodeOptio
3840
RCLCPP_INFO(
3941
this->get_logger(), "filter_semantic_label_target: %s %d", item.first.c_str(), item.second);
4042
}
43+
is_publish_debug_mask_ = declare_parameter<bool>("is_publish_debug_mask");
44+
pub_debug_mask_ptr_ = image_transport::create_publisher(this, "~/debug/mask");
4145
}
4246

4347
void SegmentPointCloudFusionNode::preprocess(__attribute__((unused)) PointCloud2 & pointcloud_msg)
@@ -57,18 +61,18 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage(
5761
if (input_pointcloud_msg.data.empty()) {
5862
return;
5963
}
60-
cv_bridge::CvImagePtr in_image_ptr;
61-
try {
62-
in_image_ptr = cv_bridge::toCvCopy(
63-
std::make_shared<sensor_msgs::msg::Image>(input_mask), input_mask.encoding);
64-
} catch (const std::exception & e) {
65-
RCLCPP_ERROR(this->get_logger(), "cv_bridge exception:%s", e.what());
64+
if (input_mask.height == 0 || input_mask.width == 0) {
6665
return;
6766
}
67+
std::vector<uint8_t> mask_data(input_mask.data.begin(), input_mask.data.end());
68+
cv::Mat mask = perception_utils::runLengthDecoder(mask_data, input_mask.height, input_mask.width);
6869

69-
cv::Mat mask = in_image_ptr->image;
70-
if (mask.cols == 0 || mask.rows == 0) {
71-
return;
70+
// publish debug mask
71+
if (is_publish_debug_mask_) {
72+
sensor_msgs::msg::Image::SharedPtr debug_mask_msg =
73+
cv_bridge::CvImage(std_msgs::msg::Header(), "mono8", mask).toImageMsg();
74+
debug_mask_msg->header = input_mask.header;
75+
pub_debug_mask_ptr_.publish(debug_mask_msg);
7276
}
7377
const int orig_width = camera_info.width;
7478
const int orig_height = camera_info.height;

0 commit comments

Comments
 (0)