35 #include <opencv2/core/core.hpp> 36 #include <opencv2/core/core_c.h> 37 #include <opencv2/calib3d/calib3d.hpp> 47 _matchCountMinAccepted(
Parameters::defaultVhEpMatchCountMin()),
48 _ransacParam1(
Parameters::defaultVhEpRansacParam1()),
49 _ransacParam2(
Parameters::defaultVhEpRansacParam2())
67 if(ssA == 0 || ssB == 0)
73 std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > pairs;
82 std::vector<uchar> status;
85 int inliers =
uSum(status);
93 UDEBUG(
"inliers = %d/%d", inliers, pairs.size());
102 if(fundamentalMatrix.rows != 3 || fundamentalMatrix.cols != 3)
108 if(fundamentalMatrix.type() != CV_64FC1)
115 cv::SVD svd(fundamentalMatrix);
123 e1[0] = v.at<
double>(0,2);
124 e1[1] = v.at<
double>(1,2);
125 e1[2] = v.at<
double>(2,2);
127 e2[0] = u.at<
double>(0,2);
128 e2[1] = u.at<
double>(1,2);
129 e2[2] = u.at<
double>(2,2);
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);
157 cv::triangulatePoints(p0, p, x, xp, pts4D);
161 for(
int i=0; i<x.cols; ++i)
164 if(pts4D.at<
double>(2,i)/pts4D.at<
double>(3,i) > 5)
170 UDEBUG(
"nValid=%d/%d", nValid, x.cols);
184 UASSERT(E.rows == 3 && E.cols == 3);
186 UASSERT(x.rows == 2 && x.cols>0 && x.type() == CV_64FC1);
187 UASSERT(xp.rows == 2 && xp.cols>0 && x.type() == CV_64FC1);
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;
197 cv::SVD svd(e,cv::SVD::MODIFY_A);
207 cv::Mat diag = cv::Mat::eye(3,3,CV_64FC1);
208 diag.at<
double>(2,2) = 0;
210 svd(e,cv::SVD::MODIFY_A);
220 svd(e,cv::SVD::MODIFY_A);
231 cv::Mat r2 = u*wt*vt;
233 cv::Mat t1 = u.col(2);
234 cv::Mat t2 = u.col(2)*-1;
270 UDEBUG(
"Case %d", maxIndex);
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);
293 const std::list<std::pair<
int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs,
294 std::vector<uchar> & status,
299 status = std::vector<uchar>(pairs.size(), 0);
302 cv::Mat points1(1, pairs.size(), CV_32FC2);
303 cv::Mat points2(1, pairs.size(), CV_32FC2);
305 float * points1data = points1.ptr<
float>(0);
306 float * points2data = points2.ptr<
float>(0);
310 for(std::list<std::pair<
int, std::pair<cv::KeyPoint, cv::KeyPoint> > >::const_iterator iter = pairs.begin();
314 points1data[i*2] = (*iter).second.first.pt.x;
315 points1data[i*2+1] = (*iter).second.first.pt.y;
317 points2data[i*2] = (*iter).second.second.pt.x;
318 points2data[i*2+1] = (*iter).second.second.pt.y;
327 cv::Mat fundamentalMatrix = cv::findFundamentalMat(
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) )
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]);
372 return fundamentalMatrix;
380 UASSERT(p.cols == 4 && p.rows == 3);
381 r = cv::Mat(p, cv::Range(0,3), cv::Range(0,3));
389 cv::Mat R = cv::Mat::eye(3, 3, CV_64FC1);
394 cv::Mat tx = (cv::Mat_<double>(3,3) <<
399 cv::Mat K = (cv::Mat_<double>(3,3) <<
406 return K.inv().t()*E*K.inv();
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)
419 int realPairsCount = 0;
421 for(std::map<int, cv::KeyPoint>::const_iterator i=wordsA.begin(); i!=wordsA.end(); ++i)
423 if(!ignoreInvalidIds || (ignoreInvalidIds && i->first>=0))
425 std::map<int, cv::KeyPoint>::const_iterator ptB = wordsB.find(i->first);
426 if(ptB != wordsB.end())
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)));
433 return realPairsCount;
441 const std::multimap<int, cv::KeyPoint> & wordsB,
442 std::list<std::pair<
int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs,
443 bool ignoreInvalidIds)
446 std::multimap<int, cv::KeyPoint>::const_iterator iterA;
447 std::multimap<int, cv::KeyPoint>::const_iterator iterB;
449 int realPairsCount = 0;
450 for(std::list<int>::const_iterator i=ids.begin(); i!=ids.end(); ++i)
452 if(!ignoreInvalidIds || (ignoreInvalidIds && *i >= 0))
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)
458 pairs.push_back(std::pair<
int, std::pair<cv::KeyPoint, cv::KeyPoint> >(*i, std::pair<cv::KeyPoint, cv::KeyPoint>((*iterA).second, (*iterB).second)));
465 return realPairsCount;
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)
479 int realPairsCount = 0;
481 for(std::list<int>::const_iterator i=ids.begin(); i!=ids.end(); ++i)
483 if(!ignoreInvalidIds || (ignoreInvalidIds && *i>=0))
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)
489 pairs.push_back(std::pair<
int, std::pair<cv::KeyPoint, cv::KeyPoint> >(*i, std::pair<cv::KeyPoint, cv::KeyPoint>(ptsA.front(), ptsB.front())));
492 else if(ptsA.size()>1 && ptsB.size()>1)
495 realPairsCount += ptsA.size() > ptsB.size() ? ptsB.size() : ptsA.size();
499 return realPairsCount;
507 const std::multimap<int, cv::KeyPoint> & wordsB,
508 std::list<std::pair<
int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs,
509 bool ignoreInvalidIds)
515 int realPairsCount = 0;;
516 for(std::list<int>::const_iterator iter=ids.begin(); iter!=ids.end(); ++iter)
518 if(!ignoreInvalidIds || (ignoreInvalidIds && *iter>=0))
520 std::list<cv::KeyPoint> ptsA =
uValues(wordsA, *iter);
521 std::list<cv::KeyPoint> ptsB =
uValues(wordsB, *iter);
523 realPairsCount += ptsA.size() > ptsB.size() ? ptsB.size() : ptsA.size();
525 for(std::list<cv::KeyPoint>::iterator jter=ptsA.begin(); jter!=ptsA.end(); ++jter)
527 for(std::list<cv::KeyPoint>::iterator kter=ptsB.begin(); kter!=ptsB.end(); ++kter)
529 pairs.push_back(std::pair<
int, std::pair<cv::KeyPoint, cv::KeyPoint> >(*iter, std::pair<cv::KeyPoint, cv::KeyPoint>(*jter, *kter)));
535 return realPairsCount;
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)
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)));
568 solve(A,B,X,cv::DECOMP_SVD);
580 const cv::Matx34d & P,
582 const cv::Matx34d & P1)
584 double wi = 1, wi1 = 1;
585 double EPSILON = 0.0001;
587 cv::Mat X(4,1,CV_64FC1);
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++)
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);
600 if(fabs(wi - p2x) <= EPSILON && fabs(wi1 - p2x1) <= EPSILON)
break;
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);
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;
631 const cv::Mat& pt_set,
632 const cv::Mat& pt_set1,
635 pcl::PointCloud<pcl::PointXYZ>::Ptr & pointcloud,
636 std::vector<double> & reproj_errors)
638 pointcloud.reset(
new pcl::PointCloud<pcl::PointXYZ>);
640 unsigned int pts_size = pt_set.cols;
642 pointcloud->resize(pts_size);
643 reproj_errors.resize(pts_size);
645 for(
unsigned int i=0; i<pts_size; i++)
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);
652 cv::Mat x_proj = P * X;
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);
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));
661 return cv::mean(reproj_errors)[0];
std::list< K > uUniqueKeys(const std::multimap< K, V > &mm)
static bool parse(const ParametersMap ¶meters, const std::string &key, bool &value)
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
int inFrontOfBothCameras(const cv::Mat &x, const cv::Mat &xp, const cv::Mat &R, const cv::Mat &T)
EpipolarGeometry(const ParametersMap ¶meters=ParametersMap())
GLM_FUNC_DECL genType e()
void parseParameters(const ParametersMap ¶meters)
std::map< std::string, std::string > ParametersMap
int _matchCountMinAccepted
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)
virtual ~EpipolarGeometry()
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(...)
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)
bool check(const Signature *ssA, const Signature *ssB)
std::vector< V > uValues(const std::multimap< K, V > &mm)
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
ULogger class and convenient macros.
static void findRTFromP(const cv::Mat &p, cv::Mat &r, cv::Mat &t)
T uSum(const std::list< T > &list)
#define ULOGGER_ERROR(...)
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)