21 #include <yarp/cv/Cv.h>
22 #include <opencv2/core/types.hpp>
25 using namespace yarp::cv;
29 bool SFM::configure(ResourceFinder &rf)
31 string name=rf.check(
"name",Value(
"SFM")).asString();
32 string robot=rf.check(
"robot",Value(
"icub")).asString();
33 string left=rf.check(
"leftPort",Value(
"/left:i")).asString();
34 string right=rf.check(
"rightPort",Value(
"/right:i")).asString();
35 string SFMFile=rf.check(
"SFMFile",Value(
"SFM.ini")).asString();
42 string outDispName=rf.check(
"outDispPort",Value(
"/disp:o")).asString();
43 string outMatchName=rf.check(
"outMatchPort",Value(
"/match:o")).asString();
45 string outLeftRectImgPortName=rf.check(
"outLeftRectImgPort",Value(
"/rect_left:o")).asString();
46 string outRightRectImgPortName=rf.check(
"outRightRectImgPort",Value(
"/rect_right:o")).asString();
48 ResourceFinder localCalibration;
49 localCalibration.setDefaultContext(
"cameraCalibration");
50 localCalibration.setDefaultConfigFile(SFMFile.c_str());
51 localCalibration.configure(0,NULL);
53 this->camCalibFile=localCalibration.getHomeContextPath();
54 this->camCalibFile+=
"/"+SFMFile;
56 outMatchName=sname+outMatchName;
57 outDispName=sname+outDispName;
59 outLeftRectImgPortName=sname+outLeftRectImgPortName;
60 outRightRectImgPortName=sname+outRightRectImgPortName;
62 string rpc_name=sname+
"/rpc";
63 string world_name=sname+rf.check(
"outWorldPort",Value(
"/world")).asString();
65 int calib=rf.check(
"useCalibrated",Value(1)).asInt32();
66 bool useCalibrated=(calib!=0);
68 leftImgPort.open(left);
69 rightImgPort.open(right);
70 outMatch.open(outMatchName);
71 outDisp.open(outDispName);
72 handlerPort.open(rpc_name);
73 worldCartPort.open(world_name+
"/cartesian:o");
74 worldCylPort.open(world_name+
"/cylindrical:o");
77 outLeftRectImgPort.open(outLeftRectImgPortName);
78 outRightRectImgPort.open(outRightRectImgPortName);
82 if (!rf.check(
"use_sgbm"))
85 Mat KL, KR, DistL, DistR;
87 loadIntrinsics(rf,KL,KR,DistL,DistR);
88 loadExtrinsics(localCalibration,R0,T0,eyes0);
89 eyes.resize(eyes0.length(),0.0);
91 stereo->setIntrinsics(KL,KR,DistL,DistR);
93 this->useBestDisp=
true;
94 this->uniquenessRatio=15;
95 this->speckleWindowSize=50;
96 this->speckleRange=16;
97 this->SADWindowSize=7;
99 this->preFilterCap=63;
100 this->disp12MaxDiff=0;
102 this->numberOfDisparities = 96;
105 bool skipBLF = rf.check(
"skipBLF");
107 this->doBLF =
false;}
109 cout <<
" Bilateral filter set to " << doBLF << endl;
110 this->sigmaColorBLF = 10.0;
111 this->sigmaSpaceBLF = 10.0;
113 this->HL_root=Mat::zeros(4,4,CV_64F);
114 this->HR_root=Mat::zeros(4,4,CV_64F);
118 Mat KL=this->stereo->getKleft();
119 Mat KR=this->stereo->getKright();
120 Mat zeroDist=Mat::zeros(1,8,CV_64FC1);
121 this->stereo->setIntrinsics(KL,KR,zeroDist,zeroDist);
128 utils=
new Utilities();
129 utils->initSIFT_GPU();
133 optionHead.put(
"device",
"remote_controlboard");
134 optionHead.put(
"remote",
"/"+robot+
"/head");
135 optionHead.put(
"local",sname+
"/headClient");
136 if (headCtrl.open(optionHead))
138 headCtrl.view(iencs);
139 iencs->getAxes(&nHeadAxes);
143 cout<<
"Devices not available"<<endl;
148 optionGaze.put(
"device",
"gazecontrollerclient");
149 optionGaze.put(
"remote",
"/iKinGazeCtrl");
150 optionGaze.put(
"local",sname+
"/gazeClient");
151 if (gazeCtrl.open(optionGaze))
152 gazeCtrl.view(igaze);
155 cout<<
"Devices not available"<<endl;
160 if (!R0.empty() && !T0.empty())
162 stereo->setRotation(R0,0);
163 stereo->setTranslation(T0,0);
167 cout <<
"No local calibration file found in " << camCalibFile <<
" ... Using Kinematics and Running SFM once." << endl;
168 updateViaGazeCtrl(
true);
169 R0=this->stereo->getRotation();
170 T0=this->stereo->getTranslation();
174 updateViaGazeCtrl(
false);
181 void SFM::updateViaKinematics(
const yarp::sig::Vector& deyes)
183 double dpan=CTRL_DEG2RAD*deyes[1];
184 double dver=CTRL_DEG2RAD*deyes[2];
186 yarp::sig::Vector rot_l_pan(4,0.0);
188 rot_l_pan[3]=dpan+dver/2.0;
189 Matrix L1=axis2dcm(rot_l_pan);
191 yarp::sig::Vector rot_r_pan(4,0.0);
193 rot_r_pan[3]=dpan-dver/2.0;
194 Matrix R1=axis2dcm(rot_r_pan);
196 Mat RT0=buildRotTras(R0,T0);
197 Matrix H0; convert(RT0,H0);
198 Matrix H=SE3inv(R1)*H0*L1;
200 Mat R=Mat::zeros(3,3,CV_64F);
201 Mat T=Mat::zeros(3,1,CV_64F);
203 for (
int i=0; i<R.rows; i++)
204 for(
int j=0; j<R.cols; j++)
205 R.at<
double>(i,j)=H(i,j);
207 for (
int i=0; i<T.rows; i++)
208 T.at<
double>(i,0)=H(i,3);
210 this->stereo->setRotation(R,0);
211 this->stereo->setTranslation(T,0);
216 void SFM::updateViaGazeCtrl(
const bool update)
218 Matrix L1=getCameraHGazeCtrl(LEFT);
219 Matrix R1=getCameraHGazeCtrl(RIGHT);
221 Matrix RT=SE3inv(R1)*L1;
223 Mat R=Mat::zeros(3,3,CV_64F);
224 Mat T=Mat::zeros(3,1,CV_64F);
226 for (
int i=0; i<R.rows; i++)
227 for(
int j=0; j<R.cols; j++)
228 R.at<
double>(i,j)=RT(i,j);
230 for (
int i=0; i<T.rows; i++)
231 T.at<
double>(i,0)=RT(i,3);
235 stereo->setRotation(R,0);
236 stereo->setTranslation(T,0);
239 stereo->setExpectedPosition(R,T);
244 bool SFM::interruptModule()
246 leftImgPort.interrupt();
247 rightImgPort.interrupt();
249 handlerPort.interrupt();
250 outMatch.interrupt();
251 worldCartPort.interrupt();
252 worldCylPort.interrupt();
254 outLeftRectImgPort.interrupt();
255 outRightRectImgPort.interrupt();
265 rightImgPort.close();
269 worldCartPort.close();
270 worldCylPort.close();
272 outLeftRectImgPort.close();
273 outRightRectImgPort.close();
289 bool SFM::updateModule()
291 ImageOf<PixelRgb> *yarp_imgL=leftImgPort.read(
true);
292 ImageOf<PixelRgb> *yarp_imgR=rightImgPort.read(
true);
294 Stamp stamp_left, stamp_right;
295 leftImgPort.getEnvelope(stamp_left);
296 rightImgPort.getEnvelope(stamp_right);
298 if ((yarp_imgL==NULL) || (yarp_imgR==NULL))
302 iencs->getEncoder(nHeadAxes-3,&eyes[0]);
303 iencs->getEncoder(nHeadAxes-2,&eyes[1]);
304 iencs->getEncoder(nHeadAxes-1,&eyes[2]);
306 updateViaKinematics(eyes-eyes0);
307 updateViaGazeCtrl(
false);
309 leftMat=toCvMat(*yarp_imgL);
310 rightMat=toCvMat(*yarp_imgR);
314 this->numberOfDisparities=(leftMat.size().width<=320)?96:128;
318 getCameraHGazeCtrl(LEFT);
319 getCameraHGazeCtrl(RIGHT);
321 this->stereo->setImages(leftMat,rightMat);
323 mutexRecalibration.lock();
327 utils->extractMatch_GPU(leftMat,rightMat);
328 vector<Point2f> leftM,rightM;
329 utils->getMatches(leftM,rightM);
331 this->stereo->setMatches(leftM,rightM);
334 this->stereo->findMatch(
false);
336 this->stereo->estimateEssential();
337 bool ok=this->stereo->essentialDecomposition();
344 cv_calibEndEvent.notify_all();
348 if (++numberOfTrials>5)
352 cv_calibEndEvent.notify_all();
356 mutexRecalibration.unlock();
359 this->stereo->computeDisparity(this->useBestDisp,this->uniquenessRatio,this->speckleWindowSize,
360 this->speckleRange,this->numberOfDisparities,this->SADWindowSize,
361 this->minDisparity,this->preFilterCap,this->disp12MaxDiff);
364 if (outLeftRectImgPort.getOutputCount()>0)
366 Mat rectLeft = this->stereo->getLRectified();
368 ImageOf<PixelRgb>& rectLeftImage = outLeftRectImgPort.prepare();
369 rectLeftImage.resize(rectLeft.cols,rectLeft.rows);
371 Mat rectLeftImageMat=toCvMat(rectLeftImage);
372 rectLeft.copyTo(rectLeftImageMat);
374 outLeftRectImgPort.setEnvelope(stamp_left);
375 outLeftRectImgPort.write();
378 if (outRightRectImgPort.getOutputCount()>0)
380 Mat rectRight = this->stereo->getRRectified();
382 ImageOf<PixelRgb>& rectRightImage = outRightRectImgPort.prepare();
383 rectRightImage.resize(rectRight.cols,rectRight.rows);
385 Mat rectRightImageMat=toCvMat(rectRightImage);
386 rectRight.copyTo(rectRightImageMat);
388 outRightRectImgPort.setEnvelope(stamp_right);
389 outRightRectImgPort.write();
392 if (outMatch.getOutputCount()>0)
394 Mat matches=this->stereo->drawMatches();
395 cvtColor(matches,matches,CV_BGR2RGB);
396 ImageOf<PixelBgr>& imgMatch=outMatch.prepare();
397 imgMatch.resize(matches.cols,matches.rows);
398 matches.copyTo(toCvMat(imgMatch));
402 if (outDisp.getOutputCount()>0)
407 outputDm = stereo->getDisparity();
409 if (!outputDm.empty())
416 ImageOf<PixelMono> &outim = outDisp.prepare();
422 outimMat = outputDfiltm;
429 outim = fromCvMat<PixelMono>(outimMat);
434 ImageOf<PixelRgbFloat>& outcart=worldCartPort.prepare();
435 ImageOf<PixelRgbFloat>& outcyl=worldCylPort.prepare();
437 outcart.resize(leftMat.size().width,leftMat.size().height);
438 outcyl.resize(leftMat.size().width,leftMat.size().height);
440 fillWorld3D(outcart,outcyl);
442 worldCartPort.write();
443 worldCylPort.write();
450 double SFM::getPeriod()
459 bool SFM::loadExtrinsics(yarp::os::ResourceFinder& rf, Mat& Ro, Mat& To, yarp::sig::Vector& eyes)
461 Bottle extrinsics=rf.findGroup(
"STEREO_DISPARITY");
464 if (Bottle *bEyes=extrinsics.find(
"eyes").asList())
466 size_t sz=std::min(eyes.length(),(
size_t)bEyes->size());
467 for (
size_t i=0; i<sz; i++)
468 eyes[i]=bEyes->get(i).asFloat64();
471 cout<<
"read eyes configuration = ("<<eyes.toString(3,3)<<
")"<<endl;
473 if (Bottle *pXo=extrinsics.find(
"HN").asList())
475 Ro=Mat::zeros(3,3,CV_64FC1);
476 To=Mat::zeros(3,1,CV_64FC1);
477 for (
int i=0; i<(pXo->size()-4); i+=4)
479 Ro.at<
double>(i/4,0)=pXo->get(i).asFloat64();
480 Ro.at<
double>(i/4,1)=pXo->get(i+1).asFloat64();
481 Ro.at<
double>(i/4,2)=pXo->get(i+2).asFloat64();
482 To.at<
double>(i/4,0)=pXo->get(i+3).asFloat64();
493 bool SFM::loadIntrinsics(yarp::os::ResourceFinder &rf, Mat &KL, Mat &KR, Mat &DistL,
496 Bottle left=rf.findGroup(
"CAMERA_CALIBRATION_LEFT");
497 if(!left.check(
"fx") || !left.check(
"fy") || !left.check(
"cx") || !left.check(
"cy"))
500 double fx=left.find(
"fx").asFloat64();
501 double fy=left.find(
"fy").asFloat64();
503 double cx=left.find(
"cx").asFloat64();
504 double cy=left.find(
"cy").asFloat64();
506 double k1=left.check(
"k1",Value(0)).asFloat64();
507 double k2=left.check(
"k2",Value(0)).asFloat64();
509 double p1=left.check(
"p1",Value(0)).asFloat64();
510 double p2=left.check(
"p2",Value(0)).asFloat64();
512 DistL=Mat::zeros(1,8,CV_64FC1);
513 DistL.at<
double>(0,0)=k1;
514 DistL.at<
double>(0,1)=k2;
515 DistL.at<
double>(0,2)=p1;
516 DistL.at<
double>(0,3)=p2;
518 KL=Mat::eye(3,3,CV_64FC1);
519 KL.at<
double>(0,0)=fx;
520 KL.at<
double>(0,2)=cx;
521 KL.at<
double>(1,1)=fy;
522 KL.at<
double>(1,2)=cy;
524 Bottle right=rf.findGroup(
"CAMERA_CALIBRATION_RIGHT");
525 if(!right.check(
"fx") || !right.check(
"fy") || !right.check(
"cx") || !right.check(
"cy"))
528 fx=right.find(
"fx").asFloat64();
529 fy=right.find(
"fy").asFloat64();
531 cx=right.find(
"cx").asFloat64();
532 cy=right.find(
"cy").asFloat64();
534 k1=right.check(
"k1",Value(0)).asFloat64();
535 k2=right.check(
"k2",Value(0)).asFloat64();
537 p1=right.check(
"p1",Value(0)).asFloat64();
538 p2=right.check(
"p2",Value(0)).asFloat64();
540 DistR=Mat::zeros(1,8,CV_64FC1);
541 DistR.at<
double>(0,0)=k1;
542 DistR.at<
double>(0,1)=k2;
543 DistR.at<
double>(0,2)=p1;
544 DistR.at<
double>(0,3)=p2;
546 KR=Mat::eye(3,3,CV_64FC1);
547 KR.at<
double>(0,0)=fx;
548 KR.at<
double>(0,2)=cx;
549 KR.at<
double>(1,1)=fy;
550 KR.at<
double>(1,2)=cy;
557 bool SFM::updateExtrinsics(Mat& Rot, Mat& Tr, yarp::sig::Vector& eyes,
558 const string& groupname)
561 out.open(camCalibFile.c_str());
565 out <<
"["+groupname+
"]" << endl;
566 out <<
"eyes (" << eyes.toString() <<
")" << endl;
567 out <<
"HN (" << Rot.at<
double>(0,0) <<
" " << Rot.at<
double>(0,1) <<
" " << Rot.at<
double>(0,2) <<
" " << Tr.at<
double>(0,0) <<
" "
568 << Rot.at<
double>(1,0) <<
" " << Rot.at<
double>(1,1) <<
" " << Rot.at<
double>(1,2) <<
" " << Tr.at<
double>(1,0) <<
" "
569 << Rot.at<
double>(2,0) <<
" " << Rot.at<
double>(2,1) <<
" " << Rot.at<
double>(2,2) <<
" " << Tr.at<
double>(2,0) <<
" "
570 << 0.0 <<
" " << 0.0 <<
" " << 0.0 <<
" " << 1.0 <<
")"
581 void SFM::setDispParameters(
bool _useBestDisp,
int _uniquenessRatio,
582 int _speckleWindowSize,
int _speckleRange,
583 int _numberOfDisparities,
int _SADWindowSize,
584 int _minDisparity,
int _preFilterCap,
int _disp12MaxDiff)
586 this->mutexDisp.lock();
587 this->useBestDisp=_useBestDisp;
588 this->uniquenessRatio=_uniquenessRatio;
589 this->speckleWindowSize=_speckleWindowSize;
590 this->speckleRange=_speckleRange;
591 this->numberOfDisparities=_numberOfDisparities;
592 this->SADWindowSize=_SADWindowSize;
593 this->minDisparity=_minDisparity;
594 this->preFilterCap=_preFilterCap;
595 this->disp12MaxDiff=_disp12MaxDiff;
596 this->mutexDisp.unlock();
602 Point3f SFM::get3DPointsAndDisp(
int u,
int v,
int& uR,
int& vR,
const string &drive)
604 Point3f point(0.0f,0.0f,0.0f);
605 if ((drive!=
"RIGHT") && (drive!=
"LEFT") && (drive!=
"ROOT"))
608 lock_guard<mutex> lg(mutexDisp);
611 const Mat& Mapper=this->stereo->getMapperL();
615 float usign=Mapper.ptr<
float>(v)[2*u];
616 float vsign=Mapper.ptr<
float>(v)[2*u+1];
621 const Mat& disp16m=this->stereo->getDisparity16();
622 if (disp16m.empty() || (u<0) || (u>=disp16m.cols) || (v<0) || (v>=disp16m.rows))
625 const Mat& Q=this->stereo->getQ();
626 CvScalar scal=cvGet2D(&disp16m,v,u);
627 double disparity=scal.val[0]/16.0;
632 Point2f orig=this->stereo->fromRectifiedToOriginal(uR,vR,RIGHT);
636 float w=(float)(disparity*Q.at<
double>(3,2)+Q.at<
double>(3,3));
637 point.x=(float)((usign+1)*Q.at<
double>(0,0)+Q.at<
double>(0,3));
638 point.y=(float)((vsign+1)*Q.at<
double>(1,1)+Q.at<
double>(1,3));
639 point.z=(float)Q.at<
double>(2,3);
646 if ((point.z>10.0f) || (point.z<0.0f))
651 const Mat& RLrect=this->stereo->getRLrect().t();
652 Mat Tfake=Mat::zeros(0,3,CV_64F);
654 P.at<
double>(0,0)=point.x;
655 P.at<
double>(1,0)=point.y;
656 P.at<
double>(2,0)=point.z;
657 P.at<
double>(3,0)=1.0;
659 Mat Hrect=buildRotTras(RLrect,Tfake);
661 point.x=(float)(P.at<
double>(0,0)/P.at<
double>(3,0));
662 point.y=(float)(P.at<
double>(1,0)/P.at<
double>(3,0));
663 point.z=(float)(P.at<
double>(2,0)/P.at<
double>(3,0));
665 else if (drive==
"LEFT")
668 P.at<
double>(0,0)=point.x;
669 P.at<
double>(1,0)=point.y;
670 P.at<
double>(2,0)=point.z;
672 P=this->stereo->getRLrect().t()*P;
673 point.x=(float)P.at<
double>(0,0);
674 point.y=(float)P.at<
double>(1,0);
675 point.z=(float)P.at<
double>(2,0);
677 else if (drive==
"RIGHT")
679 const Mat& Rright=this->stereo->getRotation();
680 const Mat& Tright=this->stereo->getTranslation();
681 const Mat& RRright=this->stereo->getRRrect().t();
682 Mat TRright=Mat::zeros(0,3,CV_64F);
684 Mat HRL=buildRotTras(Rright,Tright);
685 Mat Hrect=buildRotTras(RRright,TRright);
688 P.at<
double>(0,0)=point.x;
689 P.at<
double>(1,0)=point.y;
690 P.at<
double>(2,0)=point.z;
691 P.at<
double>(3,0)=1.0;
694 point.x=(float)(P.at<
double>(0,0)/P.at<
double>(3,0));
695 point.y=(float)(P.at<
double>(1,0)/P.at<
double>(3,0));
696 point.z=(float)(P.at<
double>(2,0)/P.at<
double>(3,0));
704 Point3f SFM::get3DPoints(
int u,
int v,
const string &drive)
706 Point3f point(0.0f,0.0f,0.0f);
707 if ((drive!=
"RIGHT") && (drive!=
"LEFT") && (drive!=
"ROOT"))
710 lock_guard<mutex> lg(mutexDisp);
713 const Mat& Mapper=this->stereo->getMapperL();
717 float usign=Mapper.ptr<
float>(v)[2*u];
718 float vsign=Mapper.ptr<
float>(v)[2*u+1];
723 const Mat& disp16m=this->stereo->getDisparity16();
724 if (disp16m.empty() || (u<0) || (u>=disp16m.cols) || (v<0) || (v>=disp16m.rows))
727 const Mat& Q=this->stereo->getQ();
728 CvScalar scal=cvGet2D(&disp16m,v,u);
729 double disparity=scal.val[0]/16.0;
730 float w=(float)(disparity*Q.at<
double>(3,2)+Q.at<
double>(3,3));
731 point.x=(float)((usign+1)*Q.at<
double>(0,0)+Q.at<
double>(0,3));
732 point.y=(float)((vsign+1)*Q.at<
double>(1,1)+Q.at<
double>(1,3));
733 point.z=(float)Q.at<
double>(2,3);
740 if ((point.z>10.0f) || (point.z<0.0f))
745 const Mat& RLrect=this->stereo->getRLrect().t();
746 Mat Tfake=Mat::zeros(0,3,CV_64F);
748 P.at<
double>(0,0)=point.x;
749 P.at<
double>(1,0)=point.y;
750 P.at<
double>(2,0)=point.z;
751 P.at<
double>(3,0)=1.0;
753 Mat Hrect=buildRotTras(RLrect,Tfake);
755 point.x=(float)(P.at<
double>(0,0)/P.at<
double>(3,0));
756 point.y=(float)(P.at<
double>(1,0)/P.at<
double>(3,0));
757 point.z=(float)(P.at<
double>(2,0)/P.at<
double>(3,0));
759 else if (drive==
"LEFT")
762 P.at<
double>(0,0)=point.x;
763 P.at<
double>(1,0)=point.y;
764 P.at<
double>(2,0)=point.z;
766 P=this->stereo->getRLrect().t()*P;
767 point.x=(float)P.at<
double>(0,0);
768 point.y=(float)P.at<
double>(1,0);
769 point.z=(float)P.at<
double>(2,0);
771 else if (drive==
"RIGHT")
773 const Mat& Rright=this->stereo->getRotation();
774 const Mat& Tright=this->stereo->getTranslation();
775 const Mat& RRright=this->stereo->getRRrect().t();
776 Mat TRright=Mat::zeros(0,3,CV_64F);
778 Mat HRL=buildRotTras(Rright,Tright);
779 Mat Hrect=buildRotTras(RRright,TRright);
782 P.at<
double>(0,0)=point.x;
783 P.at<
double>(1,0)=point.y;
784 P.at<
double>(2,0)=point.z;
785 P.at<
double>(3,0)=1.0;
788 point.x=(float)(P.at<
double>(0,0)/P.at<
double>(3,0));
789 point.y=(float)(P.at<
double>(1,0)/P.at<
double>(3,0));
790 point.z=(float)(P.at<
double>(2,0)/P.at<
double>(3,0));
798 Point3f SFM::get3DPointMatch(
double u1,
double v1,
double u2,
double v2,
801 Point3f point(0.0f,0.0f,0.0f);
802 if ((drive!=
"RIGHT") && (drive!=
"LEFT") && (drive!=
"ROOT"))
805 lock_guard<mutex> lg(mutexDisp);
807 const Mat& MapperL=this->stereo->getMapperL();
808 const Mat& MapperR=this->stereo->getMapperR();
809 if (MapperL.empty() || MapperR.empty())
812 if ((cvRound(u1)<0) || (cvRound(u1)>=MapperL.cols) || (cvRound(v1)<0) || (cvRound(v1)>=MapperL.rows) ||
813 (cvRound(u2)<0) || (cvRound(u2)>=MapperL.cols) || (cvRound(v2)<0) || (cvRound(v2)>=MapperL.rows))
816 float urect1=MapperL.ptr<
float>(cvRound(v1))[2*cvRound(u1)];
817 float vrect1=MapperL.ptr<
float>(cvRound(v1))[2*cvRound(u1)+1];
819 float urect2=MapperR.ptr<
float>(cvRound(v2))[2*cvRound(u2)];
820 float vrect2=MapperR.ptr<
float>(cvRound(v2))[2*cvRound(u2)+1];
822 const Mat& Q=this->stereo->getQ();
823 double disparity=urect1-urect2;
824 float w=(float)(disparity*Q.at<
double>(3,2)+Q.at<
double>(3,3));
825 point.x=(float)((urect1+1)*Q.at<
double>(0,0)+Q.at<
double>(0,3));
826 point.y=(float)((vrect1+1)*Q.at<
double>(1,1)+Q.at<
double>(1,3));
827 point.z=(float)Q.at<
double>(2,3);
835 const Mat& RLrect=this->stereo->getRLrect().t();
836 Mat Tfake=Mat::zeros(0,3,CV_64F);
838 P.at<
double>(0,0)=point.x;
839 P.at<
double>(1,0)=point.y;
840 P.at<
double>(2,0)=point.z;
841 P.at<
double>(3,0)=1.0;
843 Mat Hrect=buildRotTras(RLrect,Tfake);
845 point.x=(float)(P.at<
double>(0,0)/P.at<
double>(3,0));
846 point.y=(float)(P.at<
double>(1,0)/P.at<
double>(3,0));
847 point.z=(float)(P.at<
double>(2,0)/P.at<
double>(3,0));
849 else if (drive==
"LEFT")
852 P.at<
double>(0,0)=point.x;
853 P.at<
double>(1,0)=point.y;
854 P.at<
double>(2,0)=point.z;
856 P=this->stereo->getRLrect().t()*P;
857 point.x=(float)P.at<
double>(0,0);
858 point.y=(float)P.at<
double>(1,0);
859 point.z=(float)P.at<
double>(2,0);
861 else if (drive==
"RIGHT")
863 const Mat& Rright=this->stereo->getRotation();
864 const Mat& Tright=this->stereo->getTranslation();
865 const Mat& RRright=this->stereo->getRRrect().t();
866 Mat TRright=Mat::zeros(0,3,CV_64F);
868 Mat HRL=buildRotTras(Rright,Tright);
869 Mat Hrect=buildRotTras(RRright,TRright);
872 P.at<
double>(0,0)=point.x;
873 P.at<
double>(1,0)=point.y;
874 P.at<
double>(2,0)=point.z;
875 P.at<
double>(3,0)=1.0;
878 point.x=(float)(P.at<
double>(0,0)/P.at<
double>(3,0));
879 point.y=(float)(P.at<
double>(1,0)/P.at<
double>(3,0));
880 point.z=(float)(P.at<
double>(2,0)/P.at<
double>(3,0));
888 Mat SFM::buildRotTras(
const Mat& R,
const Mat& T)
890 Mat A=Mat::eye(4,4,CV_64F);
891 for (
int i=0; i<R.rows; i++)
893 double* Mi=A.ptr<
double>(i);
894 const double* MRi=R.ptr<
double>(i);
895 for (
int j=0; j<R.cols; j++)
899 for (
int i=0; i<T.rows; i++)
901 double* Mi=A.ptr<
double>(i);
902 const double* MRi=T.ptr<
double>(i);
911 Matrix SFM::getCameraHGazeCtrl(
int camera)
913 yarp::sig::Vector x_curr;
914 yarp::sig::Vector o_curr;
917 check=igaze->getLeftEyePose(x_curr, o_curr);
919 check=igaze->getRightEyePose(x_curr, o_curr);
927 Matrix R_curr=axis2dcm(o_curr);
928 Matrix H_curr=R_curr;
929 H_curr.setSubcol(x_curr,0,3);
934 convert(H_curr,HL_root);
937 else if(camera==RIGHT)
940 convert(H_curr,HR_root);
949 void SFM::convert(Matrix& matrix, Mat& mat)
951 mat=cv::Mat(matrix.rows(),matrix.cols(),CV_64FC1);
952 for(
int i=0; i<matrix.rows(); i++)
953 for(
int j=0; j<matrix.cols(); j++)
954 mat.at<
double>(i,j)=matrix(i,j);
959 void SFM::convert(Mat& mat, Matrix& matrix)
961 matrix.resize(mat.rows,mat.cols);
962 for(
int i=0; i<mat.rows; i++)
963 for(
int j=0; j<mat.cols; j++)
964 matrix(i,j)=mat.at<
double>(i,j);
969 bool SFM::respond(
const Bottle& command, Bottle& reply)
971 if(command.size()==0)
974 if (command.get(0).asString()==
"quit") {
975 cout <<
"closing..." << endl;
979 if (command.get(0).asString()==
"help") {
980 reply.addVocab32(
"many");
981 reply.addString(
"Available commands are:");
982 reply.addString(
"- [calibrate]: It recomputes the camera positions once.");
983 reply.addString(
"- [save]: It saves the current camera positions and uses it when the module starts.");
984 reply.addString(
"- [getH]: It returns the calibrated stereo matrix.");
985 reply.addString(
"- [setNumDisp NumOfDisparities]: It sets the expected number of disparity (in pixel). Values must be divisible by 32. ");
986 reply.addString(
"- [Point x y]: Given the pixel coordinate x,y in the Left image the response is the 3D Point: X Y Z computed using the depth map wrt the LEFT eye.");
987 reply.addString(
"- [x y]: Given the pixel coordinate x,y in the Left image the response is the 3D Point: X Y Z ur vr computed using the depth map wrt the the ROOT reference system.(ur vr) is the corresponding pixel in the Right image. ");
988 reply.addString(
"- [Left x y]: Given the pixel coordinate x,y in the Left image the response is the 3D Point: X Y Z computed using the depth map wrt the LEFT eye. Points with non valid disparity (i.e. occlusions) are handled with the value (0.0,0.0,0.0). ");
989 reply.addString(
"- [Right x y]: Given the pixel coordinate x,y in the Left image the response is the 3D Point: X Y Z computed using the depth map wrt the RIGHT eye. Points with non valid disparity (i.e. occlusions) are handled with the value (0.0,0.0,0.0).");
990 reply.addString(
"- [Root x y]: Given the pixel coordinate x,y in the Left image the response is the 3D Point: X Y Z computed using the depth map wrt the ROOT reference system. Points with non valid disparity (i.e. occlusions) are handled with the value (0.0,0.0,0.0).");
991 reply.addString(
"- [Rect tlx tly w h step]: Given the pixels in the rectangle defined by {(tlx,tly) (tlx+w,tly+h)} (parsed by columns), the response contains the corresponding 3D points in the ROOT frame. The optional parameter step defines the sampling quantum; by default step=1.");
992 reply.addString(
"- [Points u_1 v_1 ... u_n v_n]: Given a list of n pixels, the response contains the corresponding 3D points in the ROOT frame.");
993 reply.addString(
"- [Flood3D x y dist]: Perform 3D flood-fill on the seed point (x,y), returning the following info: [u_1 v_1 x_1 y_1 z_1 ...]. The optional parameter dist expressed in meters regulates the fill (by default = 0.004).");
994 reply.addString(
"- [uL_1 vL_1 uR_1 vR_1 ... uL_n vL_n uR_n vR_n]: Given n quadruples uL_i vL_i uR_i vR_i, where uL_i vL_i are the pixel coordinates in the Left image and uR_i vR_i are the coordinates of the matched pixel in the Right image, the response is a set of 3D points (X1 Y1 Z1 ... Xn Yn Zn) wrt the ROOT reference system.");
995 reply.addString(
"- [cart2stereo X Y Z]: Given a world point X Y Z wrt to ROOT reference frame the response is the projection (uL vL uR vR) in the Left and Right images.");
996 reply.addString(
"- [doBLF flag]: activate Bilateral filter for flag = true, and skip it for flag = false.");
997 reply.addString(
"- [bilatfilt sigmaColor sigmaSpace]: Set the parameters for the bilateral filer (default sigmaColor = 10.0, sigmaSpace = 10.0 .");
998 reply.addString(
"For more details on the commands, check the module's documentation");
1002 if (command.get(0).asString()==
"calibrate")
1004 mutexRecalibration.lock();
1007 mutexRecalibration.unlock();
1009 unique_lock<mutex> lck(mtx_calibEndEvent);
1010 cv_calibEndEvent.wait(lck);
1014 R0=this->stereo->getRotation();
1015 T0=this->stereo->getTranslation();
1018 reply.addString(
"ACK");
1021 reply.addString(
"Calibration failed after 5 trials.. Please show a non planar scene.");
1026 if (command.get(0).asString()==
"save")
1028 updateExtrinsics(R0,T0,eyes0,
"STEREO_DISPARITY");
1029 reply.addString(
"ACK");
1033 if (command.get(0).asString()==
"getH")
1035 Mat RT0=buildRotTras(R0,T0);
1036 Matrix H0; convert(RT0,H0);
1042 if (command.get(0).asString()==
"setNumDisp")
1044 int dispNum=command.get(1).asInt32();
1047 this->numberOfDisparities=dispNum;
1048 this->setDispParameters(useBestDisp,uniquenessRatio,speckleWindowSize,speckleRange,numberOfDisparities,SADWindowSize,minDisparity,preFilterCap,disp12MaxDiff);
1049 reply.addString(
"ACK");
1054 reply.addString(
"Num Disparity must be divisible by 32");
1059 if (command.get(0).asString()==
"setMinDisp")
1061 int dispNum=command.get(1).asInt32();
1062 this->minDisparity=dispNum;
1063 this->setDispParameters(useBestDisp,uniquenessRatio,speckleWindowSize,
1064 speckleRange,numberOfDisparities,SADWindowSize,
1065 minDisparity,preFilterCap,disp12MaxDiff);
1066 reply.addString(
"ACK");
1070 if (command.get(0).asString()==
"set" && command.size()==10)
1072 bool bestDisp=command.get(1).asInt32() ? true :
false;
1073 int uniquenessRatio=command.get(2).asInt32();
1074 int speckleWindowSize=command.get(3).asInt32();
1075 int speckleRange=command.get(4).asInt32();
1076 int numberOfDisparities=command.get(5).asInt32();
1077 int SADWindowSize=command.get(6).asInt32();
1078 int minDisparity=command.get(7).asInt32();
1079 int preFilterCap=command.get(8).asInt32();
1080 int disp12MaxDiff=command.get(9).asInt32();
1082 this->setDispParameters(bestDisp,uniquenessRatio,speckleWindowSize,
1083 speckleRange,numberOfDisparities,SADWindowSize,
1084 minDisparity,preFilterCap,disp12MaxDiff);
1085 reply.addString(
"ACK");
1087 else if (command.get(0).asString()==
"Point" || command.get(0).asString()==
"Left" )
1089 int u = command.get(1).asInt32();
1090 int v = command.get(2).asInt32();
1091 Point3f point = this->get3DPoints(u,v);
1092 reply.addFloat64(point.x);
1093 reply.addFloat64(point.y);
1094 reply.addFloat64(point.z);
1096 else if (!command.get(0).isString() && command.size()==2)
1098 int u = command.get(0).asInt32();
1099 int v = command.get(1).asInt32();
1101 Point3f point = this->get3DPointsAndDisp(u,v,uR,vR,
"ROOT");
1102 reply.addFloat64(point.x);
1103 reply.addFloat64(point.y);
1104 reply.addFloat64(point.z);
1108 else if (command.get(0).asString()==
"Right")
1110 int u = command.get(1).asInt32();
1111 int v = command.get(2).asInt32();
1112 Point3f point = this->get3DPoints(u,v,
"RIGHT");
1113 reply.addFloat64(point.x);
1114 reply.addFloat64(point.y);
1115 reply.addFloat64(point.z);
1117 else if (command.get(0).asString()==
"Root")
1119 int u = command.get(1).asInt32();
1120 int v = command.get(2).asInt32();
1121 Point3f point = this->get3DPoints(u,v,
"ROOT");
1122 reply.addFloat64(point.x);
1123 reply.addFloat64(point.y);
1124 reply.addFloat64(point.z);
1126 else if (command.get(0).asString()==
"Rect")
1128 int tl_u = command.get(1).asInt32();
1129 int tl_v = command.get(2).asInt32();
1130 int br_u = tl_u+command.get(3).asInt32();
1131 int br_v = tl_v+command.get(4).asInt32();
1134 if (command.size()>=6)
1135 step=command.get(5).asInt32();
1137 for (
int u=tl_u; u<br_u; u+=step)
1139 for (
int v=tl_v; v<br_v; v+=step)
1141 Point3f point=this->get3DPoints(u,v,
"ROOT");
1142 reply.addFloat64(point.x);
1143 reply.addFloat64(point.y);
1144 reply.addFloat64(point.z);
1148 else if (command.get(0).asString()==
"Points")
1150 for (
int cnt=1; cnt<command.size()-1; cnt+=2)
1152 int u=command.get(cnt).asInt32();
1153 int v=command.get(cnt+1).asInt32();
1154 Point3f point=this->get3DPoints(u,v,
"ROOT");
1155 reply.addFloat64(point.x);
1156 reply.addFloat64(point.y);
1157 reply.addFloat64(point.z);
1160 else if (command.get(0).asString()==
"Flood3D")
1162 cv::Point seed(command.get(1).asInt32(),
1163 command.get(2).asInt32());
1166 if (command.size()>=4)
1167 dist=command.get(3).asFloat64();
1169 Point3f p=get3DPoints(seed.x,seed.y,
"ROOT");
1170 if (cv::norm(p)>0.0)
1172 reply.addInt32(seed.x);
1173 reply.addInt32(seed.y);
1174 reply.addFloat64(p.x);
1175 reply.addFloat64(p.y);
1176 reply.addFloat64(p.z);
1179 visited.insert(seed.x*outputDm.cols+seed.y);
1181 floodFill(seed,p,dist,visited,reply);
1184 reply.addString(
"NACK");
1186 else if (command.get(0).asString()==
"cart2stereo")
1188 double x = command.get(1).asFloat64();
1189 double y = command.get(2).asFloat64();
1190 double z = command.get(3).asFloat64();
1192 Point2f pointL = this->projectPoint(
"left",x,y,z);
1193 Point2f pointR = this->projectPoint(
"right",x,y,z);
1195 reply.addFloat64(pointL.x);
1196 reply.addFloat64(pointL.y);
1197 reply.addFloat64(pointR.x);
1198 reply.addFloat64(pointR.y);
1200 else if (command.get(0).asString()==
"bilatfilt" && command.size()==3)
1204 reply.addString(
"Bilateral filter activated.");
1206 sigmaColorBLF = command.get(1).asFloat64();
1207 sigmaSpaceBLF = command.get(2).asFloat64();
1208 reply.addString(
"BLF sigmaColor ");
1209 reply.addFloat64(sigmaColorBLF);
1210 reply.addString(
"BLF sigmaSpace ");
1211 reply.addFloat64(sigmaSpaceBLF);
1213 else if (command.get(0).asString()==
"doBLF")
1215 bool onoffBLF = command.get(1).asBool();
1216 if (onoffBLF ==
false ){
1219 reply.addString(
"Bilateral Filter OFF");
1221 reply.addString(
"Bilateral Filter already OFF");
1226 reply.addString(
"Bilateral Filter Already Running");
1229 reply.addString(
"Bilateral Filter ON");
1232 reply.addFloat64(sigmaColorBLF);
1233 reply.addFloat64(sigmaSpaceBLF);
1235 else if(command.size()>0 && command.size()%4==0)
1237 for (
int i=0; i<command.size(); i+=4)
1239 double ul = command.get(i).asFloat64();
1240 double vl = command.get(i+1).asFloat64();
1241 double ur = command.get(i+2).asFloat64();
1242 double vr = command.get(i+3).asFloat64();
1244 Point3f point= this->get3DPointMatch(ul,vl,ur,vr,
"ROOT");
1245 reply.addFloat64(point.x);
1246 reply.addFloat64(point.y);
1247 reply.addFloat64(point.z);
1251 reply.addString(
"NACK");
1258 Point2f SFM::projectPoint(
const string &camera,
double x,
double y,
double z)
1265 vector<Point3f> points3D;
1267 points3D.push_back(point3D);
1269 vector<Point2f> response;
1274 response=this->stereo->projectPoints3D(
"left",points3D,HL_root);
1276 response=this->stereo->projectPoints3D(
"right",points3D,HL_root);
1284 void SFM::fillWorld3D(ImageOf<PixelRgbFloat> &worldCartImg,
1285 ImageOf<PixelRgbFloat> &worldCylImg)
1288 const Mat& Mapper=this->stereo->getMapperL();
1289 const Mat& disp16m=this->stereo->getDisparity16();
1290 const Mat& Q=this->stereo->getQ();
1291 const Mat& RLrect=this->stereo->getRLrect().t();
1294 worldCartImg.zero(); worldCylImg.zero();
1295 if (Mapper.empty() || disp16m.empty() ||
1296 (worldCartImg.width()!=worldCylImg.width()) ||
1297 (worldCartImg.height()!=worldCylImg.height()))
1300 Mat Tfake=Mat::zeros(0,3,CV_64F);
1301 Mat Hrect=buildRotTras(RLrect,Tfake);
1302 Hrect=HL_root*Hrect;
1304 Mat P(4,1,CV_64FC1);
1305 P.at<
double>(3,0)=1.0;
1306 double &x=P.at<
double>(0,0);
1307 double &y=P.at<
double>(1,0);
1308 double &z=P.at<
double>(2,0);
1310 for (
int v=0; v<worldCartImg.height(); v++)
1312 for (
int u=0; u<worldCartImg.width(); u++)
1314 float usign=Mapper.ptr<
float>(v)[2*u];
1315 float vsign=Mapper.ptr<
float>(v)[2*u+1];
1317 int u_=cvRound(usign);
int v_=cvRound(vsign);
1318 if ((u_<0) || (u_>=disp16m.cols) || (v_<0) || (v_>=disp16m.rows))
1321 x=(usign+1)*Q.at<
double>(0,0)+Q.at<
double>(0,3);
1322 y=(vsign+1)*Q.at<
double>(1,1)+Q.at<
double>(1,3);
1323 z=Q.at<
double>(2,3);
1325 cv::Scalar scal(disp16m.at<
long>(v_, u_));
1327 double disparity=scal.val[0]/16.0;
1328 double w=disparity*Q.at<
double>(3,2)+Q.at<
double>(3,3);
1331 if ((z>10.0) || (z<0.0))
1336 PixelRgbFloat &pxCart=worldCartImg.pixel(u,v);
1341 PixelRgbFloat &pxCyl=worldCylImg.pixel(u,v);
1342 pxCyl.r=(float)sqrt(x*x+y*y);
1343 pxCyl.g=(float)atan2(y,x);
1351 void SFM::floodFill(
const Point &seed,
const Point3f &p0,
const double dist,
1352 set<int> &visited, Bottle &res)
1354 for (
int x=seed.x-1; x<=seed.x+1; x++)
1356 for (
int y=seed.y-1; y<=seed.y+1; y++)
1358 if ((x<0)||(y<0)||(x>outputDm.cols)||(y>outputDm.rows))
1361 int idx=x*outputDm.cols+y;
1362 set<int>::iterator el=visited.find(idx);
1363 if (el==visited.end())
1365 visited.insert(idx);
1366 Point3f p=get3DPoints(x,y,
"ROOT");
1367 if ((cv::norm(p)>0.0) && (cv::norm(p-p0)<=dist))
1371 res.addFloat64(p.x);
1372 res.addFloat64(p.y);
1373 res.addFloat64(p.z);
1375 floodFill(Point(x,y),p,dist,visited,res);
1384 int main(
int argc,
char *argv[])
1388 if (!yarp.checkNetwork())
1392 rf.setDefaultConfigFile(
"icubEyes.ini");
1393 rf.setDefaultContext(
"cameraCalibration");
1394 rf.configure(argc,argv);
1398 return mod.runModule(rf);
The base class defining stereo camera.
void bilateralFilter(cv::InputArray src, cv::OutputArray dst, double sigmaColor, double sigmaSpace)
Implementation.