15 #ifdef DARKNET_FILE_PATH 16 std::string darknetFilePath_ = DARKNET_FILE_PATH;
18 #error Path of darknet repository is not defined in CMakeLists.txt. 29 : nodeHandle_(nh), imageTransport_(nodeHandle_), numClasses_(0), classLabels_(0), rosBoxes_(0), rosBoxCounter_(0) {
30 ROS_INFO(
"[YoloObjectDetector] Node started.");
55 if (XOpenDisplay(NULL)) {
57 ROS_INFO(
"[YoloObjectDetector] Xserver is running.");
59 ROS_INFO(
"[YoloObjectDetector] Xserver is not running.");
73 ROS_INFO(
"[YoloObjectDetector] init().");
76 std::string weightsPath;
77 std::string configPath;
79 std::string configModel;
80 std::string weightsModel;
87 nodeHandle_.
param(
"yolo_model/weight_file/name", weightsModel, std::string(
"yolov2-tiny.weights"));
89 weightsPath +=
"/" + weightsModel;
90 weights =
new char[weightsPath.length() + 1];
91 strcpy(weights, weightsPath.c_str());
94 nodeHandle_.
param(
"yolo_model/config_file/name", configModel, std::string(
"yolov2-tiny.cfg"));
96 configPath +=
"/" + configModel;
97 cfg =
new char[configPath.length() + 1];
98 strcpy(cfg, configPath.c_str());
101 dataPath = darknetFilePath_;
103 data =
new char[dataPath.length() + 1];
104 strcpy(data, dataPath.c_str());
109 detectionNames[i] =
new char[
classLabels_[i].length() + 1];
110 strcpy(detectionNames[i], classLabels_[i].c_str());
114 setupNetwork(cfg, weights, data, thresh, detectionNames, numClasses_, 0, 0, 1, 0.5, 0, 0, 0, 0);
118 std::string cameraTopicName;
120 std::string objectDetectorTopicName;
121 int objectDetectorQueueSize;
122 bool objectDetectorLatch;
123 std::string boundingBoxesTopicName;
124 int boundingBoxesQueueSize;
125 bool boundingBoxesLatch;
126 std::string detectionImageTopicName;
127 int detectionImageQueueSize;
128 bool detectionImageLatch;
130 nodeHandle_.
param(
"subscribers/camera_reading/topic", cameraTopicName, std::string(
"/camera/image_raw"));
131 nodeHandle_.
param(
"subscribers/camera_reading/queue_size", cameraQueueSize, 1);
132 nodeHandle_.
param(
"publishers/object_detector/topic", objectDetectorTopicName, std::string(
"found_object"));
133 nodeHandle_.
param(
"publishers/object_detector/queue_size", objectDetectorQueueSize, 1);
134 nodeHandle_.
param(
"publishers/object_detector/latch", objectDetectorLatch,
false);
135 nodeHandle_.
param(
"publishers/bounding_boxes/topic", boundingBoxesTopicName, std::string(
"bounding_boxes"));
136 nodeHandle_.
param(
"publishers/bounding_boxes/queue_size", boundingBoxesQueueSize, 1);
137 nodeHandle_.
param(
"publishers/bounding_boxes/latch", boundingBoxesLatch,
false);
138 nodeHandle_.
param(
"publishers/detection_image/topic", detectionImageTopicName, std::string(
"detection_image"));
139 nodeHandle_.
param(
"publishers/detection_image/queue_size", detectionImageQueueSize, 1);
140 nodeHandle_.
param(
"publishers/detection_image/latch", detectionImageLatch,
true);
144 nodeHandle_.
advertise<darknet_ros_msgs::ObjectCount>(objectDetectorTopicName, objectDetectorQueueSize, objectDetectorLatch);
146 nodeHandle_.
advertise<darknet_ros_msgs::BoundingBoxes>(boundingBoxesTopicName, boundingBoxesQueueSize, boundingBoxesLatch);
148 nodeHandle_.
advertise<sensor_msgs::Image>(detectionImageTopicName, detectionImageQueueSize, detectionImageLatch);
151 std::string checkForObjectsActionName;
152 nodeHandle_.
param(
"actions/camera_reading/topic", checkForObjectsActionName, std::string(
"check_for_objects"));
160 ROS_DEBUG(
"[YoloObjectDetector] USB image received.");
167 ROS_ERROR(
"cv_bridge exception: %s", e.what());
188 ROS_DEBUG(
"[YoloObjectDetector] Start check for objects action.");
191 sensor_msgs::Image imageAction = imageActionPtr->image;
198 ROS_ERROR(
"cv_bridge exception: %s", e.what());
222 ROS_DEBUG(
"[YoloObjectDetector] Preempt check for objects action.");
234 cvImage.
header.frame_id =
"detection_image";
236 cvImage.
image = detectionImage;
238 ROS_DEBUG(
"Detection image has been published.");
254 for (i = 0; i < net->n; ++i) {
255 layer l = net->layers[i];
256 if (l.type == YOLO || l.type == REGION || l.type == DETECTION) {
266 for (i = 0; i < net->n; ++i) {
267 layer l = net->layers[i];
268 if (l.type == YOLO || l.type == REGION || l.type == DETECTION) {
282 for (i = 0; i < net->n; ++i) {
283 layer l = net->layers[i];
284 if (l.type == YOLO || l.type == REGION || l.type == DETECTION) {
285 memcpy(l.output,
avg_ + count,
sizeof(
float) * l.outputs);
297 layer l =
net_->layers[
net_->n - 1];
299 float* prediction = network_predict(
net_, X);
306 if (nms > 0) do_nms_obj(dets, nboxes, l.classes, nms);
311 printf(
"\nFPS:%.1f\n",
fps_);
312 printf(
"Objects:\n\n");
320 for (i = 0; i < nboxes; ++i) {
321 float xmin = dets[i].bbox.x - dets[i].bbox.w / 2.;
322 float xmax = dets[i].bbox.x + dets[i].bbox.w / 2.;
323 float ymin = dets[i].bbox.y - dets[i].bbox.h / 2.;
324 float ymax = dets[i].bbox.y + dets[i].bbox.h / 2.;
326 if (xmin < 0) xmin = 0;
327 if (ymin < 0) ymin = 0;
328 if (xmax > 1) xmax = 1;
329 if (ymax > 1) ymax = 1;
333 if (dets[i].prob[j]) {
334 float x_center = (xmin + xmax) / 2;
335 float y_center = (ymin + ymax) / 2;
336 float BoundingBox_width = xmax - xmin;
337 float BoundingBox_height = ymax - ymin;
341 if (BoundingBox_width > 0.01 && BoundingBox_height > 0.01) {
362 free_detections(dets, nboxes);
384 if (c != -1) c = c % 256;
388 }
else if (c == 82) {
390 }
else if (c == 84) {
393 }
else if (c == 83) {
395 }
else if (c == 81) {
415 char* prefix,
int avg_frames,
float hier,
int w,
int h,
int frames,
int fullscreen) {
427 net_ = load_network(cfgfile, weightfile, 0);
428 set_batch_network(
net_, 1);
432 const auto wait_duration = std::chrono::milliseconds(2000);
434 printf(
"Waiting for image.\n");
438 std::this_thread::sleep_for(wait_duration);
441 std::thread detect_thread;
442 std::thread fetch_thread;
454 layer l =
net_->layers[
net_->n - 1];
474 cv::namedWindow(
"YOLO", cv::WINDOW_NORMAL);
476 cv::setWindowProperty(
"YOLO", cv::WND_PROP_FULLSCREEN, cv::WINDOW_FULLSCREEN);
478 cv::moveWindow(
"YOLO", 0, 0);
479 cv::resizeWindow(
"YOLO", 640, 480);
504 detect_thread.join();
529 cv::Mat cvImage =
disp_;
531 ROS_DEBUG(
"Detection image has not been broadcasted.");
536 if (num > 0 && num <= 100) {
537 for (
int i = 0; i < num; i++) {
546 darknet_ros_msgs::ObjectCount msg;
548 msg.header.frame_id =
"detection";
554 darknet_ros_msgs::BoundingBox boundingBox;
564 boundingBox.probability =
rosBoxes_[i][j].prob;
565 boundingBox.xmin = xmin;
566 boundingBox.ymin = ymin;
567 boundingBox.xmax = xmax;
568 boundingBox.ymax = ymax;
578 darknet_ros_msgs::ObjectCount msg;
580 msg.header.frame_id =
"detection";
585 ROS_DEBUG(
"[YoloObjectDetector] check for objects in image.");
586 darknet_ros_msgs::CheckForObjectsResult objectsActionResult;
587 objectsActionResult.id =
buffId_[0];
int sizeNetwork(network *net)
Bounding box of the detected object.
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
image mat_to_image(cv::Mat m)
image_transport::ImageTransport imageTransport_
Advertise and subscribe to image topics.
void publish(const boost::shared_ptr< M > &message) const
detection * avgPredictions(network *net, int *nboxes)
actionlib::SimpleActionServer< darknet_ros_msgs::CheckForObjectsAction > CheckForObjectsActionServer
Using.
boost::shared_mutex mutexImageStatus_
ros::Publisher objectPublisher_
std::vector< std::vector< RosBox_ > > rosBoxes_
Detected objects.
bool isCheckingForObjects() const
std_msgs::Header headerBuff_[3]
void cameraCallback(const sensor_msgs::ImageConstPtr &msg)
void * detectLoop(void *ptr)
bool getImageStatus(void)
ros::Publisher detectionImagePublisher_
Publisher of the bounding box image.
bool enableConsoleOutput_
int frameWidth_
Camera related parameters.
boost::shared_mutex mutexImageCallback_
boost::shared_mutex mutexActionStatus_
void setupNetwork(char *cfgfile, char *weightfile, char *datafile, float thresh, char **names, int classes, int delay, char *prefix, int avg_frames, float hier, int w, int h, int frames, int fullscreen)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
int numClasses_
Class labels.
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
void * displayInThread(void *ptr)
cv::Mat image_to_mat(image im)
void checkForObjectsActionPreemptCB()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::vector< std::string > classLabels_
YoloObjectDetector(ros::NodeHandle nh)
ros::Publisher boundingBoxesPublisher_
void rememberNetwork(network *net)
darknet_ros_msgs::BoundingBoxes boundingBoxesResults_
CheckForObjectsActionServerPtr checkForObjectsActionServer_
Check for objects action server.
int show_image(image p, const char *name, int ms)
void generate_image(image p, cv::Mat &disp)
ROSCPP_DECL void requestShutdown()
uint32_t getNumSubscribers() const
void * displayLoop(void *ptr)
ros::NodeHandle nodeHandle_
ROS node handle.
bool publishDetectionImage(const cv::Mat &detectionImage)
image_transport::Subscriber imageSubscriber_
ROS subscriber and publisher.
std_msgs::Header imageHeader_
CvMatWithHeader_ getCvMatWithHeader()
void checkForObjectsActionGoalCB()
sensor_msgs::ImagePtr toImageMsg() const
boost::shared_mutex mutexNodeStatus_
std::vector< int > rosBoxCounter_
image ** load_alphabet_with_file(char *datafile)