Skip to content

Commit ac666ab

Browse files
committed
Merge branch 'kjbilton-master'
2 parents 723db0e + d97ef3a commit ac666ab

File tree

1 file changed

+11
-9
lines changed

1 file changed

+11
-9
lines changed

darknet_ros/src/YoloObjectDetector.cpp

Lines changed: 11 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -406,12 +406,12 @@ void *YoloObjectDetector::detectInThread()
406406

407407
void *YoloObjectDetector::fetchInThread()
408408
{
409-
IplImageWithHeader_ imageAndHeader = getIplImageWithHeader();
410-
IplImage* ROS_img = imageAndHeader.image;
411-
ipl_into_image(ROS_img, buff_[buffIndex_]);
412-
headerBuff_[buffIndex_] = imageAndHeader.header;
413409
{
414410
boost::shared_lock<boost::shared_mutex> lock(mutexImageCallback_);
411+
IplImageWithHeader_ imageAndHeader = getIplImageWithHeader();
412+
IplImage* ROS_img = imageAndHeader.image;
413+
ipl_into_image(ROS_img, buff_[buffIndex_]);
414+
headerBuff_[buffIndex_] = imageAndHeader.header;
415415
buffId_[buffIndex_] = actionId_;
416416
}
417417
rgbgr_image(buff_[buffIndex_]);
@@ -502,12 +502,15 @@ void YoloObjectDetector::yolo()
502502
layer l = net_->layers[net_->n - 1];
503503
roiBoxes_ = (darknet_ros::RosBox_ *) calloc(l.w * l.h * l.n, sizeof(darknet_ros::RosBox_));
504504

505-
IplImageWithHeader_ imageAndHeader = getIplImageWithHeader();
506-
IplImage* ROS_img = imageAndHeader.image;
507-
buff_[0] = ipl_to_image(ROS_img);
505+
{
506+
boost::shared_lock<boost::shared_mutex> lock(mutexImageCallback_);
507+
IplImageWithHeader_ imageAndHeader = getIplImageWithHeader();
508+
IplImage* ROS_img = imageAndHeader.image;
509+
buff_[0] = ipl_to_image(ROS_img);
510+
headerBuff_[0] = imageAndHeader.header;
511+
}
508512
buff_[1] = copy_image(buff_[0]);
509513
buff_[2] = copy_image(buff_[0]);
510-
headerBuff_[0] = imageAndHeader.header;
511514
headerBuff_[1] = headerBuff_[0];
512515
headerBuff_[2] = headerBuff_[0];
513516
buffLetter_[0] = letterbox_image(buff_[0], net_->w, net_->h);
@@ -557,7 +560,6 @@ void YoloObjectDetector::yolo()
557560

558561
IplImageWithHeader_ YoloObjectDetector::getIplImageWithHeader()
559562
{
560-
boost::shared_lock<boost::shared_mutex> lock(mutexImageCallback_);
561563
IplImage* ROS_img = new IplImage(camImageCopy_);
562564
IplImageWithHeader_ header = {.image = ROS_img, .header = imageHeader_};
563565
return header;

0 commit comments

Comments
 (0)