EpipolarGeometry.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
29 #include "rtabmap/core/Signature.h"
31 #include "rtabmap/utilite/UTimer.h"
32 #include "rtabmap/utilite/UStl.h"
33 #include "rtabmap/utilite/UMath.h"
34 
35 #include <opencv2/core/core.hpp>
36 #include <opencv2/core/core_c.h>
37 #include <opencv2/calib3d/calib3d.hpp>
38 #include <iostream>
39 
40 namespace rtabmap
41 {
42 
44 // HypVerificatorEpipolarGeo
47  _matchCountMinAccepted(Parameters::defaultVhEpMatchCountMin()),
48  _ransacParam1(Parameters::defaultVhEpRansacParam1()),
49  _ransacParam2(Parameters::defaultVhEpRansacParam2())
50 {
51  this->parseParameters(parameters);
52 }
53 
55 
56 }
57 
59 {
60  Parameters::parse(parameters, Parameters::kVhEpMatchCountMin(), _matchCountMinAccepted);
61  Parameters::parse(parameters, Parameters::kVhEpRansacParam1(), _ransacParam1);
62  Parameters::parse(parameters, Parameters::kVhEpRansacParam2(), _ransacParam2);
63 }
64 
65 bool EpipolarGeometry::check(const Signature * ssA, const Signature * ssB)
66 {
67  if(ssA == 0 || ssB == 0)
68  {
69  return false;
70  }
71  ULOGGER_DEBUG("id(%d,%d)", ssA->id(), ssB->id());
72 
73  std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > pairs;
74 
75  findPairsUnique(ssA->getWords(), ssB->getWords(), pairs);
76 
77  if((int)pairs.size()<_matchCountMinAccepted)
78  {
79  return false;
80  }
81 
82  std::vector<uchar> status;
83  cv::Mat f = findFFromWords(pairs, status, _ransacParam1, _ransacParam2);
84 
85  int inliers = uSum(status);
86  if(inliers < _matchCountMinAccepted)
87  {
88  ULOGGER_DEBUG("Epipolar constraint failed A : not enough inliers (%d/%d), min is %d", inliers, pairs.size(), _matchCountMinAccepted);
89  return false;
90  }
91  else
92  {
93  UDEBUG("inliers = %d/%d", inliers, pairs.size());
94  return true;
95  }
96 }
97 
98 //STATIC STUFF
99 //Epipolar geometry
100 void EpipolarGeometry::findEpipolesFromF(const cv::Mat & fundamentalMatrix, cv::Vec3d & e1, cv::Vec3d & e2)
101 {
102  if(fundamentalMatrix.rows != 3 || fundamentalMatrix.cols != 3)
103  {
104  ULOGGER_ERROR("The matrix is not the good size...");
105  return;
106  }
107 
108  if(fundamentalMatrix.type() != CV_64FC1)
109  {
110  ULOGGER_ERROR("The matrix is not the good type...");
111  return;
112  }
113 
114 
115  cv::SVD svd(fundamentalMatrix);
116  cv::Mat u = svd.u;
117  cv::Mat v = svd.vt;
118  cv::Mat w = svd.w;
119 
120  // v is for image 1
121  // u is for image 2
122 
123  e1[0] = v.at<double>(0,2);// /v->data.db[2*3+2];
124  e1[1] = v.at<double>(1,2);// /v->data.db[2*3+2];
125  e1[2] = v.at<double>(2,2);// /v->data.db[2*3+2];
126 
127  e2[0] = u.at<double>(0,2);// /u->data.db[2*3+2];
128  e2[1] = u.at<double>(1,2);// /u->data.db[2*3+2];
129  e2[2] = u.at<double>(2,2);// /u->data.db[2*3+2];
130 }
131 
132 int inFrontOfBothCameras(const cv::Mat & x, const cv::Mat & xp, const cv::Mat & R, const cv::Mat & T)
133 {
134  // P0 matrix 3X4
135  cv::Mat p0 = cv::Mat::zeros(3, 4, CV_64FC1);
136  p0.at<double>(0,0) = 1;
137  p0.at<double>(1,1) = 1;
138  p0.at<double>(2,2) = 1;
139  cv::Mat p = cv::Mat::zeros(3, 4, CV_64FC1);
140  p.at<double>(0,0) = R.at<double>(0,0);
141  p.at<double>(0,1) = R.at<double>(0,1);
142  p.at<double>(0,2) = R.at<double>(0,2);
143  p.at<double>(1,0) = R.at<double>(1,0);
144  p.at<double>(1,1) = R.at<double>(1,1);
145  p.at<double>(1,2) = R.at<double>(1,2);
146  p.at<double>(2,0) = R.at<double>(2,0);
147  p.at<double>(2,1) = R.at<double>(2,1);
148  p.at<double>(2,2) = R.at<double>(2,2);
149  p.at<double>(0,3) = T.at<double>(0,0);
150  p.at<double>(1,3) = T.at<double>(1,0);
151  p.at<double>(2,3) = T.at<double>(2,0);
152 
153  cv::Mat pts4D;
154  //std::vector<double> reprojErrors;
155  //pcl::PointCloud<pcl::PointXYZ>::Ptr cloud;
156  //EpipolarGeometry::triangulatePoints(x, xp, p0, p, cloud, reprojErrors);
157  cv::triangulatePoints(p0, p, x, xp, pts4D);
158 
159  //http://en.wikipedia.org/wiki/Essential_matrix#3D_points_from_corresponding_image_points
160  int nValid = 0;
161  for(int i=0; i<x.cols; ++i)
162  {
163  // the five to ignore when all points are super close to the camera
164  if(pts4D.at<double>(2,i)/pts4D.at<double>(3,i) > 5)
165  //if(cloud->at(i).z > 5)
166  {
167  ++nValid;
168  }
169  }
170  UDEBUG("nValid=%d/%d", nValid, x.cols);
171 
172  return nValid;
173 }
174 
175 //Assuming P0 = [eye(3) zeros(3,1)]
176 // x1 and x2 are 2D points
177 // return camera matrix P (3x4) matrix
178 //http://www.robots.ox.ac.uk/~vgg/hzbook/hzbook2/HZepipolar.pdf
179 cv::Mat EpipolarGeometry::findPFromE(const cv::Mat & E,
180  const cv::Mat & x,
181  const cv::Mat & xp)
182 {
183  UDEBUG("begin");
184  UASSERT(E.rows == 3 && E.cols == 3);
185  UASSERT(E.type() == CV_64FC1);
186  UASSERT(x.rows == 2 && x.cols>0 && x.type() == CV_64FC1);
187  UASSERT(xp.rows == 2 && xp.cols>0 && x.type() == CV_64FC1);
188 
189  // skew matrix 3X3
190  cv::Mat w = cv::Mat::zeros( 3, 3, CV_64FC1);
191  w.at<double>(0,1) = -1;
192  w.at<double>(1,0) = 1;
193  w.at<double>(2,2) = 1;
194  //std::cout << "W=" << w << std::endl;
195 
196  cv::Mat e = E;
197  cv::SVD svd(e,cv::SVD::MODIFY_A);
198  cv::Mat u = svd.u;
199  cv::Mat vt = svd.vt;
200  cv::Mat s = svd.w;
201 
202  //std::cout << "u=" << u << std::endl;
203  //std::cout << "vt=" << vt << std::endl;
204  //std::cout << "s=" << s << std::endl;
205 
206  // E = u*diag(1,1,0)*vt
207  cv::Mat diag = cv::Mat::eye(3,3,CV_64FC1);
208  diag.at<double>(2,2) = 0;
209  e = u*diag*vt;
210  svd(e,cv::SVD::MODIFY_A);
211  u = svd.u;
212  vt = svd.vt;
213  s = svd.w;
214 
215  cv::Mat r = u*w*vt;
216  if(cv::determinant(r)+1.0 < 1e-09) {
217  //according to http://en.wikipedia.org/wiki/Essential_matrix#Showing_that_it_is_valid
218  UDEBUG("det(R) == -1 [%f]: flip E's sign", cv::determinant(r));
219  e = -E;
220  svd(e,cv::SVD::MODIFY_A);
221  u = svd.u;
222  vt = svd.vt;
223  s = svd.w;
224  }
225  cv::Mat wt = w.t();
226 
227  // INFO: There 4 cases of P, only one have all the points in
228  // front of the two cameras (positive z).
229 
230  cv::Mat r1 = u*w*vt;
231  cv::Mat r2 = u*wt*vt;
232 
233  cv::Mat t1 = u.col(2);
234  cv::Mat t2 = u.col(2)*-1;
235 
236  int max = 0;
237  int maxIndex = 1;
238  int maxTmp;
239  cv::Mat R=r1,T=t1;
240 
241  // Case 1 : P = [U*W*V' t];
242  max = inFrontOfBothCameras(x, xp, r1, t1);
243  // Case 2 : P = [U*W*V' -t];
244  maxTmp = inFrontOfBothCameras(x, xp, r1, t2);
245  if(maxTmp > max)
246  {
247  maxIndex = 2;
248  max = maxTmp;
249  R=r1,T=t2;
250  }
251  // Case 3 : P = [U*W'*V' t];
252  maxTmp = inFrontOfBothCameras(x, xp, r2, t1);
253  if(maxTmp > max)
254  {
255  maxIndex = 3;
256  max = maxTmp;
257  R=r2,T=t1;
258  }
259  // Case 4 : P = [U*W'*V' -t];
260  maxTmp = inFrontOfBothCameras(x, xp, r2, t2);
261  if(maxTmp > max)
262  {
263  maxIndex = 4;
264  max = maxTmp;
265  R=r2,T=t2;
266  }
267 
268  if(max > 0)
269  {
270  UDEBUG("Case %d", maxIndex);
271 
272  // P matrix 3x4
273  cv::Mat p = cv::Mat::zeros(3, 4, CV_64FC1);
274  p.at<double>(0,0) = R.at<double>(0,0);
275  p.at<double>(0,1) = R.at<double>(0,1);
276  p.at<double>(0,2) = R.at<double>(0,2);
277  p.at<double>(1,0) = R.at<double>(1,0);
278  p.at<double>(1,1) = R.at<double>(1,1);
279  p.at<double>(1,2) = R.at<double>(1,2);
280  p.at<double>(2,0) = R.at<double>(2,0);
281  p.at<double>(2,1) = R.at<double>(2,1);
282  p.at<double>(2,2) = R.at<double>(2,2);
283  p.at<double>(0,3) = T.at<double>(0);
284  p.at<double>(1,3) = T.at<double>(1);
285  p.at<double>(2,3) = T.at<double>(2);
286  return p;
287  }
288 
289  return cv::Mat();
290 }
291 
293  const std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs, // id, kpt1, kpt2
294  std::vector<uchar> & status,
295  double ransacParam1,
296  double ransacParam2)
297 {
298 
299  status = std::vector<uchar>(pairs.size(), 0);
300  //Convert Keypoints to a structure that OpenCV understands
301  //3 dimensions (Homogeneous vectors)
302  cv::Mat points1(1, pairs.size(), CV_32FC2);
303  cv::Mat points2(1, pairs.size(), CV_32FC2);
304 
305  float * points1data = points1.ptr<float>(0);
306  float * points2data = points2.ptr<float>(0);
307 
308  // Fill the points here ...
309  int i=0;
310  for(std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > >::const_iterator iter = pairs.begin();
311  iter != pairs.end();
312  ++iter )
313  {
314  points1data[i*2] = (*iter).second.first.pt.x;
315  points1data[i*2+1] = (*iter).second.first.pt.y;
316 
317  points2data[i*2] = (*iter).second.second.pt.x;
318  points2data[i*2+1] = (*iter).second.second.pt.y;
319 
320  ++i;
321  }
322 
323  UTimer timer;
324  timer.start();
325 
326  // Find the fundamental matrix
327  cv::Mat fundamentalMatrix = cv::findFundamentalMat(
328  points1,
329  points2,
330  status,
331  cv::FM_RANSAC,
332  ransacParam1,
333  ransacParam2);
334 
335  ULOGGER_DEBUG("Find fundamental matrix (OpenCV) time = %fs", timer.ticks());
336 
337  // Fundamental matrix is valid ?
338  bool fundMatFound = false;
339  UASSERT(fundamentalMatrix.type() == CV_64FC1);
340  if(fundamentalMatrix.cols==3 && fundamentalMatrix.rows==3 &&
341  (fundamentalMatrix.at<double>(0,0) != 0.0 ||
342  fundamentalMatrix.at<double>(0,1) != 0.0 ||
343  fundamentalMatrix.at<double>(0,2) != 0.0 ||
344  fundamentalMatrix.at<double>(1,0) != 0.0 ||
345  fundamentalMatrix.at<double>(1,1) != 0.0 ||
346  fundamentalMatrix.at<double>(1,2) != 0.0 ||
347  fundamentalMatrix.at<double>(2,0) != 0.0 ||
348  fundamentalMatrix.at<double>(2,1) != 0.0 ||
349  fundamentalMatrix.at<double>(2,2) != 0.0) )
350 
351  {
352  fundMatFound = true;
353  }
354 
355  ULOGGER_DEBUG("fm_count=%d...", fundMatFound);
356 
357  if(fundMatFound)
358  {
359  // Show the fundamental matrix
360  UDEBUG(
361  "F = [%f %f %f;%f %f %f;%f %f %f]",
362  fundamentalMatrix.ptr<double>(0)[0],
363  fundamentalMatrix.ptr<double>(0)[1],
364  fundamentalMatrix.ptr<double>(0)[2],
365  fundamentalMatrix.ptr<double>(0)[3],
366  fundamentalMatrix.ptr<double>(0)[4],
367  fundamentalMatrix.ptr<double>(0)[5],
368  fundamentalMatrix.ptr<double>(0)[6],
369  fundamentalMatrix.ptr<double>(0)[7],
370  fundamentalMatrix.ptr<double>(0)[8]);
371  }
372  return fundamentalMatrix;
373 }
374 
376  const cv::Mat & p,
377  cv::Mat & r,
378  cv::Mat & t)
379 {
380  UASSERT(p.cols == 4 && p.rows == 3);
381  r = cv::Mat(p, cv::Range(0,3), cv::Range(0,3));
382  //r = -r.inv();
383  //t = r*p.col(3);
384  t = p.col(3);
385 }
386 
387 cv::Mat EpipolarGeometry::findFFromCalibratedStereoCameras(double fx, double fy, double cx, double cy, double Tx, double Ty)
388 {
389  cv::Mat R = cv::Mat::eye(3, 3, CV_64FC1);
390 
391  double Bx = Tx/-fx;
392  double By = Ty/-fy;
393 
394  cv::Mat tx = (cv::Mat_<double>(3,3) <<
395  0, 0, By,
396  0, 0, -Bx,
397  -By, Bx, 0);
398 
399  cv::Mat K = (cv::Mat_<double>(3,3) <<
400  fx, 0, cx,
401  0, fy, cy,
402  0, 0, 1);
403 
404  cv::Mat E = tx*R;
405 
406  return K.inv().t()*E*K.inv();
407 }
408 
414  const std::map<int, cv::KeyPoint> & wordsA,
415  const std::map<int, cv::KeyPoint> & wordsB,
416  std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs,
417  bool ignoreInvalidIds)
418 {
419  int realPairsCount = 0;
420  pairs.clear();
421  for(std::map<int, cv::KeyPoint>::const_iterator i=wordsA.begin(); i!=wordsA.end(); ++i)
422  {
423  if(!ignoreInvalidIds || (ignoreInvalidIds && i->first>=0))
424  {
425  std::map<int, cv::KeyPoint>::const_iterator ptB = wordsB.find(i->first);
426  if(ptB != wordsB.end())
427  {
428  pairs.push_back(std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> >(i->first, std::pair<cv::KeyPoint, cv::KeyPoint>(i->second, ptB->second)));
429  ++realPairsCount;
430  }
431  }
432  }
433  return realPairsCount;
434 }
435 
440 int EpipolarGeometry::findPairs(const std::multimap<int, cv::KeyPoint> & wordsA,
441  const std::multimap<int, cv::KeyPoint> & wordsB,
442  std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs,
443  bool ignoreInvalidIds)
444 {
445  const std::list<int> & ids = uUniqueKeys(wordsA);
446  std::multimap<int, cv::KeyPoint>::const_iterator iterA;
447  std::multimap<int, cv::KeyPoint>::const_iterator iterB;
448  pairs.clear();
449  int realPairsCount = 0;
450  for(std::list<int>::const_iterator i=ids.begin(); i!=ids.end(); ++i)
451  {
452  if(!ignoreInvalidIds || (ignoreInvalidIds && *i >= 0))
453  {
454  iterA = wordsA.find(*i);
455  iterB = wordsB.find(*i);
456  while(iterA != wordsA.end() && iterB != wordsB.end() && (*iterA).first == (*iterB).first && (*iterA).first == *i)
457  {
458  pairs.push_back(std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> >(*i, std::pair<cv::KeyPoint, cv::KeyPoint>((*iterA).second, (*iterB).second)));
459  ++iterA;
460  ++iterB;
461  ++realPairsCount;
462  }
463  }
464  }
465  return realPairsCount;
466 }
467 
473  const std::multimap<int, cv::KeyPoint> & wordsA,
474  const std::multimap<int, cv::KeyPoint> & wordsB,
475  std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs,
476  bool ignoreInvalidIds)
477 {
478  const std::list<int> & ids = uUniqueKeys(wordsA);
479  int realPairsCount = 0;
480  pairs.clear();
481  for(std::list<int>::const_iterator i=ids.begin(); i!=ids.end(); ++i)
482  {
483  if(!ignoreInvalidIds || (ignoreInvalidIds && *i>=0))
484  {
485  std::list<cv::KeyPoint> ptsA = uValues(wordsA, *i);
486  std::list<cv::KeyPoint> ptsB = uValues(wordsB, *i);
487  if(ptsA.size() == 1 && ptsB.size() == 1)
488  {
489  pairs.push_back(std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> >(*i, std::pair<cv::KeyPoint, cv::KeyPoint>(ptsA.front(), ptsB.front())));
490  ++realPairsCount;
491  }
492  else if(ptsA.size()>1 && ptsB.size()>1)
493  {
494  // just update the count
495  realPairsCount += ptsA.size() > ptsB.size() ? ptsB.size() : ptsA.size();
496  }
497  }
498  }
499  return realPairsCount;
500 }
501 
506 int EpipolarGeometry::findPairsAll(const std::multimap<int, cv::KeyPoint> & wordsA,
507  const std::multimap<int, cv::KeyPoint> & wordsB,
508  std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs,
509  bool ignoreInvalidIds)
510 {
511  UTimer timer;
512  timer.start();
513  const std::list<int> & ids = uUniqueKeys(wordsA);
514  pairs.clear();
515  int realPairsCount = 0;;
516  for(std::list<int>::const_iterator iter=ids.begin(); iter!=ids.end(); ++iter)
517  {
518  if(!ignoreInvalidIds || (ignoreInvalidIds && *iter>=0))
519  {
520  std::list<cv::KeyPoint> ptsA = uValues(wordsA, *iter);
521  std::list<cv::KeyPoint> ptsB = uValues(wordsB, *iter);
522 
523  realPairsCount += ptsA.size() > ptsB.size() ? ptsB.size() : ptsA.size();
524 
525  for(std::list<cv::KeyPoint>::iterator jter=ptsA.begin(); jter!=ptsA.end(); ++jter)
526  {
527  for(std::list<cv::KeyPoint>::iterator kter=ptsB.begin(); kter!=ptsB.end(); ++kter)
528  {
529  pairs.push_back(std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> >(*iter, std::pair<cv::KeyPoint, cv::KeyPoint>(*jter, *kter)));
530  }
531  }
532  }
533  }
534  ULOGGER_DEBUG("time = %f", timer.ticks());
535  return realPairsCount;
536 }
537 
538 
539 
546  cv::Point3d u, //homogenous image point (u,v,1)
547  cv::Matx34d P, //camera 1 matrix 3x4 double
548  cv::Point3d u1, //homogenous image point in 2nd camera
549  cv::Matx34d P1 //camera 2 matrix 3x4 double
550  )
551 {
552  //build matrix A for homogenous equation system Ax = 0
553  //assume X = (x,y,z,1), for Linear-LS method
554  //which turns it into a AX = B system, where A is 4x3, X is 3x1 and B is 4x1
555  cv::Mat A = (cv::Mat_<double>(4,3) <<
556  u.x*P(2,0)-P(0,0), u.x*P(2,1)-P(0,1), u.x*P(2,2)-P(0,2),
557  u.y*P(2,0)-P(1,0), u.y*P(2,1)-P(1,1), u.y*P(2,2)-P(1,2),
558  u1.x*P1(2,0)-P1(0,0), u1.x*P1(2,1)-P1(0,1), u1.x*P1(2,2)-P1(0,2),
559  u1.y*P1(2,0)-P1(1,0), u1.y*P1(2,1)-P1(1,1), u1.y*P1(2,2)-P1(1,2)
560  );
561  cv::Mat B = (cv::Mat_<double>(4,1) <<
562  -(u.x*P(2,3) -P(0,3)),
563  -(u.y*P(2,3) -P(1,3)),
564  -(u1.x*P1(2,3) -P1(0,3)),
565  -(u1.y*P1(2,3) -P1(1,3)));
566 
567  cv::Mat X;
568  solve(A,B,X,cv::DECOMP_SVD);
569 
570  return X; // return 1x3 double
571 }
572 
579  cv::Point3d u, //homogenous image point (u,v,1)
580  const cv::Matx34d & P, //camera 1 matrix 3x4 double
581  cv::Point3d u1, //homogenous image point in 2nd camera
582  const cv::Matx34d & P1) //camera 2 matrix 3x4 double
583 {
584  double wi = 1, wi1 = 1;
585  double EPSILON = 0.0001;
586 
587  cv::Mat X(4,1,CV_64FC1);
588  cv::Mat X_ = linearLSTriangulation(u,P,u1,P1);
589  X.at<double>(0) = X_.at<double>(0);
590  X.at<double>(1) = X_.at<double>(1);
591  X.at<double>(2) = X_.at<double>(2);
592  X.at<double>(3) = 1.0;
593  for (int i=0; i<10; i++) //Hartley suggests 10 iterations at most
594  {
595  //recalculate weights
596  double p2x = cv::Mat(cv::Mat(P).row(2)*X).at<double>(0);
597  double p2x1 = cv::Mat(cv::Mat(P1).row(2)*X).at<double>(0);
598 
599  //breaking point
600  if(fabs(wi - p2x) <= EPSILON && fabs(wi1 - p2x1) <= EPSILON) break;
601 
602  wi = p2x;
603  wi1 = p2x1;
604 
605  //reweight equations and solve
606  cv::Mat A = (cv::Mat_<double>(4,3) <<
607  (u.x*P(2,0)-P(0,0))/wi, (u.x*P(2,1)-P(0,1))/wi, (u.x*P(2,2)-P(0,2))/wi,
608  (u.y*P(2,0)-P(1,0))/wi, (u.y*P(2,1)-P(1,1))/wi, (u.y*P(2,2)-P(1,2))/wi,
609  (u1.x*P1(2,0)-P1(0,0))/wi1, (u1.x*P1(2,1)-P1(0,1))/wi1, (u1.x*P1(2,2)-P1(0,2))/wi1,
610  (u1.y*P1(2,0)-P1(1,0))/wi1, (u1.y*P1(2,1)-P1(1,1))/wi1, (u1.y*P1(2,2)-P1(1,2))/wi1);
611  cv::Mat B = (cv::Mat_<double>(4,1) <<
612  -(u.x*P(2,3) -P(0,3))/wi,
613  -(u.y*P(2,3) -P(1,3))/wi,
614  -(u1.x*P1(2,3) -P1(0,3))/wi1,
615  -(u1.y*P1(2,3) -P1(1,3))/wi1);
616 
617  solve(A,B,X_,cv::DECOMP_SVD);
618  X.at<double>(0) = X_.at<double>(0);
619  X.at<double>(1) = X_.at<double>(1);
620  X.at<double>(2) = X_.at<double>(2);
621  X.at<double>(3) = 1.0;
622  }
623  return X; // return 4x1 double
624 }
625 
629 //Triagulate points
631  const cv::Mat& pt_set, //2xN double
632  const cv::Mat& pt_set1, //2xN double
633  const cv::Mat& P, // 3x4 double
634  const cv::Mat& P1, // 3x4 double
635  pcl::PointCloud<pcl::PointXYZ>::Ptr & pointcloud,
636  std::vector<double> & reproj_errors)
637 {
638  pointcloud.reset(new pcl::PointCloud<pcl::PointXYZ>);
639 
640  unsigned int pts_size = pt_set.cols;
641 
642  pointcloud->resize(pts_size);
643  reproj_errors.resize(pts_size);
644 
645  for(unsigned int i=0; i<pts_size; i++)
646  {
647  cv::Point3d u(pt_set.at<double>(0,i),pt_set.at<double>(1,i),1.0);
648  cv::Point3d u1(pt_set1.at<double>(0,i),pt_set1.at<double>(1,i),1.0);
649 
650  cv::Mat X = iterativeLinearLSTriangulation(u,P,u1,P1);
651 
652  cv::Mat x_proj = P * X; //reproject
653  x_proj = x_proj / x_proj.at<double>(2);
654  cv::Point3d xPt_img_(x_proj.at<double>(0), x_proj.at<double>(1), 1.0);
655 
656  double reprj_err = norm(xPt_img_ - u);
657  reproj_errors[i] = reprj_err;
658  pointcloud->at(i) = pcl::PointXYZ(X.at<double>(0),X.at<double>(1),X.at<double>(2));
659  }
660 
661  return cv::mean(reproj_errors)[0]; // mean reproj error
662 }
663 
664 } // namespace rtabmap
std::list< K > uUniqueKeys(const std::multimap< K, V > &mm)
Definition: UStl.h:46
static bool parse(const ParametersMap &parameters, const std::string &key, bool &value)
Definition: Parameters.cpp:446
Definition: UTimer.h:46
static int findPairs(const std::map< int, cv::KeyPoint > &wordsA, const std::map< int, cv::KeyPoint > &wordsB, std::list< std::pair< int, std::pair< cv::KeyPoint, cv::KeyPoint > > > &pairs, bool ignoreNegativeIds=true)
static cv::Mat findFFromCalibratedStereoCameras(double fx, double fy, double cx, double cy, double Tx, double Ty)
const std::multimap< int, cv::KeyPoint > & getWords() const
Definition: Signature.h:108
f
int inFrontOfBothCameras(const cv::Mat &x, const cv::Mat &xp, const cv::Mat &R, const cv::Mat &T)
EpipolarGeometry(const ParametersMap &parameters=ParametersMap())
GLM_FUNC_DECL genType e()
void parseParameters(const ParametersMap &parameters)
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:41
GLM_FUNC_DECL genType::row_type row(genType const &m, length_t const &index)
GLM_FUNC_DECL T determinant(matType< T, P > const &m)
Basic mathematics functions.
static int findPairsUnique(const std::multimap< int, cv::KeyPoint > &wordsA, const std::multimap< int, cv::KeyPoint > &wordsB, std::list< std::pair< int, std::pair< cv::KeyPoint, cv::KeyPoint > > > &pairs, bool ignoreNegativeIds=true)
static cv::Mat findFFromWords(const std::list< std::pair< int, std::pair< cv::KeyPoint, cv::KeyPoint > > > &pairs, std::vector< uchar > &status, double ransacParam1=3.0, double ransacParam2=0.99)
#define UASSERT(condition)
Wrappers of STL for convenient functions.
static double triangulatePoints(const cv::Mat &pt_set1, const cv::Mat &pt_set2, const cv::Mat &P, const cv::Mat &P1, pcl::PointCloud< pcl::PointXYZ >::Ptr &pointcloud, std::vector< double > &reproj_errors)
static int findPairsAll(const std::multimap< int, cv::KeyPoint > &wordsA, const std::multimap< int, cv::KeyPoint > &wordsB, std::list< std::pair< int, std::pair< cv::KeyPoint, cv::KeyPoint > > > &pairs, bool ignoreNegativeIds=true)
#define ULOGGER_DEBUG(...)
Definition: ULogger.h:53
static cv::Mat linearLSTriangulation(cv::Point3d u, cv::Matx34d P, cv::Point3d u1, cv::Matx34d P1)
static void findEpipolesFromF(const cv::Mat &fundamentalMatrix, cv::Vec3d &e1, cv::Vec3d &e2)
int id() const
Definition: Signature.h:70
bool check(const Signature *ssA, const Signature *ssB)
void start()
Definition: UTimer.cpp:80
std::vector< V > uValues(const std::multimap< K, V > &mm)
Definition: UStl.h:100
#define UDEBUG(...)
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
ULogger class and convenient macros.
double ticks()
Definition: UTimer.cpp:110
static void findRTFromP(const cv::Mat &p, cv::Mat &r, cv::Mat &t)
T uSum(const std::list< T > &list)
Definition: UMath.h:320
#define ULOGGER_ERROR(...)
Definition: ULogger.h:56
static cv::Mat findPFromE(const cv::Mat &E, const cv::Mat &x, const cv::Mat &xp)
static cv::Mat iterativeLinearLSTriangulation(cv::Point3d u, const cv::Matx34d &P, cv::Point3d u1, const cv::Matx34d &P1)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:31