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());
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.");
165 if (msg->encoding ==
"mono8" || msg->encoding ==
"bgr8" || msg->encoding ==
"rgb8") {
167 }
else if ( msg->encoding ==
"bgra8") {
169 }
else if ( msg->encoding ==
"rgba8") {
171 }
else if ( msg->encoding ==
"mono16") {
175 ROS_ERROR(
"Image message encoding provided is not mono8, mono16, bgr8, bgra8, rgb8 or rgba8.");
178 ROS_ERROR(
"cv_bridge exception: %s", e.what());
199 ROS_DEBUG(
"[YoloObjectDetector] Start check for objects action.");
202 sensor_msgs::Image imageAction = imageActionPtr->image;
209 ROS_ERROR(
"cv_bridge exception: %s", e.what());
233 ROS_DEBUG(
"[YoloObjectDetector] Preempt check for objects action.");
245 cvImage.
header.frame_id =
"detection_image";
247 cvImage.
image = detectionImage;
249 ROS_DEBUG(
"Detection image has been published.");
265 for (i = 0; i < net->n; ++i) {
266 layer l = net->layers[i];
267 if (l.type == YOLO || l.type == REGION || l.type == DETECTION) {
277 for (i = 0; i < net->n; ++i) {
278 layer l = net->layers[i];
279 if (l.type == YOLO || l.type == REGION || l.type == DETECTION) {
293 for (i = 0; i < net->n; ++i) {
294 layer l = net->layers[i];
295 if (l.type == YOLO || l.type == REGION || l.type == DETECTION) {
296 memcpy(l.output,
avg_ + count,
sizeof(
float) * l.outputs);
308 layer l =
net_->layers[
net_->n - 1];
310 float* prediction = network_predict(
net_, X);
317 if (nms > 0) do_nms_obj(dets, nboxes, l.classes, nms);
322 printf(
"\nFPS:%.1f\n",
fps_);
323 printf(
"Objects:\n\n");
331 for (i = 0; i < nboxes; ++i) {
332 float xmin = dets[i].bbox.x - dets[i].bbox.w / 2.;
333 float xmax = dets[i].bbox.x + dets[i].bbox.w / 2.;
334 float ymin = dets[i].bbox.y - dets[i].bbox.h / 2.;
335 float ymax = dets[i].bbox.y + dets[i].bbox.h / 2.;
337 if (xmin < 0) xmin = 0;
338 if (ymin < 0) ymin = 0;
339 if (xmax > 1) xmax = 1;
340 if (ymax > 1) ymax = 1;
344 if (dets[i].prob[j]) {
345 float x_center = (xmin + xmax) / 2;
346 float y_center = (ymin + ymax) / 2;
347 float BoundingBox_width = xmax - xmin;
348 float BoundingBox_height = ymax - ymin;
352 if (BoundingBox_width > 0.01 && BoundingBox_height > 0.01) {
373 free_detections(dets, nboxes);
395 if (c != -1) c = c % 256;
399 }
else if (c == 82) {
401 }
else if (c == 84) {
404 }
else if (c == 83) {
406 }
else if (c == 81) {
426 char* prefix,
int avg_frames,
float hier,
int w,
int h,
int frames,
int fullscreen) {
438 net_ = load_network(cfgfile, weightfile, 0);
439 set_batch_network(
net_, 1);
443 const auto wait_duration = std::chrono::milliseconds(2000);
445 printf(
"Waiting for image.\n");
449 std::this_thread::sleep_for(wait_duration);
452 std::thread detect_thread;
453 std::thread fetch_thread;
465 layer l =
net_->layers[
net_->n - 1];
485 cv::namedWindow(
"YOLO", cv::WINDOW_NORMAL);
487 cv::setWindowProperty(
"YOLO", cv::WND_PROP_FULLSCREEN, cv::WINDOW_FULLSCREEN);
489 cv::moveWindow(
"YOLO", 0, 0);
490 cv::resizeWindow(
"YOLO", 640, 480);
515 detect_thread.join();
540 cv::Mat cvImage =
disp_;
542 ROS_DEBUG(
"Detection image has not been broadcasted.");
547 if (num > 0 && num <= 100) {
548 for (
int i = 0; i < num; i++) {
557 darknet_ros_msgs::ObjectCount msg;
559 msg.header.frame_id =
"detection";
565 darknet_ros_msgs::BoundingBox boundingBox;
575 boundingBox.probability =
rosBoxes_[i][j].prob;
576 boundingBox.xmin = xmin;
577 boundingBox.ymin = ymin;
578 boundingBox.xmax = xmax;
579 boundingBox.ymax = ymax;
589 darknet_ros_msgs::ObjectCount msg;
591 msg.header.frame_id =
"detection";
596 ROS_DEBUG(
"[YoloObjectDetector] check for objects in image.");
597 darknet_ros_msgs::CheckForObjectsResult objectsActionResult;
598 objectsActionResult.id =
buffId_[0];