@@ -95,10 +95,20 @@ namespace yolox_ros_cpp
9595 this , this ->params_ .src_image_topic_name ,
9696 std::bind (&YoloXNode::colorImageCallback, this , std::placeholders::_1),
9797 " raw" );
98- this ->pub_bboxes_ = this ->create_publisher <bboxes_ex_msgs::msg::BoundingBoxes>(
99- this ->params_ .publish_boundingbox_topic_name ,
100- 10 );
101- this ->pub_image_ = image_transport::create_publisher (this , this ->params_ .publish_image_topic_name );
98+
99+ if (this ->params_ .use_bbox_ex_msgs ) {
100+ this ->pub_bboxes_ = this ->create_publisher <bboxes_ex_msgs::msg::BoundingBoxes>(
101+ this ->params_ .publish_boundingbox_topic_name ,
102+ 10 );
103+ } else {
104+ this ->pub_detection2d_ = this ->create_publisher <vision_msgs::msg::Detection2DArray>(
105+ this ->params_ .publish_boundingbox_topic_name ,
106+ 10 );
107+ }
108+
109+ if (this ->params_ .publish_resized_image ) {
110+ this ->pub_image_ = image_transport::create_publisher (this , this ->params_ .publish_image_topic_name );
111+ }
102112 }
103113
104114 void YoloXNode::colorImageCallback (const sensor_msgs::msg::Image::ConstSharedPtr &ptr)
@@ -108,10 +118,10 @@ namespace yolox_ros_cpp
108118
109119 auto now = std::chrono::system_clock::now ();
110120 auto objects = this ->yolox_ ->inference (frame);
111-
112121 auto end = std::chrono::system_clock::now ();
122+
113123 auto elapsed = std::chrono::duration_cast<std::chrono::milliseconds>(end - now);
114- RCLCPP_INFO (this ->get_logger (), " Inference: %f FPS " , 1000 . 0f / elapsed.count ());
124+ RCLCPP_INFO (this ->get_logger (), " Inference time : %5ld ms " , elapsed.count ());
115125
116126 yolox_cpp::utils::draw_objects (frame, objects, this ->class_names_ );
117127 if (this ->params_ .imshow_isshow )
@@ -124,12 +134,32 @@ namespace yolox_ros_cpp
124134 }
125135 }
126136
127- auto boxes = objects_to_bboxes (frame, objects, img->header );
128- this ->pub_bboxes_ ->publish (boxes);
137+ if (this ->params_ .use_bbox_ex_msgs )
138+ {
139+ if (this ->pub_bboxes_ == nullptr )
140+ {
141+ RCLCPP_ERROR (this ->get_logger (), " pub_bboxes_ is nullptr" );
142+ return ;
143+ }
144+ auto boxes = objects_to_bboxes (frame, objects, img->header );
145+ this ->pub_bboxes_ ->publish (boxes);
146+ }
147+ else
148+ {
149+ if (this ->pub_detection2d_ == nullptr )
150+ {
151+ RCLCPP_ERROR (this ->get_logger (), " pub_detection2d_ is nullptr" );
152+ return ;
153+ }
154+ vision_msgs::msg::Detection2DArray detections = objects_to_detection2d (objects, img->header );
155+ this ->pub_detection2d_ ->publish (detections);
156+ }
129157
130- sensor_msgs::msg::Image::SharedPtr pub_img;
131- pub_img = cv_bridge::CvImage (img->header , " bgr8" , frame).toImageMsg ();
132- this ->pub_image_ .publish (pub_img);
158+ if (this ->params_ .publish_resized_image ) {
159+ sensor_msgs::msg::Image::SharedPtr pub_img =
160+ cv_bridge::CvImage (img->header , " bgr8" , frame).toImageMsg ();
161+ this ->pub_image_ .publish (pub_img);
162+ }
133163 }
134164
135165 bboxes_ex_msgs::msg::BoundingBoxes YoloXNode::objects_to_bboxes (
@@ -140,8 +170,8 @@ namespace yolox_ros_cpp
140170 for (const auto &obj : objects)
141171 {
142172 bboxes_ex_msgs::msg::BoundingBox box;
143- box.probability = obj.prob ;
144- box.class_id = this -> class_names_ [ obj.label ] ;
173+ box.probability = obj.prob ;;
174+ box.class_id = std::to_string ( obj.label ) ;
145175 box.xmin = obj.rect .x ;
146176 box.ymin = obj.rect .y ;
147177 box.xmax = (obj.rect .x + obj.rect .width );
@@ -152,6 +182,26 @@ namespace yolox_ros_cpp
152182 }
153183 return boxes;
154184 }
185+
186+ vision_msgs::msg::Detection2DArray YoloXNode::objects_to_detection2d (const std::vector<yolox_cpp::Object> &objects, const std_msgs::msg::Header &header)
187+ {
188+ vision_msgs::msg::Detection2DArray detection2d;
189+ detection2d.header = header;
190+ for (const auto &obj : objects)
191+ {
192+ vision_msgs::msg::Detection2D det;
193+ det.bbox .center .position .x = obj.rect .x + obj.rect .width / 2 ;
194+ det.bbox .center .position .y = obj.rect .y + obj.rect .height / 2 ;
195+ det.bbox .size_x = obj.rect .width ;
196+ det.bbox .size_y = obj.rect .height ;
197+
198+ det.results .resize (1 );
199+ det.results [0 ].hypothesis .class_id = std::to_string (obj.label );
200+ det.results [0 ].hypothesis .score = obj.prob ;
201+ detection2d.detections .emplace_back (det);
202+ }
203+ return detection2d;
204+ }
155205}
156206
157207RCLCPP_COMPONENTS_REGISTER_NODE (yolox_ros_cpp::YoloXNode)
0 commit comments