@@ -157,9 +157,9 @@ void YoloObjectDetector::init()
157157
158158 imageSubscriber_ = imageTransport_.subscribe (cameraTopicName, cameraQueueSize,
159159 &YoloObjectDetector::cameraCallback, this );
160- objectPublisher_ = nodeHandle_.advertise <std_msgs::Int8 >(objectDetectorTopicName,
161- objectDetectorQueueSize,
162- objectDetectorLatch);
160+ objectPublisher_ = nodeHandle_.advertise <darknet_ros_msgs::ObjectCount >(objectDetectorTopicName,
161+ objectDetectorQueueSize,
162+ objectDetectorLatch);
163163 boundingBoxesPublisher_ = nodeHandle_.advertise <darknet_ros_msgs::BoundingBoxes>(
164164 boundingBoxesTopicName, boundingBoxesQueueSize, boundingBoxesLatch);
165165 detectionImagePublisher_ = nodeHandle_.advertise <sensor_msgs::Image>(detectionImageTopicName,
@@ -599,8 +599,10 @@ void *YoloObjectDetector::publishInThread()
599599 }
600600 }
601601
602- std_msgs::Int8 msg;
603- msg.data = num;
602+ darknet_ros_msgs::ObjectCount msg;
603+ msg.header .stamp = ros::Time::now ();
604+ msg.header .frame_id = " detection" ;
605+ msg.count = num;
604606 objectPublisher_.publish (msg);
605607
606608 for (int i = 0 ; i < numClasses_; i++) {
@@ -629,8 +631,10 @@ void *YoloObjectDetector::publishInThread()
629631 boundingBoxesResults_.image_header = headerBuff_[(buffIndex_ + 1 ) % 3 ];
630632 boundingBoxesPublisher_.publish (boundingBoxesResults_);
631633 } else {
632- std_msgs::Int8 msg;
633- msg.data = 0 ;
634+ darknet_ros_msgs::ObjectCount msg;
635+ msg.header .stamp = ros::Time::now ();
636+ msg.header .frame_id = " detection" ;
637+ msg.count = 0 ;
634638 objectPublisher_.publish (msg);
635639 }
636640 if (isCheckingForObjects ()) {
0 commit comments