Skip to content
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.

Commit 3d42d8b

Browse files
committedJul 9, 2024··
fix: rle compress
Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>
1 parent 357ceec commit 3d42d8b

File tree

2 files changed

+4
-8
lines changed

2 files changed

+4
-8
lines changed
 

‎perception/tensorrt_yolox/include/tensorrt_yolox/tensorrt_yolox_node.hpp

+1-3
Original file line numberDiff line numberDiff line change
@@ -34,13 +34,13 @@
3434
#else
3535
#include <cv_bridge/cv_bridge.h>
3636
#endif
37-
#include <std_msgs/msg/string.hpp>
3837

3938
#include <chrono>
4039
#include <fstream>
4140
#include <map>
4241
#include <memory>
4342
#include <string>
43+
#include <utility>
4444
#include <vector>
4545

4646
namespace tensorrt_yolox
@@ -83,8 +83,6 @@ class TrtYoloXNode : public rclcpp::Node
8383
int mapRoiLabel2SegLabel(const int32_t roi_label_index);
8484
image_transport::Publisher image_pub_;
8585
image_transport::Publisher mask_pub_;
86-
// rclcpp::Publisher<sensor_msgs::msg::Image>::SharedPtr mask_pub_;
87-
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr str_pub_;
8886

8987
image_transport::Publisher color_mask_pub_;
9088

‎perception/tensorrt_yolox/src/tensorrt_yolox_node.cpp

+3-5
Original file line numberDiff line numberDiff line change
@@ -142,7 +142,6 @@ TrtYoloXNode::TrtYoloXNode(const rclcpp::NodeOptions & node_options)
142142
mask_pub_ = image_transport::create_publisher(this, "~/out/mask");
143143
color_mask_pub_ = image_transport::create_publisher(this, "~/out/color_mask");
144144
image_pub_ = image_transport::create_publisher(this, "~/out/image");
145-
str_pub_ = this->create_publisher<std_msgs::msg::String>("~/out/mask_string", 10);
146145

147146
if (declare_parameter("build_only", false)) {
148147
RCLCPP_INFO(this->get_logger(), "TensorRT engine file is built and exit.");
@@ -236,7 +235,7 @@ void TrtYoloXNode::onImage(const sensor_msgs::msg::Image::ConstSharedPtr msg)
236235
overlapSegmentByRoi(yolox_object, mask, width, height);
237236
}
238237
}
239-
// TODO(badai-nguyen): consider to change to 4bits data transfer
238+
// Compress mask to RLE format
240239
if (trt_yolox_->getMultitaskNum() > 0) {
241240
sensor_msgs::msg::Image::SharedPtr out_mask_msg =
242241
cv_bridge::CvImage(std_msgs::msg::Header(), sensor_msgs::image_encodings::MONO8, mask)
@@ -247,12 +246,11 @@ void TrtYoloXNode::onImage(const sensor_msgs::msg::Image::ConstSharedPtr msg)
247246
int step = sizeof(uint8_t) + sizeof(int);
248247
out_mask_msg->data.resize(static_cast<int>(compressed_data.size()) * step);
249248
for (size_t i = 0; i < compressed_data.size(); ++i) {
250-
std::memcpy(&compressed_data.at(i).first, &out_mask_msg->data[i * step], sizeof(uint8_t));
249+
std::memcpy(&out_mask_msg->data[i * step], &compressed_data.at(i).first, sizeof(uint8_t));
251250
std::memcpy(
252-
&compressed_data.at(i).second, &out_mask_msg->data[i * step + sizeof(uint8_t)],
251+
&out_mask_msg->data[i * step + sizeof(uint8_t)], &compressed_data.at(i).second,
253252
sizeof(int));
254253
}
255-
out_mask_msg->step = step;
256254
mask_pub_.publish(out_mask_msg);
257255
}
258256
image_pub_.publish(in_image_ptr->toImageMsg());

0 commit comments

Comments
 (0)
Please sign in to comment.