Skip to content

Commit

Permalink
YOLO publishes Object Count with Time stamp using custom msg with Header
Browse files Browse the repository at this point in the history
  • Loading branch information
martinspedro committed Oct 14, 2019
1 parent 3041047 commit 42e3157
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 8 deletions.
2 changes: 1 addition & 1 deletion darknet_ros/include/darknet_ros/YoloObjectDetector.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@
// ROS
#include <ros/ros.h>
#include <std_msgs/Header.h>
#include <std_msgs/Int8.h>
#include <actionlib/server/simple_action_server.h>
#include <sensor_msgs/image_encodings.h>
#include <sensor_msgs/Image.h>
Expand All @@ -36,6 +35,7 @@
// darknet_ros_msgs
#include <darknet_ros_msgs/BoundingBoxes.h>
#include <darknet_ros_msgs/BoundingBox.h>
#include <darknet_ros_msgs/ObjectCount.h>
#include <darknet_ros_msgs/CheckForObjectsAction.h>

// Darknet.
Expand Down
18 changes: 11 additions & 7 deletions darknet_ros/src/YoloObjectDetector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -157,9 +157,9 @@ void YoloObjectDetector::init()

imageSubscriber_ = imageTransport_.subscribe(cameraTopicName, cameraQueueSize,
&YoloObjectDetector::cameraCallback, this);
objectPublisher_ = nodeHandle_.advertise<std_msgs::Int8>(objectDetectorTopicName,
objectDetectorQueueSize,
objectDetectorLatch);
objectPublisher_ = nodeHandle_.advertise<darknet_ros_msgs::ObjectCount>(objectDetectorTopicName,
objectDetectorQueueSize,
objectDetectorLatch);
boundingBoxesPublisher_ = nodeHandle_.advertise<darknet_ros_msgs::BoundingBoxes>(
boundingBoxesTopicName, boundingBoxesQueueSize, boundingBoxesLatch);
detectionImagePublisher_ = nodeHandle_.advertise<sensor_msgs::Image>(detectionImageTopicName,
Expand Down Expand Up @@ -599,8 +599,10 @@ void *YoloObjectDetector::publishInThread()
}
}

std_msgs::Int8 msg;
msg.data = num;
darknet_ros_msgs::ObjectCount msg;
msg.header.stamp = ros::Time::now();
msg.header.frame_id = "detection";
msg.count = num;
objectPublisher_.publish(msg);

for (int i = 0; i < numClasses_; i++) {
Expand Down Expand Up @@ -629,8 +631,10 @@ void *YoloObjectDetector::publishInThread()
boundingBoxesResults_.image_header = headerBuff_[(buffIndex_ + 1) % 3];
boundingBoxesPublisher_.publish(boundingBoxesResults_);
} else {
std_msgs::Int8 msg;
msg.data = 0;
darknet_ros_msgs::ObjectCount msg;
msg.header.stamp = ros::Time::now();
msg.header.frame_id = "detection";
msg.count = 0;
objectPublisher_.publish(msg);
}
if (isCheckingForObjects()) {
Expand Down

0 comments on commit 42e3157

Please sign in to comment.