@@ -103,7 +103,6 @@ TrtYoloXNode::TrtYoloXNode(const rclcpp::NodeOptions & node_options)
103
103
mask_pub_ = image_transport::create_publisher (this , " ~/out/mask" );
104
104
color_mask_pub_ = image_transport::create_publisher (this , " ~/out/color_mask" );
105
105
image_pub_ = image_transport::create_publisher (this , " ~/out/image" );
106
- str_pub_ = this ->create_publisher <std_msgs::msg::String>(" ~/out/mask_string" , 10 );
107
106
108
107
if (declare_parameter (" build_only" , false )) {
109
108
RCLCPP_INFO (this ->get_logger (), " TensorRT engine file is built and exit." );
@@ -197,7 +196,7 @@ void TrtYoloXNode::onImage(const sensor_msgs::msg::Image::ConstSharedPtr msg)
197
196
overlapSegmentByRoi (yolox_object, mask, width, height);
198
197
}
199
198
}
200
- // TODO(badai-nguyen): consider to change to 4bits data transfer
199
+ // Compress mask to RLE format
201
200
if (trt_yolox_->getMultitaskNum () > 0 ) {
202
201
sensor_msgs::msg::Image::SharedPtr out_mask_msg =
203
202
cv_bridge::CvImage (std_msgs::msg::Header (), sensor_msgs::image_encodings::MONO8, mask)
@@ -208,12 +207,11 @@ void TrtYoloXNode::onImage(const sensor_msgs::msg::Image::ConstSharedPtr msg)
208
207
int step = sizeof (uint8_t ) + sizeof (int );
209
208
out_mask_msg->data .resize (static_cast <int >(compressed_data.size ()) * step);
210
209
for (size_t i = 0 ; i < compressed_data.size (); ++i) {
211
- std::memcpy (&compressed_data. at (i). first , & out_mask_msg->data [i * step], sizeof (uint8_t ));
210
+ std::memcpy (&out_mask_msg->data [i * step], &compressed_data. at (i). first , sizeof (uint8_t ));
212
211
std::memcpy (
213
- &compressed_data. at (i). second , & out_mask_msg->data [i * step + sizeof (uint8_t )],
212
+ &out_mask_msg->data [i * step + sizeof (uint8_t )], &compressed_data. at (i). second ,
214
213
sizeof (int ));
215
214
}
216
- out_mask_msg->step = step;
217
215
mask_pub_.publish (out_mask_msg);
218
216
}
219
217
image_pub_.publish (in_image_ptr->toImageMsg ());
0 commit comments