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