YoloObjectDetector.cpp
Go to the documentation of this file.
1 /*
2  * YoloObjectDetector.cpp
3  *
4  * Created on: Dec 19, 2016
5  * Author: Marko Bjelonic
6  * Institute: ETH Zurich, Robotic Systems Lab
7  */
8 
9 // yolo object detector
11 
12 // Check for xServer
13 #include <X11/Xlib.h>
14 
15 #ifdef DARKNET_FILE_PATH
16 std::string darknetFilePath_ = DARKNET_FILE_PATH;
17 #else
18 #error Path of darknet repository is not defined in CMakeLists.txt.
19 #endif
20 
21 namespace darknet_ros {
22 
23 char* cfg;
24 char* weights;
25 char* data;
27 
29  : nodeHandle_(nh), imageTransport_(nodeHandle_), numClasses_(0), classLabels_(0), rosBoxes_(0), rosBoxCounter_(0) {
30  ROS_INFO("[YoloObjectDetector] Node started.");
31 
32  // Read parameters from config file.
33  if (!readParameters()) {
35  }
36 
37  init();
38 }
39 
41  {
42  boost::unique_lock<boost::shared_mutex> lockNodeStatus(mutexNodeStatus_);
43  isNodeRunning_ = false;
44  }
45  yoloThread_.join();
46 }
47 
49  // Load common parameters.
50  nodeHandle_.param("image_view/enable_opencv", viewImage_, true);
51  nodeHandle_.param("image_view/wait_key_delay", waitKeyDelay_, 3);
52  nodeHandle_.param("image_view/enable_console_output", enableConsoleOutput_, false);
53 
54  // Check if Xserver is running on Linux.
55  if (XOpenDisplay(NULL)) {
56  // Do nothing!
57  ROS_INFO("[YoloObjectDetector] Xserver is running.");
58  } else {
59  ROS_INFO("[YoloObjectDetector] Xserver is not running.");
60  viewImage_ = false;
61  }
62 
63  // Set vector sizes.
64  nodeHandle_.param("yolo_model/detection_classes/names", classLabels_, std::vector<std::string>(0));
65  numClasses_ = classLabels_.size();
66  rosBoxes_ = std::vector<std::vector<RosBox_> >(numClasses_);
67  rosBoxCounter_ = std::vector<int>(numClasses_);
68 
69  return true;
70 }
71 
73  ROS_INFO("[YoloObjectDetector] init().");
74 
75  // Initialize deep network of darknet.
76  std::string weightsPath;
77  std::string configPath;
78  std::string dataPath;
79  std::string configModel;
80  std::string weightsModel;
81 
82  // Threshold of object detection.
83  float thresh;
84  nodeHandle_.param("yolo_model/threshold/value", thresh, (float)0.3);
85 
86  // Path to weights file.
87  nodeHandle_.param("yolo_model/weight_file/name", weightsModel, std::string("yolov2-tiny.weights"));
88  nodeHandle_.param("weights_path", weightsPath, std::string("/default"));
89  weightsPath += "/" + weightsModel;
90  weights = new char[weightsPath.length() + 1];
91  strcpy(weights, weightsPath.c_str());
92 
93  // Path to config file.
94  nodeHandle_.param("yolo_model/config_file/name", configModel, std::string("yolov2-tiny.cfg"));
95  nodeHandle_.param("config_path", configPath, std::string("/default"));
96  configPath += "/" + configModel;
97  cfg = new char[configPath.length() + 1];
98  strcpy(cfg, configPath.c_str());
99 
100  // Path to data folder.
101  dataPath = darknetFilePath_;
102  dataPath += "/data";
103  data = new char[dataPath.length() + 1];
104  strcpy(data, dataPath.c_str());
105 
106  // Get classes.
107  detectionNames = (char**)realloc((void*)detectionNames, (numClasses_ + 1) * sizeof(char*));
108  for (int i = 0; i < numClasses_; i++) {
109  detectionNames[i] = new char[classLabels_[i].length() + 1];
110  strcpy(detectionNames[i], classLabels_[i].c_str());
111  }
112 
113  // Load network.
114  setupNetwork(cfg, weights, data, thresh, detectionNames, numClasses_, 0, 0, 1, 0.5, 0, 0, 0, 0);
115  yoloThread_ = std::thread(&YoloObjectDetector::yolo, this);
116 
117  // Initialize publisher and subscriber.
118  std::string cameraTopicName;
119  int cameraQueueSize;
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;
129 
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);
141 
142  imageSubscriber_ = imageTransport_.subscribe(cameraTopicName, cameraQueueSize, &YoloObjectDetector::cameraCallback, this);
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);
149 
150  // Action servers.
151  std::string checkForObjectsActionName;
152  nodeHandle_.param("actions/camera_reading/topic", checkForObjectsActionName, std::string("check_for_objects"));
153  checkForObjectsActionServer_.reset(new CheckForObjectsActionServer(nodeHandle_, checkForObjectsActionName, false));
154  checkForObjectsActionServer_->registerGoalCallback(boost::bind(&YoloObjectDetector::checkForObjectsActionGoalCB, this));
155  checkForObjectsActionServer_->registerPreemptCallback(boost::bind(&YoloObjectDetector::checkForObjectsActionPreemptCB, this));
157 }
158 
159 void YoloObjectDetector::cameraCallback(const sensor_msgs::ImageConstPtr& msg) {
160  ROS_DEBUG("[YoloObjectDetector] USB image received.");
161 
162  cv_bridge::CvImagePtr cam_image;
163 
164  try {
166  } catch (cv_bridge::Exception& e) {
167  ROS_ERROR("cv_bridge exception: %s", e.what());
168  return;
169  }
170 
171  if (cam_image) {
172  {
173  boost::unique_lock<boost::shared_mutex> lockImageCallback(mutexImageCallback_);
174  imageHeader_ = msg->header;
175  camImageCopy_ = cam_image->image.clone();
176  }
177  {
178  boost::unique_lock<boost::shared_mutex> lockImageStatus(mutexImageStatus_);
179  imageStatus_ = true;
180  }
181  frameWidth_ = cam_image->image.size().width;
182  frameHeight_ = cam_image->image.size().height;
183  }
184  return;
185 }
186 
188  ROS_DEBUG("[YoloObjectDetector] Start check for objects action.");
189 
191  sensor_msgs::Image imageAction = imageActionPtr->image;
192 
193  cv_bridge::CvImagePtr cam_image;
194 
195  try {
197  } catch (cv_bridge::Exception& e) {
198  ROS_ERROR("cv_bridge exception: %s", e.what());
199  return;
200  }
201 
202  if (cam_image) {
203  {
204  boost::unique_lock<boost::shared_mutex> lockImageCallback(mutexImageCallback_);
205  camImageCopy_ = cam_image->image.clone();
206  }
207  {
208  boost::unique_lock<boost::shared_mutex> lockImageCallback(mutexActionStatus_);
209  actionId_ = imageActionPtr->id;
210  }
211  {
212  boost::unique_lock<boost::shared_mutex> lockImageStatus(mutexImageStatus_);
213  imageStatus_ = true;
214  }
215  frameWidth_ = cam_image->image.size().width;
216  frameHeight_ = cam_image->image.size().height;
217  }
218  return;
219 }
220 
222  ROS_DEBUG("[YoloObjectDetector] Preempt check for objects action.");
223  checkForObjectsActionServer_->setPreempted();
224 }
225 
227  return (ros::ok() && checkForObjectsActionServer_->isActive() && !checkForObjectsActionServer_->isPreemptRequested());
228 }
229 
230 bool YoloObjectDetector::publishDetectionImage(const cv::Mat& detectionImage) {
231  if (detectionImagePublisher_.getNumSubscribers() < 1) return false;
232  cv_bridge::CvImage cvImage;
233  cvImage.header.stamp = ros::Time::now();
234  cvImage.header.frame_id = "detection_image";
236  cvImage.image = detectionImage;
238  ROS_DEBUG("Detection image has been published.");
239  return true;
240 }
241 
242 // double YoloObjectDetector::getWallTime()
243 // {
244 // struct timeval time;
245 // if (gettimeofday(&time, NULL)) {
246 // return 0;
247 // }
248 // return (double) time.tv_sec + (double) time.tv_usec * .000001;
249 // }
250 
252  int i;
253  int count = 0;
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) {
257  count += l.outputs;
258  }
259  }
260  return count;
261 }
262 
264  int i;
265  int count = 0;
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) {
269  memcpy(predictions_[demoIndex_] + count, net->layers[i].output, sizeof(float) * l.outputs);
270  count += l.outputs;
271  }
272  }
273 }
274 
275 detection* YoloObjectDetector::avgPredictions(network* net, int* nboxes) {
276  int i, j;
277  int count = 0;
278  fill_cpu(demoTotal_, 0, avg_, 1);
279  for (j = 0; j < demoFrame_; ++j) {
280  axpy_cpu(demoTotal_, 1. / demoFrame_, predictions_[j], 1, avg_, 1);
281  }
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);
286  count += l.outputs;
287  }
288  }
289  detection* dets = get_network_boxes(net, buff_[0].w, buff_[0].h, demoThresh_, demoHier_, 0, 1, nboxes);
290  return dets;
291 }
292 
294  running_ = 1;
295  float nms = .4;
296 
297  layer l = net_->layers[net_->n - 1];
298  float* X = buffLetter_[(buffIndex_ + 2) % 3].data;
299  float* prediction = network_predict(net_, X);
300 
302  detection* dets = 0;
303  int nboxes = 0;
304  dets = avgPredictions(net_, &nboxes);
305 
306  if (nms > 0) do_nms_obj(dets, nboxes, l.classes, nms);
307 
308  if (enableConsoleOutput_) {
309  printf("\033[2J");
310  printf("\033[1;1H");
311  printf("\nFPS:%.1f\n", fps_);
312  printf("Objects:\n\n");
313  }
314  image display = buff_[(buffIndex_ + 2) % 3];
315  draw_detections(display, dets, nboxes, demoThresh_, demoNames_, demoAlphabet_, demoClasses_);
316 
317  // extract the bounding boxes and send them to ROS
318  int i, j;
319  int count = 0;
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.;
325 
326  if (xmin < 0) xmin = 0;
327  if (ymin < 0) ymin = 0;
328  if (xmax > 1) xmax = 1;
329  if (ymax > 1) ymax = 1;
330 
331  // iterate through possible boxes and collect the bounding boxes
332  for (j = 0; j < demoClasses_; ++j) {
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;
338 
339  // define bounding box
340  // BoundingBox must be 1% size of frame (3.2x2.4 pixels)
341  if (BoundingBox_width > 0.01 && BoundingBox_height > 0.01) {
342  roiBoxes_[count].x = x_center;
343  roiBoxes_[count].y = y_center;
344  roiBoxes_[count].w = BoundingBox_width;
345  roiBoxes_[count].h = BoundingBox_height;
346  roiBoxes_[count].Class = j;
347  roiBoxes_[count].prob = dets[i].prob[j];
348  count++;
349  }
350  }
351  }
352  }
353 
354  // create array to store found bounding boxes
355  // if no object detected, make sure that ROS knows that num = 0
356  if (count == 0) {
357  roiBoxes_[0].num = 0;
358  } else {
359  roiBoxes_[0].num = count;
360  }
361 
362  free_detections(dets, nboxes);
363  demoIndex_ = (demoIndex_ + 1) % demoFrame_;
364  running_ = 0;
365  return 0;
366 }
367 
369  {
370  boost::shared_lock<boost::shared_mutex> lock(mutexImageCallback_);
371  CvMatWithHeader_ imageAndHeader = getCvMatWithHeader();
372  free_image(buff_[buffIndex_]);
373  buff_[buffIndex_] = mat_to_image(imageAndHeader.image);
374  headerBuff_[buffIndex_] = imageAndHeader.header;
376  }
377  rgbgr_image(buff_[buffIndex_]);
378  letterbox_image_into(buff_[buffIndex_], net_->w, net_->h, buffLetter_[buffIndex_]);
379  return 0;
380 }
381 
383  int c = show_image(buff_[(buffIndex_ + 1) % 3], "YOLO", 1);
384  if (c != -1) c = c % 256;
385  if (c == 27) {
386  demoDone_ = 1;
387  return 0;
388  } else if (c == 82) {
389  demoThresh_ += .02;
390  } else if (c == 84) {
391  demoThresh_ -= .02;
392  if (demoThresh_ <= .02) demoThresh_ = .02;
393  } else if (c == 83) {
394  demoHier_ += .02;
395  } else if (c == 81) {
396  demoHier_ -= .02;
397  if (demoHier_ <= .0) demoHier_ = .0;
398  }
399  return 0;
400 }
401 
403  while (1) {
404  displayInThread(0);
405  }
406 }
407 
409  while (1) {
410  detectInThread();
411  }
412 }
413 
414 void YoloObjectDetector::setupNetwork(char* cfgfile, char* weightfile, char* datafile, float thresh, char** names, int classes, int delay,
415  char* prefix, int avg_frames, float hier, int w, int h, int frames, int fullscreen) {
416  demoPrefix_ = prefix;
417  demoDelay_ = delay;
418  demoFrame_ = avg_frames;
419  image** alphabet = load_alphabet_with_file(datafile);
420  demoNames_ = names;
421  demoAlphabet_ = alphabet;
422  demoClasses_ = classes;
423  demoThresh_ = thresh;
424  demoHier_ = hier;
425  fullScreen_ = fullscreen;
426  printf("YOLO\n");
427  net_ = load_network(cfgfile, weightfile, 0);
428  set_batch_network(net_, 1);
429 }
430 
432  const auto wait_duration = std::chrono::milliseconds(2000);
433  while (!getImageStatus()) {
434  printf("Waiting for image.\n");
435  if (!isNodeRunning()) {
436  return;
437  }
438  std::this_thread::sleep_for(wait_duration);
439  }
440 
441  std::thread detect_thread;
442  std::thread fetch_thread;
443 
444  srand(2222222);
445 
446  int i;
448  predictions_ = (float**)calloc(demoFrame_, sizeof(float*));
449  for (i = 0; i < demoFrame_; ++i) {
450  predictions_[i] = (float*)calloc(demoTotal_, sizeof(float));
451  }
452  avg_ = (float*)calloc(demoTotal_, sizeof(float));
453 
454  layer l = net_->layers[net_->n - 1];
455  roiBoxes_ = (darknet_ros::RosBox_*)calloc(l.w * l.h * l.n, sizeof(darknet_ros::RosBox_));
456 
457  {
458  boost::shared_lock<boost::shared_mutex> lock(mutexImageCallback_);
459  CvMatWithHeader_ imageAndHeader = getCvMatWithHeader();
460  buff_[0] = mat_to_image(imageAndHeader.image);
461  headerBuff_[0] = imageAndHeader.header;
462  }
463  buff_[1] = copy_image(buff_[0]);
464  buff_[2] = copy_image(buff_[0]);
465  headerBuff_[1] = headerBuff_[0];
466  headerBuff_[2] = headerBuff_[0];
467  buffLetter_[0] = letterbox_image(buff_[0], net_->w, net_->h);
468  buffLetter_[1] = letterbox_image(buff_[0], net_->w, net_->h);
469  buffLetter_[2] = letterbox_image(buff_[0], net_->w, net_->h);
470  disp_ = image_to_mat(buff_[0]);
471 
472  int count = 0;
473  if (!demoPrefix_ && viewImage_) {
474  cv::namedWindow("YOLO", cv::WINDOW_NORMAL);
475  if (fullScreen_) {
476  cv::setWindowProperty("YOLO", cv::WND_PROP_FULLSCREEN, cv::WINDOW_FULLSCREEN);
477  } else {
478  cv::moveWindow("YOLO", 0, 0);
479  cv::resizeWindow("YOLO", 640, 480);
480  }
481  }
482 
483  demoTime_ = what_time_is_it_now();
484 
485  while (!demoDone_) {
486  buffIndex_ = (buffIndex_ + 1) % 3;
487  fetch_thread = std::thread(&YoloObjectDetector::fetchInThread, this);
488  detect_thread = std::thread(&YoloObjectDetector::detectInThread, this);
489  if (!demoPrefix_) {
490  fps_ = 1. / (what_time_is_it_now() - demoTime_);
491  demoTime_ = what_time_is_it_now();
492  if (viewImage_) {
493  displayInThread(0);
494  } else {
495  generate_image(buff_[(buffIndex_ + 1) % 3], disp_);
496  }
497  publishInThread();
498  } else {
499  char name[256];
500  sprintf(name, "%s_%08d", demoPrefix_, count);
501  save_image(buff_[(buffIndex_ + 1) % 3], name);
502  }
503  fetch_thread.join();
504  detect_thread.join();
505  ++count;
506  if (!isNodeRunning()) {
507  demoDone_ = true;
508  }
509  }
510 }
511 
513  CvMatWithHeader_ header = {.image = camImageCopy_, .header = imageHeader_};
514  return header;
515 }
516 
518  boost::shared_lock<boost::shared_mutex> lock(mutexImageStatus_);
519  return imageStatus_;
520 }
521 
523  boost::shared_lock<boost::shared_mutex> lock(mutexNodeStatus_);
524  return isNodeRunning_;
525 }
526 
528  // Publish image.
529  cv::Mat cvImage = disp_;
530  if (!publishDetectionImage(cv::Mat(cvImage))) {
531  ROS_DEBUG("Detection image has not been broadcasted.");
532  }
533 
534  // Publish bounding boxes and detection result.
535  int num = roiBoxes_[0].num;
536  if (num > 0 && num <= 100) {
537  for (int i = 0; i < num; i++) {
538  for (int j = 0; j < numClasses_; j++) {
539  if (roiBoxes_[i].Class == j) {
540  rosBoxes_[j].push_back(roiBoxes_[i]);
541  rosBoxCounter_[j]++;
542  }
543  }
544  }
545 
546  darknet_ros_msgs::ObjectCount msg;
547  msg.header.stamp = ros::Time::now();
548  msg.header.frame_id = "detection";
549  msg.count = num;
551 
552  for (int i = 0; i < numClasses_; i++) {
553  if (rosBoxCounter_[i] > 0) {
554  darknet_ros_msgs::BoundingBox boundingBox;
555 
556  for (int j = 0; j < rosBoxCounter_[i]; j++) {
557  int xmin = (rosBoxes_[i][j].x - rosBoxes_[i][j].w / 2) * frameWidth_;
558  int ymin = (rosBoxes_[i][j].y - rosBoxes_[i][j].h / 2) * frameHeight_;
559  int xmax = (rosBoxes_[i][j].x + rosBoxes_[i][j].w / 2) * frameWidth_;
560  int ymax = (rosBoxes_[i][j].y + rosBoxes_[i][j].h / 2) * frameHeight_;
561 
562  boundingBox.Class = classLabels_[i];
563  boundingBox.id = i;
564  boundingBox.probability = rosBoxes_[i][j].prob;
565  boundingBox.xmin = xmin;
566  boundingBox.ymin = ymin;
567  boundingBox.xmax = xmax;
568  boundingBox.ymax = ymax;
569  boundingBoxesResults_.bounding_boxes.push_back(boundingBox);
570  }
571  }
572  }
573  boundingBoxesResults_.header.stamp = ros::Time::now();
574  boundingBoxesResults_.header.frame_id = "detection";
575  boundingBoxesResults_.image_header = headerBuff_[(buffIndex_ + 1) % 3];
577  } else {
578  darknet_ros_msgs::ObjectCount msg;
579  msg.header.stamp = ros::Time::now();
580  msg.header.frame_id = "detection";
581  msg.count = 0;
583  }
584  if (isCheckingForObjects()) {
585  ROS_DEBUG("[YoloObjectDetector] check for objects in image.");
586  darknet_ros_msgs::CheckForObjectsResult objectsActionResult;
587  objectsActionResult.id = buffId_[0];
588  objectsActionResult.bounding_boxes = boundingBoxesResults_;
589  checkForObjectsActionServer_->setSucceeded(objectsActionResult, "Send bounding boxes.");
590  }
591  boundingBoxesResults_.bounding_boxes.clear();
592  for (int i = 0; i < numClasses_; i++) {
593  rosBoxes_[i].clear();
594  rosBoxCounter_[i] = 0;
595  }
596 
597  return 0;
598 }
599 
600 } /* namespace darknet_ros*/
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.
std::string encoding
std::vector< std::vector< RosBox_ > > rosBoxes_
Detected objects.
void cameraCallback(const sensor_msgs::ImageConstPtr &msg)
ros::Publisher detectionImagePublisher_
Publisher of the bounding box image.
int frameWidth_
Camera related parameters.
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)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
cv::Mat image_to_mat(image im)
ROSCPP_DECL bool ok()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::vector< std::string > classLabels_
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
static Time now()
ros::NodeHandle nodeHandle_
ROS node handle.
bool publishDetectionImage(const cv::Mat &detectionImage)
image_transport::Subscriber imageSubscriber_
ROS subscriber and publisher.
#define ROS_ERROR(...)
sensor_msgs::ImagePtr toImageMsg() const
std_msgs::Header header
#define ROS_DEBUG(...)
image ** load_alphabet_with_file(char *datafile)


darknet_ros
Author(s): Marko Bjelonic
autogenerated on Wed May 5 2021 02:58:30