Skip to content

Commit cc20fcd

Browse files
committed
fix: use rld in tensorrt utils
Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>
1 parent b6a1b00 commit cc20fcd

File tree

5 files changed

+30
-30
lines changed

5 files changed

+30
-30
lines changed

perception/image_projection_based_fusion/config/segmentation_pointcloud_fusion.param.yaml

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

2323
# the maximum distance of pointcloud to be applied filter
2424
filter_distance_threshold: 60.0
25+
is_publish_debug_mask: false

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

+3-1
Original file line numberDiff line numberDiff line change
@@ -44,11 +44,13 @@ class SegmentPointCloudFusionNode : public FusionNode<PointCloud2, PointCloud2,
4444
{"BIKE", false}, {"ROAD", false}, {"SIDEWALK", false}, {"ROAD_PAINT", false},
4545
{"CURBSTONE", false}, {"CROSSWALK", false}, {"VEGETATION", false}, {"SKY", false}};
4646

47+
image_transport::Publisher pub_debug_mask_ptr_;
48+
bool is_publish_debug_mask_;
49+
4750
public:
4851
explicit SegmentPointCloudFusionNode(const rclcpp::NodeOptions & options);
4952

5053
protected:
51-
cv::Mat rle_decompress(const std::vector<uint8_t> & rle_data, const int rows, const int cols);
5254
void preprocess(PointCloud2 & pointcloud_msg) override;
5355

5456
void postprocess(PointCloud2 & pointcloud_msg) override;

perception/image_projection_based_fusion/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818

1919
<depend>autoware_perception_msgs</depend>
2020
<depend>autoware_point_types</depend>
21+
<depend>autoware_tensorrt_yolox</depend>
2122
<depend>autoware_universe_utils</depend>
2223
<depend>cv_bridge</depend>
2324
<depend>euclidean_cluster</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

+15-28
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,8 @@ SegmentPointCloudFusionNode::SegmentPointCloudFusionNode(const rclcpp::NodeOptio
3838
RCLCPP_INFO(
3939
this->get_logger(), "filter_semantic_label_target: %s %d", item.first.c_str(), item.second);
4040
}
41+
is_publish_debug_mask_ = declare_parameter<bool>("is_publish_debug_mask");
42+
pub_debug_mask_ptr_ = image_transport::create_publisher(this, "debug/mask");
4143
}
4244

4345
void SegmentPointCloudFusionNode::preprocess(__attribute__((unused)) PointCloud2 & pointcloud_msg)
@@ -49,32 +51,6 @@ void SegmentPointCloudFusionNode::postprocess(__attribute__((unused)) PointCloud
4951
{
5052
return;
5153
}
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-
}
7854
void SegmentPointCloudFusionNode::fuseOnSingleImage(
7955
const PointCloud2 & input_pointcloud_msg, __attribute__((unused)) const std::size_t image_id,
8056
[[maybe_unused]] const Image & input_mask, __attribute__((unused)) const CameraInfo & camera_info,
@@ -86,9 +62,20 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage(
8662
if (input_mask.height == 0 || input_mask.width == 0) {
8763
return;
8864
}
89-
cv::Mat mask = SegmentPointCloudFusionNode::rle_decompress(
65+
cv::Mat mask = autoware::tensorrt_yolox::runLengthDecoder(
9066
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;
9279
const int orig_width = camera_info.width;
9380
const int orig_height = camera_info.height;
9481
// resize mask to the same size as the camera image

0 commit comments

Comments
 (0)