stereo-vision
All Data Structures Namespaces Functions Modules Pages
disparityThread.cpp
1 /*
2  * Copyright (C) 2011 Department of Robotics Brain and Cognitive Sciences - Istituto Italiano di Tecnologia
3  * Authors: Vadim Tikhanoff
4  * email: vadim.tikhanoff@iit.it
5  * website: www.robotcub.org
6  * Permission is granted to copy, distribute, and/or modify this program
7  * under the terms of the GNU General Public License, version 2 or any
8  * later version published by the Free Software Foundation.
9  *
10  * A copy of the license can be found at
11  * http://www.robotcub.org/icub/license/gpl.txtd
12  *
13  * This program is distributed in the hope that it will be useful, but
14  * WITHOUT ANY WARRANTY; without even the implied warranty of
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
16  * Public License for more details
17  */
18 
19 #include <opencv2/core/core_c.h>
20 #include "iCub/stereoVision/disparityThread.h"
21 
22 bool DisparityThread::loadExtrinsics(yarp::os::ResourceFinder& rf, Mat& Ro, Mat& To, yarp::sig::Vector& eyes)
23 {
24  Bottle extrinsics=rf.findGroup("STEREO_DISPARITY");
25 
26  eyes.resize(3,0.0);
27  if (Bottle *bEyes=extrinsics.find("eyes").asList())
28  {
29  size_t sz=std::min(eyes.length(),(size_t)bEyes->size());
30  for (size_t i=0; i<sz; i++)
31  eyes[i]=bEyes->get(i).asFloat64();
32  }
33 
34  cout<<"read eyes configuration = ("<<eyes.toString(3,3)<<")"<<endl;
35 
36  if (Bottle *pXo=extrinsics.find("HN").asList())
37  {
38  Ro=Mat::zeros(3,3,CV_64FC1);
39  To=Mat::zeros(3,1,CV_64FC1);
40  for (int i=0; i<(pXo->size()-4); i+=4)
41  {
42  Ro.at<double>(i/4,0)=pXo->get(i).asFloat64();
43  Ro.at<double>(i/4,1)=pXo->get(i+1).asFloat64();
44  Ro.at<double>(i/4,2)=pXo->get(i+2).asFloat64();
45  To.at<double>(i/4,0)=pXo->get(i+3).asFloat64();
46  }
47  }
48  else
49  return false;
50 
51  return true;
52 }
53 
54 
55 DisparityThread::DisparityThread(const string &name, yarp::os::ResourceFinder &rf,
56  bool useHorn, bool updateCamera, bool rectify) : PeriodicThread(0.01)
57 {
58  moduleName=name;
59  Bottle pars=rf.findGroup("STEREO_DISPARITY");
60  robotName=pars.check("robotName",Value("icub")).asString();
61 
62  if (Bottle *pXo=pars.find("QL").asList())
63  {
64  QL.resize(pXo->size());
65  for (int i=0; i<(pXo->size()); i++)
66  QL[i]=pXo->get(i).asFloat64();
67  }
68 
69  if (Bottle *pXo=pars.find("QR").asList())
70  {
71  QR.resize(pXo->size());
72  for (int i=0; i<(pXo->size()); i++)
73  QR[i]=pXo->get(i).asFloat64();
74  }
75 
76  int calib=rf.check("useCalibrated",Value(1)).asInt32();
77  this->useCalibrated=(calib!=0);
78  this->useHorn=useHorn;
79  Mat KL, KR, DistL, DistR, R, T;
80  success=loadStereoParameters(rf,KL,KR,DistL,DistR,R,T);
81 
82  ResourceFinder localCalibration;
83  localCalibration.setDefaultContext("cameraCalibration");
84  localCalibration.setDefaultConfigFile("SFM.ini");
85  localCalibration.configure(0,NULL);
86 
87  loadExtrinsics(localCalibration,R0,T0,eyes0);
88  eyes.resize(eyes0.length(),0.0);
89 
90  this->stereo=new StereoCamera(rectify);
91  if (success)
92  {
93  stereo->setIntrinsics(KL,KR,DistL,DistR);
94  this->HL_root=Mat::zeros(4,4,CV_64F);
95 
96  if (R0.empty() || T0.empty())
97  {
98  R0=R;
99  T0=T;
100  }
101 
102  stereo->setRotation(R0,0);
103  stereo->setTranslation(T0,0);
104 
105  if (useCalibrated)
106  {
107  Mat KL=this->stereo->getKleft();
108  Mat KR=this->stereo->getKright();
109  Mat zeroDist=Mat::zeros(1,8,CV_64FC1);
110  this->stereo->setIntrinsics(KL,KR,zeroDist,zeroDist);
111  }
112 
113  printf("Disparity Thread has started...\n");
114  }
115 
116  this->widthInit=320;
117  this->useBestDisp=true;
118  this->uniquenessRatio=15;
119  this->speckleWindowSize=50;
120  this->speckleRange=16;
121  this->numberOfDisparities=96;
122  this->SADWindowSize=7;
123  this->minDisparity=0;
124  this->preFilterCap=63;
125  this->disp12MaxDiff=0;
126 
127  this->init=true;
128  this->work=false;
129  this->done=false;
130  this->updateOnce=false;
131  this->updateCamera=updateCamera;
132 
133 #ifdef USING_GPU
134  utils=new Utilities();
135  utils->initSIFT_GPU();
136 #endif
137 }
138 
139 
140 bool DisparityThread::isOpen()
141 {
142  return success;
143 }
144 
145 
146 void DisparityThread::updateViaKinematics(const yarp::sig::Vector& deyes)
147 {
148  double dpan=CTRL_DEG2RAD*deyes[1];
149  double dver=CTRL_DEG2RAD*deyes[2];
150 
151  yarp::sig::Vector rot_l_pan(4,0.0);
152  rot_l_pan[1]=1.0;
153  rot_l_pan[3]=dpan+dver/2.0;
154  Matrix L1=axis2dcm(rot_l_pan);
155 
156  yarp::sig::Vector rot_r_pan(4,0.0);
157  rot_r_pan[1]=1.0;
158  rot_r_pan[3]=dpan-dver/2.0;
159  Matrix R1=axis2dcm(rot_r_pan);
160 
161  Mat RT0=buildRotTras(R0,T0);
162  Matrix H0; convert(RT0,H0);
163  Matrix H=SE3inv(R1)*H0*L1;
164 
165  Mat R=Mat::zeros(3,3,CV_64F);
166  Mat T=Mat::zeros(3,1,CV_64F);
167 
168  for (int i=0; i<R.rows; i++)
169  for(int j=0; j<R.cols; j++)
170  R.at<double>(i,j)=H(i,j);
171 
172  for (int i=0; i<T.rows; i++)
173  T.at<double>(i,0)=H(i,3);
174 
175  this->stereo->setRotation(R,0);
176  this->stereo->setTranslation(T,0);
177 }
178 
179 
180 void DisparityThread::updateViaGazeCtrl(const bool update)
181 {
182  Matrix L1=getCameraHGazeCtrl(LEFT);
183  Matrix R1=getCameraHGazeCtrl(RIGHT);
184 
185  Matrix RT=SE3inv(R1)*L1;
186 
187  Mat R=Mat::zeros(3,3,CV_64F);
188  Mat T=Mat::zeros(3,1,CV_64F);
189 
190  for (int i=0; i<R.rows; i++)
191  for(int j=0; j<R.cols; j++)
192  R.at<double>(i,j)=RT(i,j);
193 
194  for (int i=0; i<T.rows; i++)
195  T.at<double>(i,0)=RT(i,3);
196 
197  if (update)
198  {
199  stereo->setRotation(R,0);
200  stereo->setTranslation(T,0);
201  }
202  else
203  stereo->setExpectedPosition(R,T);
204 }
205 
206 
207 void DisparityThread::run()
208 {
209  if (!success)
210  {
211  printf("Error. Cannot load camera parameters... Check your config file \n");
212  return;
213  }
214 
215  if (work)
216  {
217  // read encoders
218  posHead->getEncoder(nHeadAxis-3,&eyes[0]);
219  posHead->getEncoder(nHeadAxis-2,&eyes[1]);
220  posHead->getEncoder(nHeadAxis-1,&eyes[2]);
221 
222  updateViaKinematics(eyes-eyes0);
223  updateViaGazeCtrl(false);
224 
225  mutexDisp.lock();
226  if (updateCamera || updateOnce)
227  {
228  #ifdef USING_GPU
229  Mat leftMat=this->stereo->getImLeft();
230  Mat rightMat=this->stereo->getImRight();
231  this->stereo->setImages(leftMat,rightMat);
232  utils->extractMatch_GPU(leftMat,rightMat);
233  vector<Point2f> leftM,rightM;
234  utils->getMatches(leftM,rightM);
235  this->stereo->setMatches(leftM,rightM);
236  #else
237  this->stereo->findMatch(false,15,10.0);
238  #endif
239 
240  this->stereo->estimateEssential();
241  if (this->stereo->essentialDecomposition())
242  {
243  R0=this->stereo->getRotation();
244  T0=this->stereo->getTranslation();
245  eyes0=eyes;
246 
247  if (updateOnce)
248  updateOnce=false;
249  }
250  }
251 
252  // Compute Disparity
253  this->stereo->computeDisparity(this->useBestDisp, this->uniquenessRatio, this->speckleWindowSize,
254  this->speckleRange, this->numberOfDisparities, this->SADWindowSize,
255  this->minDisparity, this->preFilterCap, this->disp12MaxDiff);
256  mutexDisp.unlock();
257  work=false;
258  done=true;
259  this->suspend();
260  }
261 }
262 
263 
264 void DisparityThread::setImages(const Mat &left, const Mat &right)
265 {
266  stereo->setImages(left,right);
267 
268  if (left.size().width!=widthInit)
269  {
270  this->numberOfDisparities=(left.size().width<=320)?96:128;
271  widthInit=left.size().width;
272  }
273 
274  this->done=false;
275  this->work=true;
276  this->resume();
277 }
278 
279 
280 void DisparityThread::getDisparity(Mat &Disp)
281 {
282  mutexDisp.lock();
283  Mat tmp=stereo->getDisparity();
284  Disp=tmp.clone();
285  mutexDisp.unlock();
286 }
287 
288 
289 void DisparityThread::getDisparityFloat(Mat &Disp)
290 {
291  mutexDisp.lock();
292  Mat tmp=stereo->getDisparity16();
293  Disp= tmp.clone();
294  mutexDisp.unlock();
295 }
296 
297 
298 void DisparityThread::getQMat(Mat &Q)
299 {
300  mutexDisp.lock();
301  Mat tmp=stereo->getQ();
302  Q= tmp.clone();
303  mutexDisp.unlock();
304 }
305 
306 
307 void DisparityThread::getMapper(Mat &Mapper)
308 {
309  mutexDisp.lock();
310  Mat tmp=stereo->getMapperL();
311  Mapper= tmp.clone();
312  mutexDisp.unlock();
313 }
314 
315 
316 void DisparityThread::getRectMatrix(Mat &RL)
317 {
318  mutexDisp.lock();
319  Mat tmp=stereo->getRLrect();
320  RL= tmp.clone();
321  mutexDisp.unlock();
322 }
323 
324 
325 bool DisparityThread::threadInit()
326 {
327  Property option;
328  option.put("device","gazecontrollerclient");
329  option.put("remote","/iKinGazeCtrl");
330  option.put("local","/"+moduleName+"/gaze");
331  if (gazeCtrl.open(option))
332  {
333  mutexDisp.lock();
334  gazeCtrl.view(igaze);
335  getCameraHGazeCtrl(LEFT);
336  getCameraHGazeCtrl(RIGHT);
337  mutexDisp.unlock();
338  }
339  else
340  {
341  cout<<"Devices not available"<<endl;
342  success=false;
343  return false;
344  }
345 
346  Property optHead;
347  optHead.put("device","remote_controlboard");
348  optHead.put("remote","/"+robotName+"/head");
349  optHead.put("local","/"+moduleName+"/head");
350  if (polyHead.open(optHead))
351  {
352  polyHead.view(posHead);
353  polyHead.view(HctrlLim);
354  posHead->getAxes(&nHeadAxis);
355  }
356  else
357  {
358  cout<<"Devices not available"<<endl;
359  success=false;
360  return false;
361  }
362 
363  Property optTorso;
364  optTorso.put("device","remote_controlboard");
365  optTorso.put("remote","/"+robotName+"/torso");
366  optTorso.put("local","/"+moduleName+"/torso");
367  if (polyTorso.open(optTorso))
368  {
369  polyTorso.view(posTorso);
370  polyTorso.view(TctrlLim);
371  }
372  else
373  {
374  cout<<"Devices not available"<<endl;
375  success=false;
376  return false;
377  }
378 
379  Bottle p;
380  igaze->getInfo(p);
381  auto vHead=p.check(("head_version"),Value("1.0")).asString();
382  LeyeKin=new iCubEye("left_v"+vHead);
383  ReyeKin=new iCubEye("right_v"+vHead);
384  LeyeKin->releaseLink(0);
385  LeyeKin->releaseLink(1);
386  LeyeKin->releaseLink(2);
387  ReyeKin->releaseLink(0);
388  ReyeKin->releaseLink(1);
389  ReyeKin->releaseLink(2);
390  deque<IControlLimits*> lim;
391  lim.push_back(TctrlLim);
392  lim.push_back(HctrlLim);
393  LeyeKin->alignJointsBounds(lim);
394  ReyeKin->alignJointsBounds(lim);
395 
396  return true;
397 }
398 
399 
400 void DisparityThread::threadRelease()
401 {
402  delete stereo;
403 
404  gazeCtrl.close();
405 
406  delete LeyeKin;
407  delete ReyeKin;
408 
409  if (polyHead.isValid())
410  polyHead.close();
411 
412  if (polyTorso.isValid())
413  polyTorso.close();
414 
415  #ifdef USING_GPU
416  delete utils;
417  #endif
418 
419  printf("Disparity Thread Closed... \n");
420 }
421 
422 
423 bool DisparityThread::checkDone()
424 {
425  return done;
426 }
427 
428 
429 void DisparityThread::stopUpdate()
430 {
431  updateCamera=false;
432 }
433 
434 
435 void DisparityThread::startUpdate()
436 {
437  updateCamera=true;
438 }
439 
440 
441 void DisparityThread::updateCamerasOnce()
442 {
443  updateCamera=false;
444  updateOnce=true;
445 }
446 
447 
448 void DisparityThread::triangulate(Point2f &pixel,Point3f &point)
449 {
450  mutexDisp.lock();
451  Mat disparity=stereo->getDisparity16();
452  Mat Q= stereo->getQ();
453  Mat Mapper=stereo->getMapperL();
454  Mat RLrect=stereo->getRLrect();
455 
456  int u=(int) pixel.x;
457  int v=(int) pixel.y;
458 
459  // Mapping from Rectified Cameras to Original Cameras
460  if(Mapper.empty())
461  {
462  point.x=0.0;
463  point.y=0.0;
464  point.z=0.0;
465  this->mutexDisp.unlock();
466  return;
467  }
468 
469  float usign=Mapper.ptr<float>(v)[2*u];
470  float vsign=Mapper.ptr<float>(v)[2*u+1];
471 
472  u=cvRound(usign);
473  v=cvRound(vsign);
474 
475  if(disparity.empty() || u<0 || u>=disparity.size().width || v<0 || v>=disparity.size().height)
476  {
477  point.x=0.0;
478  point.y=0.0;
479  point.z=0.0;
480  this->mutexDisp.unlock();
481  return;
482  }
483  else
484  {
485  CvScalar scal=cvGet2D(&disparity,v,u);
486  double dispVal=scal.val[0]/16.0;
487  float w= (float) ((float) dispVal*Q.at<double>(3,2)) + ((float)Q.at<double>(3,3));
488  point.x= (float)((float) (usign+1)*Q.at<double>(0,0)) + ((float) Q.at<double>(0,3));
489  point.y=(float)((float) (vsign+1)*Q.at<double>(1,1)) + ((float) Q.at<double>(1,3));
490  point.z=(float) Q.at<double>(2,3);
491 
492  point.x=point.x/w;
493  point.y=point.y/w;
494  point.z=point.z/w;
495  }
496  // discard points far more than 10 meters or with not valid disparity (<0)
497  if(point.z>10 || point.z<0)
498  {
499  point.x=0.0;
500  point.y=0.0;
501  point.z=0.0;
502  this->mutexDisp.unlock();
503  return;
504  }
505  else
506  {
507  Mat RLrecttemp=RLrect.t();
508  Mat Tfake = Mat::zeros(0,3,CV_64F);
509  Mat P(4,1,CV_64FC1);
510  P.at<double>(0,0)=point.x;
511  P.at<double>(1,0)=point.y;
512  P.at<double>(2,0)=point.z;
513  P.at<double>(3,0)=1;
514 
515  Mat Hrect = Mat::eye(4, 4, CV_64F);
516  Hrect=buildRotTras(RLrecttemp,Tfake);
517 
518  P=HL_root*Hrect*P;
519  point.x=(float) ((float) P.at<double>(0,0)/P.at<double>(3,0));
520  point.y=(float) ((float) P.at<double>(1,0)/P.at<double>(3,0));
521  point.z=(float) ((float) P.at<double>(2,0)/P.at<double>(3,0));
522  }
523  this->mutexDisp.unlock();
524  return;
525 }
526 
527 
528 Mat DisparityThread::buildRotTras(Mat& R, Mat& T)
529 {
530  Mat A=Mat::eye(4,4,CV_64F);
531  for (int i=0; i<R.rows; i++)
532  {
533  double* Mi=A.ptr<double>(i);
534  double* MRi=R.ptr<double>(i);
535  for (int j=0; j<R.cols; j++)
536  Mi[j]=MRi[j];
537  }
538 
539  for (int i=0; i<T.rows; i++)
540  {
541  double* Mi=A.ptr<double>(i);
542  double* MRi=T.ptr<double>(i);
543  Mi[3]=MRi[0];
544  }
545 
546  return A;
547 }
548 
549 
550 bool DisparityThread::loadStereoParameters(yarp::os::ResourceFinder &rf, Mat &KL,
551  Mat &KR, Mat &DistL, Mat &DistR, Mat &Ro, Mat &To)
552 {
553 
554  Bottle left=rf.findGroup("CAMERA_CALIBRATION_LEFT");
555  if (!left.check("fx") || !left.check("fy") || !left.check("cx") || !left.check("cy"))
556  return false;
557 
558  double fx=left.find("fx").asFloat64();
559  double fy=left.find("fy").asFloat64();
560 
561  double cx=left.find("cx").asFloat64();
562  double cy=left.find("cy").asFloat64();
563 
564  double k1=left.check("k1",Value(0)).asFloat64();
565  double k2=left.check("k2",Value(0)).asFloat64();
566 
567  double p1=left.check("p1",Value(0)).asFloat64();
568  double p2=left.check("p2",Value(0)).asFloat64();
569 
570  DistL=Mat::zeros(1,8,CV_64FC1);
571  DistL.at<double>(0,0)=k1;
572  DistL.at<double>(0,1)=k2;
573  DistL.at<double>(0,2)=p1;
574  DistL.at<double>(0,3)=p2;
575 
576 
577  KL=Mat::eye(3,3,CV_64FC1);
578  KL.at<double>(0,0)=fx;
579  KL.at<double>(0,2)=cx;
580  KL.at<double>(1,1)=fy;
581  KL.at<double>(1,2)=cy;
582 
583  Bottle right=rf.findGroup("CAMERA_CALIBRATION_RIGHT");
584  if(!right.check("fx") || !right.check("fy") || !right.check("cx") || !right.check("cy"))
585  return false;
586 
587  fx=right.find("fx").asFloat64();
588  fy=right.find("fy").asFloat64();
589 
590  cx=right.find("cx").asFloat64();
591  cy=right.find("cy").asFloat64();
592 
593  k1=right.check("k1",Value(0)).asFloat64();
594  k2=right.check("k2",Value(0)).asFloat64();
595 
596  p1=right.check("p1",Value(0)).asFloat64();
597  p2=right.check("p2",Value(0)).asFloat64();
598 
599  DistR=Mat::zeros(1,8,CV_64FC1);
600  DistR.at<double>(0,0)=k1;
601  DistR.at<double>(0,1)=k2;
602  DistR.at<double>(0,2)=p1;
603  DistR.at<double>(0,3)=p2;
604 
605  KR=Mat::eye(3,3,CV_64FC1);
606  KR.at<double>(0,0)=fx;
607  KR.at<double>(0,2)=cx;
608  KR.at<double>(1,1)=fy;
609  KR.at<double>(1,2)=cy;
610 
611  Ro=Mat::zeros(3,3,CV_64FC1);
612  To=Mat::zeros(3,1,CV_64FC1);
613 
614  /*Bottle extrinsics=rf.findGroup("STEREO_DISPARITY");
615  if (Bottle *pXo=extrinsics.find("HN").asList()) {
616  for (int i=0; i<(pXo->size()-4); i+=4) {
617  Ro.at<double>(i/4,0)=pXo->get(i).asFloat64();
618  Ro.at<double>(i/4,1)=pXo->get(i+1).asFloat64();
619  Ro.at<double>(i/4,2)=pXo->get(i+2).asFloat64();
620  T.at<double>(i/4,0)=pXo->get(i+3).asFloat64();
621  }
622  }
623  else
624  return false;*/
625 
626  return true;
627 }
628 
629 
630 void DisparityThread::printMatrixYarp(Matrix &A)
631 {
632  cout << endl;
633  for (int i=0; i<A.rows(); i++)
634  {
635  for (int j=0; j<A.cols(); j++)
636  cout<<A(i,j)<<" ";
637  cout<<endl;
638  }
639  cout << endl;
640 }
641 
642 
643 void DisparityThread::convert(Matrix& matrix, Mat& mat)
644 {
645  mat=cv::Mat(matrix.rows(),matrix.cols(),CV_64FC1);
646  for(int i=0; i<matrix.rows(); i++)
647  for(int j=0; j<matrix.cols(); j++)
648  mat.at<double>(i,j)=matrix(i,j);
649 }
650 
651 
652 void DisparityThread::convert(Mat& mat, Matrix& matrix)
653 {
654  matrix.resize(mat.rows,mat.cols);
655  for(int i=0; i<mat.rows; i++)
656  for(int j=0; j<mat.cols; j++)
657  matrix(i,j)=mat.at<double>(i,j);
658 }
659 
660 
661 void DisparityThread::getRootTransformation(Mat & Trans,int eye)
662 {
663  mutexDisp.lock();
664 
665  if(eye==LEFT)
666  Trans= HL_root.clone();
667  else
668  Trans= HR_root.clone();
669 
670  mutexDisp.unlock();
671 
672 }
673 
674 
675 Matrix DisparityThread::getCameraH(yarp::sig::Vector &head_angles,
676  yarp::sig::Vector &torso_angles, iCubEye *eyeKin, int camera)
677 {
678 
679  yarp::sig::Vector q(torso_angles.size()+head_angles.size());
680 
681  //torso angles are inverted
682  for(int i=0; i<torso_angles.size(); i++)
683  q[i]=torso_angles[torso_angles.size()-i-1];
684 
685  for(int i=0; i<head_angles.size()-2; i++)
686  q[i+torso_angles.size()]=head_angles[i];
687 
688  // Vs=(L+R)/2 Vg=L-R
689  q[7]=head_angles[4]+(0.5-(camera))*head_angles[5];
690 
691  q=CTRL_DEG2RAD*q;
692 
693 
694  Matrix H_curr=eyeKin->getH(q);
695 
696  q=eyeKin->getAng();
697 
698 
699 
700  if(camera==LEFT)
701  {
702  /*q=q*CTRL_RAD2DEG;
703  cout << " Q Chain" << endl;
704  cout << q.toString(5,5) << endl;*/
705  convert(H_curr,HL_root);
706  }
707  else if(camera==RIGHT)
708  {
709  convert(H_curr,HR_root);
710  }
711 
712 
713  return H_curr;
714 }
715 
716 
717 Matrix DisparityThread::getCameraHGazeCtrl(int camera)
718 {
719  yarp::sig::Vector x_curr;
720  yarp::sig::Vector o_curr;
721  bool check=false;
722  if(camera==LEFT)
723  check=igaze->getLeftEyePose(x_curr, o_curr);
724  else
725  check=igaze->getRightEyePose(x_curr, o_curr);
726 
727  if (!check)
728  {
729  Matrix H_curr(4, 4);
730  return H_curr;
731  }
732 
733  Matrix R_curr=axis2dcm(o_curr);
734  Matrix H_curr=R_curr;
735  H_curr.setSubcol(x_curr,0,3);
736 
737  if (camera==LEFT)
738  convert(H_curr,HL_root);
739  else if (camera==RIGHT)
740  convert(H_curr,HR_root);
741 
742  return H_curr;
743 }
744 
745 
746 void DisparityThread::onStop()
747 {
748  this->work=false;
749  this->done=true;
750 }
751 
752 
753 void DisparityThread::setDispParameters(bool _useBestDisp, int _uniquenessRatio, int _speckleWindowSize,
754  int _speckleRange, int _numberOfDisparities, int _SADWindowSize,
755  int _minDisparity, int _preFilterCap, int _disp12MaxDiff)
756 {
757  mutexDisp.lock();
758 
759  this->useBestDisp=_useBestDisp;
760  this->uniquenessRatio=_uniquenessRatio;
761  this->speckleWindowSize=_speckleWindowSize;
762  this->speckleRange=_speckleRange;
763  this->numberOfDisparities=_numberOfDisparities;
764  this->SADWindowSize=_SADWindowSize;
765  this->minDisparity=_minDisparity;
766  this->preFilterCap=_preFilterCap;
767  this->disp12MaxDiff=_disp12MaxDiff;
768 
769  this->mutexDisp.unlock();
770 
771 }
772 
773 
774 Point3f DisparityThread::get3DPointMatch(double u1, double v1, double u2, double v2, string drive)
775 {
776  Point3f point;
777  if(drive!="RIGHT" && drive !="LEFT" && drive!="ROOT") {
778  point.x=0.0;
779  point.y=0.0;
780  point.z=0.0;
781  return point;
782  }
783 
784  mutexDisp.lock();
785 
786  // Mapping from Rectified Cameras to Original Cameras
787  Mat MapperL=this->stereo->getMapperL();
788  Mat MapperR=this->stereo->getMapperR();
789 
790  if(MapperL.empty() || MapperR.empty()) {
791  point.x=0.0;
792  point.y=0.0;
793  point.z=0.0;
794 
795  this->mutexDisp.unlock();
796  return point;
797  }
798 
799  if(cvRound(u1)<0 || cvRound(u1)>=MapperL.cols || cvRound(v1)<0 || cvRound(v1)>=MapperL.rows) {
800  point.x=0.0;
801  point.y=0.0;
802  point.z=0.0;
803  this->mutexDisp.unlock();
804  return point;
805  }
806 
807  if(cvRound(u2)<0 || cvRound(u2)>=MapperL.cols || cvRound(v2)<0 || cvRound(v2)>=MapperL.rows) {
808  point.x=0.0;
809  point.y=0.0;
810  point.z=0.0;
811  this->mutexDisp.unlock();
812  return point;
813  }
814 
815  float urect1=MapperL.ptr<float>(cvRound(v1))[2*cvRound(u1)];
816  float vrect1=MapperL.ptr<float>(cvRound(v1))[2*cvRound(u1)+1];
817 
818  float urect2=MapperR.ptr<float>(cvRound(v2))[2*cvRound(u2)];
819  float vrect2=MapperR.ptr<float>(cvRound(v2))[2*cvRound(u2)+1];
820 
821  Mat Q=this->stereo->getQ();
822  double disparity=urect1-urect2;
823  float w= (float) ((float) disparity*Q.at<double>(3,2)) + ((float)Q.at<double>(3,3));
824  point.x= (float)((float) (urect1+1)*Q.at<double>(0,0)) + ((float) Q.at<double>(0,3));
825  point.y=(float)((float) (vrect1+1)*Q.at<double>(1,1)) + ((float) Q.at<double>(1,3));
826  point.z=(float) Q.at<double>(2,3);
827 
828  point.x=point.x/w;
829  point.y=point.y/w;
830  point.z=point.z/w;
831 
832  if(drive=="LEFT") {
833  Mat P(3,1,CV_64FC1);
834  P.at<double>(0,0)=point.x;
835  P.at<double>(1,0)=point.y;
836  P.at<double>(2,0)=point.z;
837 
838  P=this->stereo->getRLrect().t()*P;
839 
840  point.x=(float) P.at<double>(0,0);
841  point.y=(float) P.at<double>(1,0);
842  point.z=(float) P.at<double>(2,0);
843  }
844 
845  if(drive=="RIGHT") {
846  Mat Rright = this->stereo->getRotation();
847  Mat Tright = this->stereo->getTranslation();
848  Mat RRright = this->stereo->getRRrect().t();
849  Mat TRright = Mat::zeros(0,3,CV_64F);
850 
851  Mat RLrect=stereo->getRLrect();
852  Mat RLrecttemp=RLrect.t();
853  Mat Tfake = Mat::zeros(0,3,CV_64F);
854  Mat Hrect = Mat::eye(4, 4, CV_64F);
855  Hrect=buildRotTras(RLrecttemp,Tfake);
856 
857  Mat HRL;
858  HRL=buildRotTras(Rright,Tright);
859  Hrect=buildRotTras(RRright,TRright);
860 
861  Mat P(4,1,CV_64FC1);
862  P.at<double>(0,0)=point.x;
863  P.at<double>(1,0)=point.y;
864  P.at<double>(2,0)=point.z;
865  P.at<double>(3,0)=1;
866 
867  P=Hrect*HRL*P;
868  point.x=(float) ((float) P.at<double>(0,0)/P.at<double>(3,0));
869  point.y=(float) ((float) P.at<double>(1,0)/P.at<double>(3,0));
870  point.z=(float) ((float) P.at<double>(2,0)/P.at<double>(3,0));
871  }
872 
873  if(drive=="ROOT") {
874  Mat RLrect=this->stereo->getRLrect().t();
875  Mat Tfake = Mat::zeros(0,3,CV_64F);
876  Mat P(4,1,CV_64FC1);
877  P.at<double>(0,0)=point.x;
878  P.at<double>(1,0)=point.y;
879  P.at<double>(2,0)=point.z;
880  P.at<double>(3,0)=1;
881 
882  Mat Hrect;
883  Hrect=buildRotTras(RLrect,Tfake);
884  P=HL_root*Hrect*P;
885  point.x=(float) ((float) P.at<double>(0,0)/P.at<double>(3,0));
886  point.y=(float) ((float) P.at<double>(1,0)/P.at<double>(3,0));
887  point.z=(float) ((float) P.at<double>(2,0)/P.at<double>(3,0));
888  }
889 
890  this->mutexDisp.unlock();
891  return point;
892 }
893 
894 
The base class defining stereo camera.
Definition: stereoCamera.h:92
void setRotation(Mat &Rot, int mode=0)
It sets the rotation matrix (if known) between the first and the second camera.
bool essentialDecomposition()
It decomposes the essential matrix in Rotation and Translation between the two views.
const Mat & getTranslation() const
It returns the translation vector between the two cameras.
const Mat & getRRrect() const
It returns the rotation matrix between the original right camera and the rectified right camera.
const Mat & getDisparity16() const
It returns the disparity image.
const Mat & getDisparity() const
It returns the disparity image.
void computeDisparity(bool best=true, int uniquenessRatio=15, int speckleWindowSize=50, int speckleRange=16, int numberOfDisparities=64, int SADWindowSize=7, int minDisparity=0, int preFilterCap=63, int disp12MaxDiff=0)
It computes the Disparity Map (see stereoDisparity).
void setTranslation(Mat &Tras, int mul=0)
It sets the translation vector (if known) between the first and the second camera.
void setExpectedPosition(Mat &Rot, Mat &Tran)
The function set the expected Rotation and Translation parameters for the current image pair.
const Mat & getQ() const
It returns the 4x4 disparity-to-depth mapping matrix.
void estimateEssential()
It estimates the essential matrix (3x3) E between two views.
const Mat & getRLrect() const
It returns the rotation matrix between the original left camera and the rectified left camera.
const Mat & getImLeft() const
It returns the left (first) image.
const Mat & getMapperR() const
It returns the mapping between the original right camera and the rectified right camera.
const Mat & getImRight() const
It returns the right (second) image.
void setImages(const Mat &firstImg, const Mat &secondImg)
It stores in memory a couple of images.
const Mat & getMapperL() const
It returns the mapping between the original left camera and the rectified left camera.
void setMatches(std::vector< cv::Point2f > &pointsL, std::vector< cv::Point2f > &pointsR)
The function initialize the matches of the current image pair.
cv::Mat findMatch(bool visualize=false, double displacement=20.0, double radius=200.0)
It finds matches between two images.