Skip to content

Commit 4c733b7

Browse files
authored
Merge pull request #189 from martinspedro/master
/darknet_ros/found_object uses custom msg with Header for improving synchronization
2 parents f183769 + 42e3157 commit 4c733b7

File tree

4 files changed

+15
-8
lines changed

4 files changed

+15
-8
lines changed

darknet_ros/include/darknet_ros/YoloObjectDetector.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,6 @@
2020
// ROS
2121
#include <ros/ros.h>
2222
#include <std_msgs/Header.h>
23-
#include <std_msgs/Int8.h>
2423
#include <actionlib/server/simple_action_server.h>
2524
#include <sensor_msgs/image_encodings.h>
2625
#include <sensor_msgs/Image.h>
@@ -36,6 +35,7 @@
3635
// darknet_ros_msgs
3736
#include <darknet_ros_msgs/BoundingBoxes.h>
3837
#include <darknet_ros_msgs/BoundingBox.h>
38+
#include <darknet_ros_msgs/ObjectCount.h>
3939
#include <darknet_ros_msgs/CheckForObjectsAction.h>
4040

4141
// Darknet.

darknet_ros/src/YoloObjectDetector.cpp

Lines changed: 11 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -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()) {

darknet_ros_msgs/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@ add_message_files(
1717
FILES
1818
BoundingBox.msg
1919
BoundingBoxes.msg
20+
ObjectCount.msg
2021
)
2122

2223
add_action_files(

darknet_ros_msgs/msg/ObjectCount.msg

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,2 @@
1+
Header header
2+
int8 count

0 commit comments

Comments
 (0)