17
17
#include " image_projection_based_fusion/utils/geometry.hpp"
18
18
#include " image_projection_based_fusion/utils/utils.hpp"
19
19
20
+ #include < perception_utils/run_length_encoder.hpp>
21
+
20
22
#ifdef ROS_DISTRO_GALACTIC
21
23
#include < tf2_geometry_msgs/tf2_geometry_msgs.h>
22
24
#include < tf2_sensor_msgs/tf2_sensor_msgs.h>
@@ -38,6 +40,8 @@ SegmentPointCloudFusionNode::SegmentPointCloudFusionNode(const rclcpp::NodeOptio
38
40
RCLCPP_INFO (
39
41
this ->get_logger (), " filter_semantic_label_target: %s %d" , item.first .c_str (), item.second );
40
42
}
43
+ is_publish_debug_mask_ = declare_parameter<bool >(" is_publish_debug_mask" );
44
+ pub_debug_mask_ptr_ = image_transport::create_publisher (this , " ~/debug/mask" );
41
45
}
42
46
43
47
void SegmentPointCloudFusionNode::preprocess (__attribute__((unused)) PointCloud2 & pointcloud_msg)
@@ -57,18 +61,18 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage(
57
61
if (input_pointcloud_msg.data .empty ()) {
58
62
return ;
59
63
}
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 ) {
66
65
return ;
67
66
}
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 );
68
69
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);
72
76
}
73
77
const int orig_width = camera_info.width ;
74
78
const int orig_height = camera_info.height ;
0 commit comments