Skip to content

Commit f9e419e

Browse files
committed
fix: add rle decompress
Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>
1 parent abcc634 commit f9e419e

File tree

2 files changed

+31
-10
lines changed
  • perception/image_projection_based_fusion
    • include/image_projection_based_fusion/segmentation_pointcloud_fusion
    • src/segmentation_pointcloud_fusion

2 files changed

+31
-10
lines changed

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

+2
Original file line numberDiff line numberDiff line change
@@ -48,6 +48,8 @@ class SegmentPointCloudFusionNode : public FusionNode<PointCloud2, PointCloud2,
4848
explicit SegmentPointCloudFusionNode(const rclcpp::NodeOptions & options);
4949

5050
protected:
51+
52+
cv::Mat rle_decompress(const std::vector<uint8_t> & rle_data, const int rows, const int cols);
5153
void preprocess(PointCloud2 & pointcloud_msg) override;
5254

5355
void postprocess(PointCloud2 & pointcloud_msg) override;

perception/image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp

+29-10
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,32 @@ void SegmentPointCloudFusionNode::postprocess(__attribute__((unused)) PointCloud
4949
{
5050
return;
5151
}
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+
}
5278
void SegmentPointCloudFusionNode::fuseOnSingleImage(
5379
const PointCloud2 & input_pointcloud_msg, __attribute__((unused)) const std::size_t image_id,
5480
[[maybe_unused]] const Image & input_mask, __attribute__((unused)) const CameraInfo & camera_info,
@@ -57,19 +83,12 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage(
5783
if (input_pointcloud_msg.data.empty()) {
5884
return;
5985
}
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());
86+
if (input_mask.height == 0 || input_mask.width == 0) {
6687
return;
6788
}
89+
cv::Mat mask = SegmentPointCloudFusionNode::rle_decompress(
90+
input_mask.data, input_mask.height, input_mask.width);
6891

69-
cv::Mat mask = in_image_ptr->image;
70-
if (mask.cols == 0 || mask.rows == 0) {
71-
return;
72-
}
7392
const int orig_width = camera_info.width;
7493
const int orig_height = camera_info.height;
7594
// resize mask to the same size as the camera image

0 commit comments

Comments
 (0)