@@ -406,12 +406,12 @@ void *YoloObjectDetector::detectInThread()
406
406
407
407
void *YoloObjectDetector::fetchInThread ()
408
408
{
409
- IplImageWithHeader_ imageAndHeader = getIplImageWithHeader ();
410
- IplImage* ROS_img = imageAndHeader.image ;
411
- ipl_into_image (ROS_img, buff_[buffIndex_]);
412
- headerBuff_[buffIndex_] = imageAndHeader.header ;
413
409
{
414
410
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 ;
415
415
buffId_[buffIndex_] = actionId_;
416
416
}
417
417
rgbgr_image (buff_[buffIndex_]);
@@ -502,12 +502,15 @@ void YoloObjectDetector::yolo()
502
502
layer l = net_->layers [net_->n - 1 ];
503
503
roiBoxes_ = (darknet_ros::RosBox_ *) calloc (l.w * l.h * l.n , sizeof (darknet_ros::RosBox_));
504
504
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
+ }
508
512
buff_[1 ] = copy_image (buff_[0 ]);
509
513
buff_[2 ] = copy_image (buff_[0 ]);
510
- headerBuff_[0 ] = imageAndHeader.header ;
511
514
headerBuff_[1 ] = headerBuff_[0 ];
512
515
headerBuff_[2 ] = headerBuff_[0 ];
513
516
buffLetter_[0 ] = letterbox_image (buff_[0 ], net_->w , net_->h );
@@ -557,7 +560,6 @@ void YoloObjectDetector::yolo()
557
560
558
561
IplImageWithHeader_ YoloObjectDetector::getIplImageWithHeader ()
559
562
{
560
- boost::shared_lock<boost::shared_mutex> lock (mutexImageCallback_);
561
563
IplImage* ROS_img = new IplImage (camImageCopy_);
562
564
IplImageWithHeader_ header = {.image = ROS_img, .header = imageHeader_};
563
565
return header;
0 commit comments