19 #include <opencv2/core/core_c.h>
20 #include "iCub/stereoVision/disparityThread.h"
22 bool DisparityThread::loadExtrinsics(yarp::os::ResourceFinder& rf, Mat& Ro, Mat& To, yarp::sig::Vector& eyes)
24 Bottle extrinsics=rf.findGroup(
"STEREO_DISPARITY");
27 if (Bottle *bEyes=extrinsics.find(
"eyes").asList())
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();
34 cout<<
"read eyes configuration = ("<<eyes.toString(3,3)<<
")"<<endl;
36 if (Bottle *pXo=extrinsics.find(
"HN").asList())
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)
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();
55 DisparityThread::DisparityThread(
const string &name, yarp::os::ResourceFinder &rf,
56 bool useHorn,
bool updateCamera,
bool rectify) : PeriodicThread(0.01)
59 Bottle pars=rf.findGroup(
"STEREO_DISPARITY");
60 robotName=pars.check(
"robotName",Value(
"icub")).asString();
62 if (Bottle *pXo=pars.find(
"QL").asList())
64 QL.resize(pXo->size());
65 for (
int i=0; i<(pXo->size()); i++)
66 QL[i]=pXo->get(i).asFloat64();
69 if (Bottle *pXo=pars.find(
"QR").asList())
71 QR.resize(pXo->size());
72 for (
int i=0; i<(pXo->size()); i++)
73 QR[i]=pXo->get(i).asFloat64();
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);
82 ResourceFinder localCalibration;
83 localCalibration.setDefaultContext(
"cameraCalibration");
84 localCalibration.setDefaultConfigFile(
"SFM.ini");
85 localCalibration.configure(0,NULL);
87 loadExtrinsics(localCalibration,R0,T0,eyes0);
88 eyes.resize(eyes0.length(),0.0);
93 stereo->setIntrinsics(KL,KR,DistL,DistR);
94 this->HL_root=Mat::zeros(4,4,CV_64F);
96 if (R0.empty() || T0.empty())
102 stereo->setRotation(R0,0);
103 stereo->setTranslation(T0,0);
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);
113 printf(
"Disparity Thread has started...\n");
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;
130 this->updateOnce=
false;
131 this->updateCamera=updateCamera;
134 utils=
new Utilities();
135 utils->initSIFT_GPU();
140 bool DisparityThread::isOpen()
146 void DisparityThread::updateViaKinematics(
const yarp::sig::Vector& deyes)
148 double dpan=CTRL_DEG2RAD*deyes[1];
149 double dver=CTRL_DEG2RAD*deyes[2];
151 yarp::sig::Vector rot_l_pan(4,0.0);
153 rot_l_pan[3]=dpan+dver/2.0;
154 Matrix L1=axis2dcm(rot_l_pan);
156 yarp::sig::Vector rot_r_pan(4,0.0);
158 rot_r_pan[3]=dpan-dver/2.0;
159 Matrix R1=axis2dcm(rot_r_pan);
161 Mat RT0=buildRotTras(R0,T0);
162 Matrix H0; convert(RT0,H0);
163 Matrix H=SE3inv(R1)*H0*L1;
165 Mat R=Mat::zeros(3,3,CV_64F);
166 Mat T=Mat::zeros(3,1,CV_64F);
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);
172 for (
int i=0; i<T.rows; i++)
173 T.at<
double>(i,0)=H(i,3);
180 void DisparityThread::updateViaGazeCtrl(
const bool update)
182 Matrix L1=getCameraHGazeCtrl(LEFT);
183 Matrix R1=getCameraHGazeCtrl(RIGHT);
185 Matrix RT=SE3inv(R1)*L1;
187 Mat R=Mat::zeros(3,3,CV_64F);
188 Mat T=Mat::zeros(3,1,CV_64F);
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);
194 for (
int i=0; i<T.rows; i++)
195 T.at<
double>(i,0)=RT(i,3);
207 void DisparityThread::run()
211 printf(
"Error. Cannot load camera parameters... Check your config file \n");
218 posHead->getEncoder(nHeadAxis-3,&eyes[0]);
219 posHead->getEncoder(nHeadAxis-2,&eyes[1]);
220 posHead->getEncoder(nHeadAxis-1,&eyes[2]);
222 updateViaKinematics(eyes-eyes0);
223 updateViaGazeCtrl(
false);
226 if (updateCamera || updateOnce)
231 this->stereo->
setImages(leftMat,rightMat);
232 utils->extractMatch_GPU(leftMat,rightMat);
233 vector<Point2f> leftM,rightM;
234 utils->getMatches(leftM,rightM);
243 R0=this->stereo->getRotation();
253 this->stereo->
computeDisparity(this->useBestDisp, this->uniquenessRatio, this->speckleWindowSize,
254 this->speckleRange, this->numberOfDisparities, this->SADWindowSize,
255 this->minDisparity, this->preFilterCap, this->disp12MaxDiff);
264 void DisparityThread::setImages(
const Mat &left,
const Mat &right)
268 if (left.size().width!=widthInit)
270 this->numberOfDisparities=(left.size().width<=320)?96:128;
271 widthInit=left.size().width;
280 void DisparityThread::getDisparity(Mat &Disp)
289 void DisparityThread::getDisparityFloat(Mat &Disp)
298 void DisparityThread::getQMat(Mat &Q)
301 Mat tmp=stereo->
getQ();
307 void DisparityThread::getMapper(Mat &Mapper)
316 void DisparityThread::getRectMatrix(Mat &RL)
325 bool DisparityThread::threadInit()
328 option.put(
"device",
"gazecontrollerclient");
329 option.put(
"remote",
"/iKinGazeCtrl");
330 option.put(
"local",
"/"+moduleName+
"/gaze");
331 if (gazeCtrl.open(option))
334 gazeCtrl.view(igaze);
335 getCameraHGazeCtrl(LEFT);
336 getCameraHGazeCtrl(RIGHT);
341 cout<<
"Devices not available"<<endl;
347 optHead.put(
"device",
"remote_controlboard");
348 optHead.put(
"remote",
"/"+robotName+
"/head");
349 optHead.put(
"local",
"/"+moduleName+
"/head");
350 if (polyHead.open(optHead))
352 polyHead.view(posHead);
353 polyHead.view(HctrlLim);
354 posHead->getAxes(&nHeadAxis);
358 cout<<
"Devices not available"<<endl;
364 optTorso.put(
"device",
"remote_controlboard");
365 optTorso.put(
"remote",
"/"+robotName+
"/torso");
366 optTorso.put(
"local",
"/"+moduleName+
"/torso");
367 if (polyTorso.open(optTorso))
369 polyTorso.view(posTorso);
370 polyTorso.view(TctrlLim);
374 cout<<
"Devices not available"<<endl;
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);
400 void DisparityThread::threadRelease()
409 if (polyHead.isValid())
412 if (polyTorso.isValid())
419 printf(
"Disparity Thread Closed... \n");
423 bool DisparityThread::checkDone()
429 void DisparityThread::stopUpdate()
435 void DisparityThread::startUpdate()
441 void DisparityThread::updateCamerasOnce()
448 void DisparityThread::triangulate(Point2f &pixel,Point3f &point)
452 Mat Q= stereo->
getQ();
465 this->mutexDisp.unlock();
469 float usign=Mapper.ptr<
float>(v)[2*u];
470 float vsign=Mapper.ptr<
float>(v)[2*u+1];
475 if(disparity.empty() || u<0 || u>=disparity.size().width || v<0 || v>=disparity.size().height)
480 this->mutexDisp.unlock();
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);
497 if(point.z>10 || point.z<0)
502 this->mutexDisp.unlock();
507 Mat RLrecttemp=RLrect.t();
508 Mat Tfake = Mat::zeros(0,3,CV_64F);
510 P.at<
double>(0,0)=point.x;
511 P.at<
double>(1,0)=point.y;
512 P.at<
double>(2,0)=point.z;
515 Mat Hrect = Mat::eye(4, 4, CV_64F);
516 Hrect=buildRotTras(RLrecttemp,Tfake);
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));
523 this->mutexDisp.unlock();
528 Mat DisparityThread::buildRotTras(Mat& R, Mat& T)
530 Mat A=Mat::eye(4,4,CV_64F);
531 for (
int i=0; i<R.rows; i++)
533 double* Mi=A.ptr<
double>(i);
534 double* MRi=R.ptr<
double>(i);
535 for (
int j=0; j<R.cols; j++)
539 for (
int i=0; i<T.rows; i++)
541 double* Mi=A.ptr<
double>(i);
542 double* MRi=T.ptr<
double>(i);
550 bool DisparityThread::loadStereoParameters(yarp::os::ResourceFinder &rf, Mat &KL,
551 Mat &KR, Mat &DistL, Mat &DistR, Mat &Ro, Mat &To)
554 Bottle left=rf.findGroup(
"CAMERA_CALIBRATION_LEFT");
555 if (!left.check(
"fx") || !left.check(
"fy") || !left.check(
"cx") || !left.check(
"cy"))
558 double fx=left.find(
"fx").asFloat64();
559 double fy=left.find(
"fy").asFloat64();
561 double cx=left.find(
"cx").asFloat64();
562 double cy=left.find(
"cy").asFloat64();
564 double k1=left.check(
"k1",Value(0)).asFloat64();
565 double k2=left.check(
"k2",Value(0)).asFloat64();
567 double p1=left.check(
"p1",Value(0)).asFloat64();
568 double p2=left.check(
"p2",Value(0)).asFloat64();
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;
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;
583 Bottle right=rf.findGroup(
"CAMERA_CALIBRATION_RIGHT");
584 if(!right.check(
"fx") || !right.check(
"fy") || !right.check(
"cx") || !right.check(
"cy"))
587 fx=right.find(
"fx").asFloat64();
588 fy=right.find(
"fy").asFloat64();
590 cx=right.find(
"cx").asFloat64();
591 cy=right.find(
"cy").asFloat64();
593 k1=right.check(
"k1",Value(0)).asFloat64();
594 k2=right.check(
"k2",Value(0)).asFloat64();
596 p1=right.check(
"p1",Value(0)).asFloat64();
597 p2=right.check(
"p2",Value(0)).asFloat64();
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;
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;
611 Ro=Mat::zeros(3,3,CV_64FC1);
612 To=Mat::zeros(3,1,CV_64FC1);
630 void DisparityThread::printMatrixYarp(Matrix &A)
633 for (
int i=0; i<A.rows(); i++)
635 for (
int j=0; j<A.cols(); j++)
643 void DisparityThread::convert(Matrix& matrix, Mat& mat)
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);
652 void DisparityThread::convert(Mat& mat, Matrix& matrix)
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);
661 void DisparityThread::getRootTransformation(Mat & Trans,
int eye)
666 Trans= HL_root.clone();
668 Trans= HR_root.clone();
675 Matrix DisparityThread::getCameraH(yarp::sig::Vector &head_angles,
676 yarp::sig::Vector &torso_angles, iCubEye *eyeKin,
int camera)
679 yarp::sig::Vector q(torso_angles.size()+head_angles.size());
682 for(
int i=0; i<torso_angles.size(); i++)
683 q[i]=torso_angles[torso_angles.size()-i-1];
685 for(
int i=0; i<head_angles.size()-2; i++)
686 q[i+torso_angles.size()]=head_angles[i];
689 q[7]=head_angles[4]+(0.5-(camera))*head_angles[5];
694 Matrix H_curr=eyeKin->getH(q);
705 convert(H_curr,HL_root);
707 else if(camera==RIGHT)
709 convert(H_curr,HR_root);
717 Matrix DisparityThread::getCameraHGazeCtrl(
int camera)
719 yarp::sig::Vector x_curr;
720 yarp::sig::Vector o_curr;
723 check=igaze->getLeftEyePose(x_curr, o_curr);
725 check=igaze->getRightEyePose(x_curr, o_curr);
733 Matrix R_curr=axis2dcm(o_curr);
734 Matrix H_curr=R_curr;
735 H_curr.setSubcol(x_curr,0,3);
738 convert(H_curr,HL_root);
739 else if (camera==RIGHT)
740 convert(H_curr,HR_root);
746 void DisparityThread::onStop()
753 void DisparityThread::setDispParameters(
bool _useBestDisp,
int _uniquenessRatio,
int _speckleWindowSize,
754 int _speckleRange,
int _numberOfDisparities,
int _SADWindowSize,
755 int _minDisparity,
int _preFilterCap,
int _disp12MaxDiff)
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;
769 this->mutexDisp.unlock();
774 Point3f DisparityThread::get3DPointMatch(
double u1,
double v1,
double u2,
double v2,
string drive)
777 if(drive!=
"RIGHT" && drive !=
"LEFT" && drive!=
"ROOT") {
790 if(MapperL.empty() || MapperR.empty()) {
795 this->mutexDisp.unlock();
799 if(cvRound(u1)<0 || cvRound(u1)>=MapperL.cols || cvRound(v1)<0 || cvRound(v1)>=MapperL.rows) {
803 this->mutexDisp.unlock();
807 if(cvRound(u2)<0 || cvRound(u2)>=MapperL.cols || cvRound(v2)<0 || cvRound(v2)>=MapperL.rows) {
811 this->mutexDisp.unlock();
815 float urect1=MapperL.ptr<
float>(cvRound(v1))[2*cvRound(u1)];
816 float vrect1=MapperL.ptr<
float>(cvRound(v1))[2*cvRound(u1)+1];
818 float urect2=MapperR.ptr<
float>(cvRound(v2))[2*cvRound(u2)];
819 float vrect2=MapperR.ptr<
float>(cvRound(v2))[2*cvRound(u2)+1];
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);
834 P.at<
double>(0,0)=point.x;
835 P.at<
double>(1,0)=point.y;
836 P.at<
double>(2,0)=point.z;
838 P=this->stereo->getRLrect().t()*P;
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);
846 Mat Rright = this->stereo->getRotation();
848 Mat RRright = this->stereo->
getRRrect().t();
849 Mat TRright = Mat::zeros(0,3,CV_64F);
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);
858 HRL=buildRotTras(Rright,Tright);
859 Hrect=buildRotTras(RRright,TRright);
862 P.at<
double>(0,0)=point.x;
863 P.at<
double>(1,0)=point.y;
864 P.at<
double>(2,0)=point.z;
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));
874 Mat RLrect=this->stereo->
getRLrect().t();
875 Mat Tfake = Mat::zeros(0,3,CV_64F);
877 P.at<
double>(0,0)=point.x;
878 P.at<
double>(1,0)=point.y;
879 P.at<
double>(2,0)=point.z;
883 Hrect=buildRotTras(RLrect,Tfake);
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));
890 this->mutexDisp.unlock();
The base class defining stereo camera.
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.