@@ -38,6 +38,8 @@ SegmentPointCloudFusionNode::SegmentPointCloudFusionNode(const rclcpp::NodeOptio
38
38
RCLCPP_INFO (
39
39
this ->get_logger (), " filter_semantic_label_target: %s %d" , item.first .c_str (), item.second );
40
40
}
41
+ is_publish_debug_mask_ = declare_parameter<bool >(" is_publish_debug_mask" );
42
+ pub_debug_mask_ptr_ = image_transport::create_publisher (this , " debug/mask" );
41
43
}
42
44
43
45
void SegmentPointCloudFusionNode::preprocess (__attribute__((unused)) PointCloud2 & pointcloud_msg)
@@ -49,32 +51,6 @@ void SegmentPointCloudFusionNode::postprocess(__attribute__((unused)) PointCloud
49
51
{
50
52
return ;
51
53
}
52
- cv::Mat SegmentPointCloudFusionNode::rle_decompress (
53
- const std::vector<uint8_t > & rle_data, const int rows, const int cols)
54
- {
55
- cv::Mat mask (rows, cols, CV_8UC1, cv::Scalar (0 ));
56
- int idx = 0 ;
57
- int step = sizeof (uint8_t ) + sizeof (int );
58
- int nb_pixels = 0 ;
59
- for (size_t i = 0 ; i < rle_data.size (); i += step) {
60
- uint8_t value;
61
- int length;
62
- std::memcpy (&value, &rle_data[i], sizeof (uint8_t ));
63
- std::memcpy (&length, &rle_data[i + sizeof (uint8_t )], sizeof (int ));
64
- nb_pixels += length;
65
- for (int j = 0 ; j < length; ++j) {
66
- int row_idx = static_cast <int >(idx / cols);
67
- int col_idx = static_cast <int >(idx % cols);
68
- mask.at <uint8_t >(row_idx, col_idx) = value;
69
- idx++;
70
- if (idx > rows * cols) {
71
- RCLCPP_ERROR (this ->get_logger (), " RLE decompression error: idx out of bound" );
72
- break ;
73
- }
74
- }
75
- }
76
- return mask;
77
- }
78
54
void SegmentPointCloudFusionNode::fuseOnSingleImage (
79
55
const PointCloud2 & input_pointcloud_msg, __attribute__((unused)) const std::size_t image_id,
80
56
[[maybe_unused]] const Image & input_mask, __attribute__((unused)) const CameraInfo & camera_info,
@@ -86,9 +62,20 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage(
86
62
if (input_mask.height == 0 || input_mask.width == 0 ) {
87
63
return ;
88
64
}
89
- cv::Mat mask = SegmentPointCloudFusionNode::rle_decompress (
65
+ cv::Mat mask = autoware::tensorrt_yolox::runLengthDecoder (
90
66
input_mask.data , input_mask.height , input_mask.width );
91
-
67
+ // publish debug mask
68
+ if (is_publish_debug_mask_) {
69
+ sensor_msgs::msg::Image::SharedPtr debug_mask_msg =
70
+ cv_bridge::CvImage (std_msgs::msg::Header (), " mono8" , mask).toImageMsg ();
71
+ debug_mask_msg->header = input_mask.header ;
72
+ pub_debug_mask_ptr_.publish (debug_mask_msg);
73
+ }
74
+ Eigen::Matrix4d projection;
75
+ projection << camera_info.p .at (0 ), camera_info.p .at (1 ), camera_info.p .at (2 ), camera_info.p .at (3 ),
76
+ camera_info.p .at (4 ), camera_info.p .at (5 ), camera_info.p .at (6 ), camera_info.p .at (7 ),
77
+ camera_info.p .at (8 ), camera_info.p .at (9 ), camera_info.p .at (10 ), camera_info.p .at (11 ), 0.0 , 0.0 ,
78
+ 0.0 , 1.0 ;
92
79
const int orig_width = camera_info.width ;
93
80
const int orig_height = camera_info.height ;
94
81
// resize mask to the same size as the camera image
0 commit comments