@@ -142,7 +142,6 @@ TrtYoloXNode::TrtYoloXNode(const rclcpp::NodeOptions & node_options)
142
142
mask_pub_ = image_transport::create_publisher (this , " ~/out/mask" );
143
143
color_mask_pub_ = image_transport::create_publisher (this , " ~/out/color_mask" );
144
144
image_pub_ = image_transport::create_publisher (this , " ~/out/image" );
145
- str_pub_ = this ->create_publisher <std_msgs::msg::String>(" ~/out/mask_string" , 10 );
146
145
147
146
if (declare_parameter (" build_only" , false )) {
148
147
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)
236
235
overlapSegmentByRoi (yolox_object, mask, width, height);
237
236
}
238
237
}
239
- // TODO(badai-nguyen): consider to change to 4bits data transfer
238
+ // Compress mask to RLE format
240
239
if (trt_yolox_->getMultitaskNum () > 0 ) {
241
240
sensor_msgs::msg::Image::SharedPtr out_mask_msg =
242
241
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)
247
246
int step = sizeof (uint8_t ) + sizeof (int );
248
247
out_mask_msg->data .resize (static_cast <int >(compressed_data.size ()) * step);
249
248
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 ));
251
250
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 ,
253
252
sizeof (int ));
254
253
}
255
- out_mask_msg->step = step;
256
254
mask_pub_.publish (out_mask_msg);
257
255
}
258
256
image_pub_.publish (in_image_ptr->toImageMsg ());
0 commit comments