stereo-vision
All Data Structures Namespaces Functions Modules Pages
SFM.cpp
1 /*
2  * Copyright (C) 2015 RobotCub Consortium
3  * Author: Sean Ryan Fanello, Giulia Pasquale
4  * email: sean.fanello@iit.it giulia.pasquale@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.txt
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 <cmath>
20 #include <algorithm>
21 #include <yarp/cv/Cv.h>
22 #include <opencv2/core/types.hpp>
23 #include "SFM.h"
24 
25 using namespace yarp::cv;
26 
27 
28 /******************************************************************************/
29 bool SFM::configure(ResourceFinder &rf)
30 {
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();
36 
37  string sname;
38  sname="/"+name;
39  left=sname+left;
40  right=sname+right;
41 
42  string outDispName=rf.check("outDispPort",Value("/disp:o")).asString();
43  string outMatchName=rf.check("outMatchPort",Value("/match:o")).asString();
44 
45  string outLeftRectImgPortName=rf.check("outLeftRectImgPort",Value("/rect_left:o")).asString();
46  string outRightRectImgPortName=rf.check("outRightRectImgPort",Value("/rect_right:o")).asString();
47 
48  ResourceFinder localCalibration;
49  localCalibration.setDefaultContext("cameraCalibration");
50  localCalibration.setDefaultConfigFile(SFMFile.c_str());
51  localCalibration.configure(0,NULL);
52 
53  this->camCalibFile=localCalibration.getHomeContextPath();
54  this->camCalibFile+="/"+SFMFile;
55 
56  outMatchName=sname+outMatchName;
57  outDispName=sname+outDispName;
58 
59  outLeftRectImgPortName=sname+outLeftRectImgPortName;
60  outRightRectImgPortName=sname+outRightRectImgPortName;
61 
62  string rpc_name=sname+"/rpc";
63  string world_name=sname+rf.check("outWorldPort",Value("/world")).asString();
64 
65  int calib=rf.check("useCalibrated",Value(1)).asInt32();
66  bool useCalibrated=(calib!=0);
67 
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");
75  attach(handlerPort);
76 
77  outLeftRectImgPort.open(outLeftRectImgPortName);
78  outRightRectImgPort.open(outRightRectImgPortName);
79 
80  this->stereo = new StereoCamera(true);
81 
82  if (!rf.check("use_sgbm"))
83  stereo->initELAS(rf);
84 
85  Mat KL, KR, DistL, DistR;
86 
87  loadIntrinsics(rf,KL,KR,DistL,DistR);
88  loadExtrinsics(localCalibration,R0,T0,eyes0);
89  eyes.resize(eyes0.length(),0.0);
90 
91  stereo->setIntrinsics(KL,KR,DistL,DistR);
92 
93  this->useBestDisp=true;
94  this->uniquenessRatio=15;
95  this->speckleWindowSize=50;
96  this->speckleRange=16;
97  this->SADWindowSize=7;
98  this->minDisparity=0;
99  this->preFilterCap=63;
100  this->disp12MaxDiff=0;
101 
102  this->numberOfDisparities = 96;
103 
104  this->doBLF = true;
105  bool skipBLF = rf.check("skipBLF");
106  if (skipBLF){
107  this->doBLF = false;}
108  // this->doBLF = rf.check("doBLF",Value(true)).asBool();
109  cout << " Bilateral filter set to " << doBLF << endl;
110  this->sigmaColorBLF = 10.0;
111  this->sigmaSpaceBLF = 10.0;
112 
113  this->HL_root=Mat::zeros(4,4,CV_64F);
114  this->HR_root=Mat::zeros(4,4,CV_64F);
115 
116  if (useCalibrated)
117  {
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);
122  }
123 
124  init=true;
125  numberOfTrials=0;
126 
127 #ifdef USING_GPU
128  utils=new Utilities();
129  utils->initSIFT_GPU();
130 #endif
131 
132  Property optionHead;
133  optionHead.put("device","remote_controlboard");
134  optionHead.put("remote","/"+robot+"/head");
135  optionHead.put("local",sname+"/headClient");
136  if (headCtrl.open(optionHead))
137  {
138  headCtrl.view(iencs);
139  iencs->getAxes(&nHeadAxes);
140  }
141  else
142  {
143  cout<<"Devices not available"<<endl;
144  return false;
145  }
146 
147  Property optionGaze;
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);
153  else
154  {
155  cout<<"Devices not available"<<endl;
156  headCtrl.close();
157  return false;
158  }
159 
160  if (!R0.empty() && !T0.empty())
161  {
162  stereo->setRotation(R0,0);
163  stereo->setTranslation(T0,0);
164  }
165  else
166  {
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();
171  }
172 
173  doSFM=false;
174  updateViaGazeCtrl(false);
175 
176  return true;
177 }
178 
179 
180 /******************************************************************************/
181 void SFM::updateViaKinematics(const yarp::sig::Vector& deyes)
182 {
183  double dpan=CTRL_DEG2RAD*deyes[1];
184  double dver=CTRL_DEG2RAD*deyes[2];
185 
186  yarp::sig::Vector rot_l_pan(4,0.0);
187  rot_l_pan[1]=1.0;
188  rot_l_pan[3]=dpan+dver/2.0;
189  Matrix L1=axis2dcm(rot_l_pan);
190 
191  yarp::sig::Vector rot_r_pan(4,0.0);
192  rot_r_pan[1]=1.0;
193  rot_r_pan[3]=dpan-dver/2.0;
194  Matrix R1=axis2dcm(rot_r_pan);
195 
196  Mat RT0=buildRotTras(R0,T0);
197  Matrix H0; convert(RT0,H0);
198  Matrix H=SE3inv(R1)*H0*L1;
199 
200  Mat R=Mat::zeros(3,3,CV_64F);
201  Mat T=Mat::zeros(3,1,CV_64F);
202 
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);
206 
207  for (int i=0; i<T.rows; i++)
208  T.at<double>(i,0)=H(i,3);
209 
210  this->stereo->setRotation(R,0);
211  this->stereo->setTranslation(T,0);
212 }
213 
214 
215 /******************************************************************************/
216 void SFM::updateViaGazeCtrl(const bool update)
217 {
218  Matrix L1=getCameraHGazeCtrl(LEFT);
219  Matrix R1=getCameraHGazeCtrl(RIGHT);
220 
221  Matrix RT=SE3inv(R1)*L1;
222 
223  Mat R=Mat::zeros(3,3,CV_64F);
224  Mat T=Mat::zeros(3,1,CV_64F);
225 
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);
229 
230  for (int i=0; i<T.rows; i++)
231  T.at<double>(i,0)=RT(i,3);
232 
233  if (update)
234  {
235  stereo->setRotation(R,0);
236  stereo->setTranslation(T,0);
237  }
238  else
239  stereo->setExpectedPosition(R,T);
240 }
241 
242 
243 /******************************************************************************/
244 bool SFM::interruptModule()
245 {
246  leftImgPort.interrupt();
247  rightImgPort.interrupt();
248  outDisp.interrupt();
249  handlerPort.interrupt();
250  outMatch.interrupt();
251  worldCartPort.interrupt();
252  worldCylPort.interrupt();
253 
254  outLeftRectImgPort.interrupt();
255  outRightRectImgPort.interrupt();
256 
257  return true;
258 }
259 
260 
261 /******************************************************************************/
262 bool SFM::close()
263 {
264  leftImgPort.close();
265  rightImgPort.close();
266  outDisp.close();
267  outMatch.close();
268  handlerPort.close();
269  worldCartPort.close();
270  worldCylPort.close();
271 
272  outLeftRectImgPort.close();
273  outRightRectImgPort.close();
274 
275  headCtrl.close();
276  gazeCtrl.close();
277 
278 #ifdef USING_GPU
279  delete utils;
280 #endif
281 
282  delete stereo;
283 
284  return true;
285 }
286 
287 
288 /******************************************************************************/
289 bool SFM::updateModule()
290 {
291  ImageOf<PixelRgb> *yarp_imgL=leftImgPort.read(true);
292  ImageOf<PixelRgb> *yarp_imgR=rightImgPort.read(true);
293 
294  Stamp stamp_left, stamp_right;
295  leftImgPort.getEnvelope(stamp_left);
296  rightImgPort.getEnvelope(stamp_right);
297 
298  if ((yarp_imgL==NULL) || (yarp_imgR==NULL))
299  return true;
300 
301  // read encoders
302  iencs->getEncoder(nHeadAxes-3,&eyes[0]);
303  iencs->getEncoder(nHeadAxes-2,&eyes[1]);
304  iencs->getEncoder(nHeadAxes-1,&eyes[2]);
305 
306  updateViaKinematics(eyes-eyes0);
307  updateViaGazeCtrl(false);
308 
309  leftMat=toCvMat(*yarp_imgL);
310  rightMat=toCvMat(*yarp_imgR);
311 
312  if (init)
313  {
314  this->numberOfDisparities=(leftMat.size().width<=320)?96:128;
315  init=false;
316  }
317 
318  getCameraHGazeCtrl(LEFT);
319  getCameraHGazeCtrl(RIGHT);
320 
321  this->stereo->setImages(leftMat,rightMat);
322 
323  mutexRecalibration.lock();
324  if (doSFM)
325  {
326 #ifdef USING_GPU
327  utils->extractMatch_GPU(leftMat,rightMat);
328  vector<Point2f> leftM,rightM;
329  utils->getMatches(leftM,rightM);
330  mutexDisp.lock();
331  this->stereo->setMatches(leftM,rightM);
332 #else
333  mutexDisp.lock();
334  this->stereo->findMatch(false);
335 #endif
336  this->stereo->estimateEssential();
337  bool ok=this->stereo->essentialDecomposition();
338  mutexDisp.unlock();
339 
340  if (ok)
341  {
342  calibUpdated=true;
343  doSFM=false;
344  cv_calibEndEvent.notify_all();
345  }
346  else
347  {
348  if (++numberOfTrials>5)
349  {
350  calibUpdated=false;
351  doSFM=false;
352  cv_calibEndEvent.notify_all();
353  }
354  }
355  }
356  mutexRecalibration.unlock();
357 
358  mutexDisp.lock();
359  this->stereo->computeDisparity(this->useBestDisp,this->uniquenessRatio,this->speckleWindowSize,
360  this->speckleRange,this->numberOfDisparities,this->SADWindowSize,
361  this->minDisparity,this->preFilterCap,this->disp12MaxDiff);
362  mutexDisp.unlock();
363 
364  if (outLeftRectImgPort.getOutputCount()>0)
365  {
366  Mat rectLeft = this->stereo->getLRectified();
367 
368  ImageOf<PixelRgb>& rectLeftImage = outLeftRectImgPort.prepare();
369  rectLeftImage.resize(rectLeft.cols,rectLeft.rows);
370 
371  Mat rectLeftImageMat=toCvMat(rectLeftImage);
372  rectLeft.copyTo(rectLeftImageMat);
373 
374  outLeftRectImgPort.setEnvelope(stamp_left);
375  outLeftRectImgPort.write();
376  }
377 
378  if (outRightRectImgPort.getOutputCount()>0)
379  {
380  Mat rectRight = this->stereo->getRRectified();
381 
382  ImageOf<PixelRgb>& rectRightImage = outRightRectImgPort.prepare();
383  rectRightImage.resize(rectRight.cols,rectRight.rows);
384 
385  Mat rectRightImageMat=toCvMat(rectRightImage);
386  rectRight.copyTo(rectRightImageMat);
387 
388  outRightRectImgPort.setEnvelope(stamp_right);
389  outRightRectImgPort.write();
390  }
391 
392  if (outMatch.getOutputCount()>0)
393  {
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));
399  outMatch.write();
400  }
401 
402  if (outDisp.getOutputCount()>0)
403  {
404 
405  //std::cout << "WITHIN OUTDISP.GETOUC" << std::endl;
406 
407  outputDm = stereo->getDisparity();
408 
409  if (!outputDm.empty())
410  {
411 
412  //std::cout << "OUTPUT SIZE AND CHANNELS" << std::endl;
413  //std::cout << outputDm.size() << std::endl;
414  //std::cout << outputDm.channels() << std::endl;
415 
416  ImageOf<PixelMono> &outim = outDisp.prepare();
417  Mat outimMat;
418  if (doBLF)
419  {
420  Mat outputDfiltm;
421  cv_extend::bilateralFilter(outputDm, outputDfiltm, sigmaColorBLF, sigmaSpaceBLF);
422  outimMat = outputDfiltm;
423  }
424  else
425  {
426 
427  outimMat = outputDm;
428  }
429  outim = fromCvMat<PixelMono>(outimMat);
430  outDisp.write();
431  }
432  }
433 
434  ImageOf<PixelRgbFloat>& outcart=worldCartPort.prepare();
435  ImageOf<PixelRgbFloat>& outcyl=worldCylPort.prepare();
436 
437  outcart.resize(leftMat.size().width,leftMat.size().height);
438  outcyl.resize(leftMat.size().width,leftMat.size().height);
439 
440  fillWorld3D(outcart,outcyl);
441 
442  worldCartPort.write();
443  worldCylPort.write();
444 
445  return true;
446 }
447 
448 
449 /******************************************************************************/
450 double SFM::getPeriod()
451 {
452  // the updateModule() method gets synchronized
453  // with camera input => no need for periodicity
454  return 0.0;
455 }
456 
457 
458 /******************************************************************************/
459 bool SFM::loadExtrinsics(yarp::os::ResourceFinder& rf, Mat& Ro, Mat& To, yarp::sig::Vector& eyes)
460 {
461  Bottle extrinsics=rf.findGroup("STEREO_DISPARITY");
462 
463  eyes.resize(3,0.0);
464  if (Bottle *bEyes=extrinsics.find("eyes").asList())
465  {
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();
469  }
470 
471  cout<<"read eyes configuration = ("<<eyes.toString(3,3)<<")"<<endl;
472 
473  if (Bottle *pXo=extrinsics.find("HN").asList())
474  {
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)
478  {
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();
483  }
484  }
485  else
486  return false;
487 
488  return true;
489 }
490 
491 
492 /******************************************************************************/
493 bool SFM::loadIntrinsics(yarp::os::ResourceFinder &rf, Mat &KL, Mat &KR, Mat &DistL,
494  Mat &DistR)
495 {
496  Bottle left=rf.findGroup("CAMERA_CALIBRATION_LEFT");
497  if(!left.check("fx") || !left.check("fy") || !left.check("cx") || !left.check("cy"))
498  return false;
499 
500  double fx=left.find("fx").asFloat64();
501  double fy=left.find("fy").asFloat64();
502 
503  double cx=left.find("cx").asFloat64();
504  double cy=left.find("cy").asFloat64();
505 
506  double k1=left.check("k1",Value(0)).asFloat64();
507  double k2=left.check("k2",Value(0)).asFloat64();
508 
509  double p1=left.check("p1",Value(0)).asFloat64();
510  double p2=left.check("p2",Value(0)).asFloat64();
511 
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;
517 
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;
523 
524  Bottle right=rf.findGroup("CAMERA_CALIBRATION_RIGHT");
525  if(!right.check("fx") || !right.check("fy") || !right.check("cx") || !right.check("cy"))
526  return false;
527 
528  fx=right.find("fx").asFloat64();
529  fy=right.find("fy").asFloat64();
530 
531  cx=right.find("cx").asFloat64();
532  cy=right.find("cy").asFloat64();
533 
534  k1=right.check("k1",Value(0)).asFloat64();
535  k2=right.check("k2",Value(0)).asFloat64();
536 
537  p1=right.check("p1",Value(0)).asFloat64();
538  p2=right.check("p2",Value(0)).asFloat64();
539 
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;
545 
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;
551 
552  return true;
553 }
554 
555 
556 /******************************************************************************/
557 bool SFM::updateExtrinsics(Mat& Rot, Mat& Tr, yarp::sig::Vector& eyes,
558  const string& groupname)
559 {
560  ofstream out;
561  out.open(camCalibFile.c_str());
562  if (out.is_open())
563  {
564  out << endl;
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 << ")"
571  << endl;
572  out.close();
573  return true;
574  }
575  else
576  return false;
577 }
578 
579 
580 /******************************************************************************/
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)
585 {
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();
597 
598 }
599 
600 
601 /******************************************************************************/
602 Point3f SFM::get3DPointsAndDisp(int u, int v, int& uR, int& vR, const string &drive)
603 {
604  Point3f point(0.0f,0.0f,0.0f);
605  if ((drive!="RIGHT") && (drive!="LEFT") && (drive!="ROOT"))
606  return point;
607 
608  lock_guard<mutex> lg(mutexDisp);
609 
610  // Mapping from Rectified Cameras to Original Cameras
611  const Mat& Mapper=this->stereo->getMapperL();
612  if (Mapper.empty())
613  return point;
614 
615  float usign=Mapper.ptr<float>(v)[2*u];
616  float vsign=Mapper.ptr<float>(v)[2*u+1];
617 
618  u=cvRound(usign);
619  v=cvRound(vsign);
620 
621  const Mat& disp16m=this->stereo->getDisparity16();
622  if (disp16m.empty() || (u<0) || (u>=disp16m.cols) || (v<0) || (v>=disp16m.rows))
623  return point;
624 
625  const Mat& Q=this->stereo->getQ();
626  CvScalar scal=cvGet2D(&disp16m,v,u);
627  double disparity=scal.val[0]/16.0;
628 
629  uR=u-(int)disparity;
630  vR=(int)v;
631 
632  Point2f orig=this->stereo->fromRectifiedToOriginal(uR,vR,RIGHT);
633  uR=(int)orig.x;
634  vR=(int)orig.y;
635 
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);
640 
641  point.x/=w;
642  point.y/=w;
643  point.z/=w;
644 
645  // discard points far more than 10 meters or with not valid disparity (<0)
646  if ((point.z>10.0f) || (point.z<0.0f))
647  return point;
648 
649  if (drive=="ROOT")
650  {
651  const Mat& RLrect=this->stereo->getRLrect().t();
652  Mat Tfake=Mat::zeros(0,3,CV_64F);
653  Mat P(4,1,CV_64FC1);
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;
658 
659  Mat Hrect=buildRotTras(RLrect,Tfake);
660  P=HL_root*Hrect*P;
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));
664  }
665  else if (drive=="LEFT")
666  {
667  Mat P(3,1,CV_64FC1);
668  P.at<double>(0,0)=point.x;
669  P.at<double>(1,0)=point.y;
670  P.at<double>(2,0)=point.z;
671 
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);
676  }
677  else if (drive=="RIGHT")
678  {
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);
683 
684  Mat HRL=buildRotTras(Rright,Tright);
685  Mat Hrect=buildRotTras(RRright,TRright);
686 
687  Mat P(4,1,CV_64FC1);
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;
692 
693  P=Hrect*HRL*P;
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));
697  }
698 
699  return point;
700 }
701 
702 
703 /******************************************************************************/
704 Point3f SFM::get3DPoints(int u, int v, const string &drive)
705 {
706  Point3f point(0.0f,0.0f,0.0f);
707  if ((drive!="RIGHT") && (drive!="LEFT") && (drive!="ROOT"))
708  return point;
709 
710  lock_guard<mutex> lg(mutexDisp);
711 
712  // Mapping from Rectified Cameras to Original Cameras
713  const Mat& Mapper=this->stereo->getMapperL();
714  if (Mapper.empty())
715  return point;
716 
717  float usign=Mapper.ptr<float>(v)[2*u];
718  float vsign=Mapper.ptr<float>(v)[2*u+1];
719 
720  u=cvRound(usign);
721  v=cvRound(vsign);
722 
723  const Mat& disp16m=this->stereo->getDisparity16();
724  if (disp16m.empty() || (u<0) || (u>=disp16m.cols) || (v<0) || (v>=disp16m.rows))
725  return point;
726 
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);
734 
735  point.x/=w;
736  point.y/=w;
737  point.z/=w;
738 
739  // discard points far more than 10 meters or with not valid disparity (<0)
740  if ((point.z>10.0f) || (point.z<0.0f))
741  return point;
742 
743  if (drive=="ROOT")
744  {
745  const Mat& RLrect=this->stereo->getRLrect().t();
746  Mat Tfake=Mat::zeros(0,3,CV_64F);
747  Mat P(4,1,CV_64FC1);
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;
752 
753  Mat Hrect=buildRotTras(RLrect,Tfake);
754  P=HL_root*Hrect*P;
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));
758  }
759  else if (drive=="LEFT")
760  {
761  Mat P(3,1,CV_64FC1);
762  P.at<double>(0,0)=point.x;
763  P.at<double>(1,0)=point.y;
764  P.at<double>(2,0)=point.z;
765 
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);
770  }
771  else if (drive=="RIGHT")
772  {
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);
777 
778  Mat HRL=buildRotTras(Rright,Tright);
779  Mat Hrect=buildRotTras(RRright,TRright);
780 
781  Mat P(4,1,CV_64FC1);
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;
786 
787  P=Hrect*HRL*P;
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));
791  }
792 
793  return point;
794 }
795 
796 
797 /******************************************************************************/
798 Point3f SFM::get3DPointMatch(double u1, double v1, double u2, double v2,
799  const string &drive)
800 {
801  Point3f point(0.0f,0.0f,0.0f);
802  if ((drive!="RIGHT") && (drive!="LEFT") && (drive!="ROOT"))
803  return point;
804 
805  lock_guard<mutex> lg(mutexDisp);
806  // Mapping from Rectified Cameras to Original Cameras
807  const Mat& MapperL=this->stereo->getMapperL();
808  const Mat& MapperR=this->stereo->getMapperR();
809  if (MapperL.empty() || MapperR.empty())
810  return point;
811 
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))
814  return point;
815 
816  float urect1=MapperL.ptr<float>(cvRound(v1))[2*cvRound(u1)];
817  float vrect1=MapperL.ptr<float>(cvRound(v1))[2*cvRound(u1)+1];
818 
819  float urect2=MapperR.ptr<float>(cvRound(v2))[2*cvRound(u2)];
820  float vrect2=MapperR.ptr<float>(cvRound(v2))[2*cvRound(u2)+1];
821 
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);
828 
829  point.x/=w;
830  point.y/=w;
831  point.z/=w;
832 
833  if (drive=="ROOT")
834  {
835  const Mat& RLrect=this->stereo->getRLrect().t();
836  Mat Tfake=Mat::zeros(0,3,CV_64F);
837  Mat P(4,1,CV_64FC1);
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;
842 
843  Mat Hrect=buildRotTras(RLrect,Tfake);
844  P=HL_root*Hrect*P;
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));
848  }
849  else if (drive=="LEFT")
850  {
851  Mat P(3,1,CV_64FC1);
852  P.at<double>(0,0)=point.x;
853  P.at<double>(1,0)=point.y;
854  P.at<double>(2,0)=point.z;
855 
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);
860  }
861  else if (drive=="RIGHT")
862  {
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);
867 
868  Mat HRL=buildRotTras(Rright,Tright);
869  Mat Hrect=buildRotTras(RRright,TRright);
870 
871  Mat P(4,1,CV_64FC1);
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;
876 
877  P=Hrect*HRL*P;
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));
881  }
882 
883  return point;
884 }
885 
886 
887 /******************************************************************************/
888 Mat SFM::buildRotTras(const Mat& R, const Mat& T)
889 {
890  Mat A=Mat::eye(4,4,CV_64F);
891  for (int i=0; i<R.rows; i++)
892  {
893  double* Mi=A.ptr<double>(i);
894  const double* MRi=R.ptr<double>(i);
895  for (int j=0; j<R.cols; j++)
896  Mi[j]=MRi[j];
897  }
898 
899  for (int i=0; i<T.rows; i++)
900  {
901  double* Mi=A.ptr<double>(i);
902  const double* MRi=T.ptr<double>(i);
903  Mi[3]=MRi[0];
904  }
905 
906  return A;
907 }
908 
909 
910 /******************************************************************************/
911 Matrix SFM::getCameraHGazeCtrl(int camera)
912 {
913  yarp::sig::Vector x_curr;
914  yarp::sig::Vector o_curr;
915  bool check=false;
916  if(camera==LEFT)
917  check=igaze->getLeftEyePose(x_curr, o_curr);
918  else
919  check=igaze->getRightEyePose(x_curr, o_curr);
920 
921  if(!check)
922  {
923  Matrix H_curr(4, 4);
924  return H_curr;
925  }
926 
927  Matrix R_curr=axis2dcm(o_curr);
928  Matrix H_curr=R_curr;
929  H_curr.setSubcol(x_curr,0,3);
930 
931  if(camera==LEFT)
932  {
933  mutexDisp.lock();
934  convert(H_curr,HL_root);
935  mutexDisp.unlock();
936  }
937  else if(camera==RIGHT)
938  {
939  mutexDisp.lock();
940  convert(H_curr,HR_root);
941  mutexDisp.unlock();
942  }
943 
944  return H_curr;
945 }
946 
947 
948 /******************************************************************************/
949 void SFM::convert(Matrix& matrix, Mat& mat)
950 {
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);
955 }
956 
957 
958 /******************************************************************************/
959 void SFM::convert(Mat& mat, Matrix& matrix)
960 {
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);
965 }
966 
967 
968 /******************************************************************************/
969 bool SFM::respond(const Bottle& command, Bottle& reply)
970 {
971  if(command.size()==0)
972  return false;
973 
974  if (command.get(0).asString()=="quit") {
975  cout << "closing..." << endl;
976  return false;
977  }
978 
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");
999  return true;
1000  }
1001 
1002  if (command.get(0).asString()=="calibrate")
1003  {
1004  mutexRecalibration.lock();
1005  numberOfTrials=0;
1006  doSFM=true;
1007  mutexRecalibration.unlock();
1008 
1009  unique_lock<mutex> lck(mtx_calibEndEvent);
1010  cv_calibEndEvent.wait(lck);
1011 
1012  if (calibUpdated)
1013  {
1014  R0=this->stereo->getRotation();
1015  T0=this->stereo->getTranslation();
1016  eyes0=eyes;
1017 
1018  reply.addString("ACK");
1019  }
1020  else
1021  reply.addString("Calibration failed after 5 trials.. Please show a non planar scene.");
1022 
1023  return true;
1024  }
1025 
1026  if (command.get(0).asString()=="save")
1027  {
1028  updateExtrinsics(R0,T0,eyes0,"STEREO_DISPARITY");
1029  reply.addString("ACK");
1030  return true;
1031  }
1032 
1033  if (command.get(0).asString()=="getH")
1034  {
1035  Mat RT0=buildRotTras(R0,T0);
1036  Matrix H0; convert(RT0,H0);
1037 
1038  reply.read(H0);
1039  return true;
1040  }
1041 
1042  if (command.get(0).asString()=="setNumDisp")
1043  {
1044  int dispNum=command.get(1).asInt32();
1045  if(dispNum%32==0)
1046  {
1047  this->numberOfDisparities=dispNum;
1048  this->setDispParameters(useBestDisp,uniquenessRatio,speckleWindowSize,speckleRange,numberOfDisparities,SADWindowSize,minDisparity,preFilterCap,disp12MaxDiff);
1049  reply.addString("ACK");
1050  return true;
1051  }
1052  else
1053  {
1054  reply.addString("Num Disparity must be divisible by 32");
1055  return true;
1056  }
1057  }
1058 
1059  if (command.get(0).asString()=="setMinDisp")
1060  {
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");
1067  return true;
1068  }
1069 
1070  if (command.get(0).asString()=="set" && command.size()==10)
1071  {
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();
1081 
1082  this->setDispParameters(bestDisp,uniquenessRatio,speckleWindowSize,
1083  speckleRange,numberOfDisparities,SADWindowSize,
1084  minDisparity,preFilterCap,disp12MaxDiff);
1085  reply.addString("ACK");
1086  }
1087  else if (command.get(0).asString()=="Point" || command.get(0).asString()=="Left" )
1088  {
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);
1095  }
1096  else if (!command.get(0).isString() && command.size()==2)
1097  {
1098  int u = command.get(0).asInt32();
1099  int v = command.get(1).asInt32();
1100  int uR,vR;
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);
1105  reply.addInt32(uR);
1106  reply.addInt32(vR);
1107  }
1108  else if (command.get(0).asString()=="Right")
1109  {
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);
1116  }
1117  else if (command.get(0).asString()=="Root")
1118  {
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);
1125  }
1126  else if (command.get(0).asString()=="Rect")
1127  {
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();
1132 
1133  int step = 1;
1134  if (command.size()>=6)
1135  step=command.get(5).asInt32();
1136 
1137  for (int u=tl_u; u<br_u; u+=step)
1138  {
1139  for (int v=tl_v; v<br_v; v+=step)
1140  {
1141  Point3f point=this->get3DPoints(u,v,"ROOT");
1142  reply.addFloat64(point.x);
1143  reply.addFloat64(point.y);
1144  reply.addFloat64(point.z);
1145  }
1146  }
1147  }
1148  else if (command.get(0).asString()=="Points")
1149  {
1150  for (int cnt=1; cnt<command.size()-1; cnt+=2)
1151  {
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);
1158  }
1159  }
1160  else if (command.get(0).asString()=="Flood3D")
1161  {
1162  cv::Point seed(command.get(1).asInt32(),
1163  command.get(2).asInt32());
1164 
1165  double dist=0.004;
1166  if (command.size()>=4)
1167  dist=command.get(3).asFloat64();
1168 
1169  Point3f p=get3DPoints(seed.x,seed.y,"ROOT");
1170  if (cv::norm(p)>0.0)
1171  {
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);
1177 
1178  set<int> visited;
1179  visited.insert(seed.x*outputDm.cols+seed.y);
1180 
1181  floodFill(seed,p,dist,visited,reply);
1182  }
1183  else
1184  reply.addString("NACK");
1185  }
1186  else if (command.get(0).asString()=="cart2stereo")
1187  {
1188  double x = command.get(1).asFloat64();
1189  double y = command.get(2).asFloat64();
1190  double z = command.get(3).asFloat64();
1191 
1192  Point2f pointL = this->projectPoint("left",x,y,z);
1193  Point2f pointR = this->projectPoint("right",x,y,z);
1194 
1195  reply.addFloat64(pointL.x);
1196  reply.addFloat64(pointL.y);
1197  reply.addFloat64(pointR.x);
1198  reply.addFloat64(pointR.y);
1199  }
1200  else if (command.get(0).asString()=="bilatfilt" && command.size()==3)
1201  {
1202  if (!doBLF){
1203  doBLF = true;
1204  reply.addString("Bilateral filter activated.");
1205  }
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);
1212  }
1213  else if (command.get(0).asString()=="doBLF")
1214  {
1215  bool onoffBLF = command.get(1).asBool();
1216  if (onoffBLF == false ){ // turn OFF Bilateral Filtering
1217  if (doBLF == true){
1218  doBLF = false;
1219  reply.addString("Bilateral Filter OFF");
1220  } else {
1221  reply.addString("Bilateral Filter already OFF");
1222  }
1223 
1224  } else { // turn ON Bilateral Filtering
1225  if (doBLF == true){
1226  reply.addString("Bilateral Filter Already Running");
1227  } else { // Set any different from 0 to activate bilateral filter.
1228  doBLF = true;
1229  reply.addString("Bilateral Filter ON");
1230  }
1231  }
1232  reply.addFloat64(sigmaColorBLF);
1233  reply.addFloat64(sigmaSpaceBLF);
1234  }
1235  else if(command.size()>0 && command.size()%4==0)
1236  {
1237  for (int i=0; i<command.size(); i+=4)
1238  {
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();
1243 
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);
1248  }
1249  }
1250  else
1251  reply.addString("NACK");
1252 
1253  return true;
1254 }
1255 
1256 
1257 /******************************************************************************/
1258 Point2f SFM::projectPoint(const string &camera, double x, double y, double z)
1259 {
1260  Point3f point3D;
1261  point3D.x=(float)x;
1262  point3D.y=(float)y;
1263  point3D.z=(float)z;
1264 
1265  vector<Point3f> points3D;
1266 
1267  points3D.push_back(point3D);
1268 
1269  vector<Point2f> response;
1270 
1271  mutexDisp.lock();
1272 
1273  if(camera=="left")
1274  response=this->stereo->projectPoints3D("left",points3D,HL_root);
1275  else
1276  response=this->stereo->projectPoints3D("right",points3D,HL_root);
1277 
1278  mutexDisp.unlock();
1279  return response[0];
1280 }
1281 
1282 
1283 /******************************************************************************/
1284 void SFM::fillWorld3D(ImageOf<PixelRgbFloat> &worldCartImg,
1285  ImageOf<PixelRgbFloat> &worldCylImg)
1286 {
1287  mutexDisp.lock();
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();
1292  mutexDisp.unlock();
1293 
1294  worldCartImg.zero(); worldCylImg.zero();
1295  if (Mapper.empty() || disp16m.empty() ||
1296  (worldCartImg.width()!=worldCylImg.width()) ||
1297  (worldCartImg.height()!=worldCylImg.height()))
1298  return;
1299 
1300  Mat Tfake=Mat::zeros(0,3,CV_64F);
1301  Mat Hrect=buildRotTras(RLrect,Tfake);
1302  Hrect=HL_root*Hrect;
1303 
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);
1309 
1310  for (int v=0; v<worldCartImg.height(); v++)
1311  {
1312  for (int u=0; u<worldCartImg.width(); u++)
1313  {
1314  float usign=Mapper.ptr<float>(v)[2*u];
1315  float vsign=Mapper.ptr<float>(v)[2*u+1];
1316 
1317  int u_=cvRound(usign); int v_=cvRound(vsign);
1318  if ((u_<0) || (u_>=disp16m.cols) || (v_<0) || (v_>=disp16m.rows))
1319  continue;
1320 
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);
1324 
1325  cv::Scalar scal(disp16m.at<long>(v_, u_));
1326 
1327  double disparity=scal.val[0]/16.0;
1328  double w=disparity*Q.at<double>(3,2)+Q.at<double>(3,3);
1329  x/=w; y/=w; z/=w;
1330 
1331  if ((z>10.0) || (z<0.0))
1332  continue;
1333 
1334  P=Hrect*P;
1335 
1336  PixelRgbFloat &pxCart=worldCartImg.pixel(u,v);
1337  pxCart.r=(float)x;
1338  pxCart.g=(float)y;
1339  pxCart.b=(float)z;
1340 
1341  PixelRgbFloat &pxCyl=worldCylImg.pixel(u,v);
1342  pxCyl.r=(float)sqrt(x*x+y*y);
1343  pxCyl.g=(float)atan2(y,x);
1344  pxCyl.b=(float)z;
1345  }
1346  }
1347 }
1348 
1349 
1350 /******************************************************************************/
1351 void SFM::floodFill(const Point &seed, const Point3f &p0, const double dist,
1352  set<int> &visited, Bottle &res)
1353 {
1354  for (int x=seed.x-1; x<=seed.x+1; x++)
1355  {
1356  for (int y=seed.y-1; y<=seed.y+1; y++)
1357  {
1358  if ((x<0)||(y<0)||(x>outputDm.cols)||(y>outputDm.rows))
1359  continue;
1360 
1361  int idx=x*outputDm.cols+y;
1362  set<int>::iterator el=visited.find(idx);
1363  if (el==visited.end())
1364  {
1365  visited.insert(idx);
1366  Point3f p=get3DPoints(x,y,"ROOT");
1367  if ((cv::norm(p)>0.0) && (cv::norm(p-p0)<=dist))
1368  {
1369  res.addInt32(x);
1370  res.addInt32(y);
1371  res.addFloat64(p.x);
1372  res.addFloat64(p.y);
1373  res.addFloat64(p.z);
1374 
1375  floodFill(Point(x,y),p,dist,visited,res);
1376  }
1377  }
1378  }
1379  }
1380 }
1381 
1382 
1383 /******************************************************************************/
1384 int main(int argc, char *argv[])
1385 {
1386  Network yarp;
1387 
1388  if (!yarp.checkNetwork())
1389  return 1;
1390 
1391  ResourceFinder rf;
1392  rf.setDefaultConfigFile("icubEyes.ini");
1393  rf.setDefaultContext("cameraCalibration");
1394  rf.configure(argc,argv);
1395 
1396  SFM mod;
1397 
1398  return mod.runModule(rf);
1399 }
1400 
1401 
The base class defining stereo camera.
Definition: stereoCamera.h:92
void bilateralFilter(cv::InputArray src, cv::OutputArray dst, double sigmaColor, double sigmaSpace)
Implementation.