EpipolarGeometry.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #include "rtabmap/core/EpipolarGeometry.h"
00029 #include "rtabmap/core/Signature.h"
00030 #include "rtabmap/utilite/ULogger.h"
00031 #include "rtabmap/utilite/UTimer.h"
00032 #include "rtabmap/utilite/UStl.h"
00033 #include "rtabmap/utilite/UMath.h"
00034 
00035 #include <opencv2/core/core.hpp>
00036 #include <opencv2/core/core_c.h>
00037 #include <opencv2/calib3d/calib3d.hpp>
00038 #include <iostream>
00039 
00040 namespace rtabmap
00041 {
00042 
00044 // HypVerificatorEpipolarGeo
00046 EpipolarGeometry::EpipolarGeometry(const ParametersMap & parameters) :
00047         _matchCountMinAccepted(Parameters::defaultVhEpMatchCountMin()),
00048         _ransacParam1(Parameters::defaultVhEpRansacParam1()),
00049         _ransacParam2(Parameters::defaultVhEpRansacParam2())
00050 {
00051         this->parseParameters(parameters);
00052 }
00053 
00054 EpipolarGeometry::~EpipolarGeometry() {
00055 
00056 }
00057 
00058 void EpipolarGeometry::parseParameters(const ParametersMap & parameters)
00059 {
00060         Parameters::parse(parameters, Parameters::kVhEpMatchCountMin(), _matchCountMinAccepted);
00061         Parameters::parse(parameters, Parameters::kVhEpRansacParam1(), _ransacParam1);
00062         Parameters::parse(parameters, Parameters::kVhEpRansacParam2(), _ransacParam2);
00063 }
00064 
00065 bool EpipolarGeometry::check(const Signature * ssA, const Signature * ssB)
00066 {
00067         if(ssA == 0 || ssB == 0)
00068         {
00069                 return false;
00070         }
00071         ULOGGER_DEBUG("id(%d,%d)", ssA->id(), ssB->id());
00072 
00073         std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > pairs;
00074 
00075         findPairsUnique(ssA->getWords(), ssB->getWords(), pairs);
00076 
00077         if((int)pairs.size()<_matchCountMinAccepted)
00078         {
00079                 return false;
00080         }
00081 
00082         std::vector<uchar> status;
00083         cv::Mat f = findFFromWords(pairs, status, _ransacParam1, _ransacParam2);
00084 
00085         int inliers = uSum(status);
00086         if(inliers < _matchCountMinAccepted)
00087         {
00088                 ULOGGER_DEBUG("Epipolar constraint failed A : not enough inliers (%d/%d), min is %d", inliers, pairs.size(), _matchCountMinAccepted);
00089                 return false;
00090         }
00091         else
00092         {
00093                 UDEBUG("inliers = %d/%d", inliers, pairs.size());
00094                 return true;
00095         }
00096 }
00097 
00098 //STATIC STUFF
00099 //Epipolar geometry
00100 void EpipolarGeometry::findEpipolesFromF(const cv::Mat & fundamentalMatrix, cv::Vec3d & e1, cv::Vec3d & e2)
00101 {
00102         if(fundamentalMatrix.rows != 3 || fundamentalMatrix.cols != 3)
00103         {
00104                 ULOGGER_ERROR("The matrix is not the good size...");
00105                 return;
00106         }
00107 
00108         if(fundamentalMatrix.type() != CV_64FC1)
00109         {
00110                 ULOGGER_ERROR("The matrix is not the good type...");
00111                 return;
00112         }
00113 
00114 
00115         cv::SVD svd(fundamentalMatrix);
00116         cv::Mat u = svd.u;
00117         cv::Mat v = svd.vt;
00118         cv::Mat w = svd.w;
00119 
00120         // v is for image 1
00121         // u is for image 2
00122 
00123         e1[0] = v.at<double>(0,2);// /v->data.db[2*3+2];
00124         e1[1] = v.at<double>(1,2);// /v->data.db[2*3+2];
00125         e1[2] = v.at<double>(2,2);// /v->data.db[2*3+2];
00126 
00127         e2[0] = u.at<double>(0,2);// /u->data.db[2*3+2];
00128         e2[1] = u.at<double>(1,2);// /u->data.db[2*3+2];
00129         e2[2] = u.at<double>(2,2);// /u->data.db[2*3+2];
00130 }
00131 
00132 int inFrontOfBothCameras(const cv::Mat & x, const cv::Mat & xp, const cv::Mat & R, const cv::Mat & T)
00133 {
00134         // P0 matrix 3X4
00135         cv::Mat p0 = cv::Mat::zeros(3, 4, CV_64FC1);
00136         p0.at<double>(0,0) = 1;
00137         p0.at<double>(1,1) = 1;
00138         p0.at<double>(2,2) = 1;
00139         cv::Mat p = cv::Mat::zeros(3, 4, CV_64FC1);
00140         p.at<double>(0,0) = R.at<double>(0,0);
00141         p.at<double>(0,1) = R.at<double>(0,1);
00142         p.at<double>(0,2) = R.at<double>(0,2);
00143         p.at<double>(1,0) = R.at<double>(1,0);
00144         p.at<double>(1,1) = R.at<double>(1,1);
00145         p.at<double>(1,2) = R.at<double>(1,2);
00146         p.at<double>(2,0) = R.at<double>(2,0);
00147         p.at<double>(2,1) = R.at<double>(2,1);
00148         p.at<double>(2,2) = R.at<double>(2,2);
00149         p.at<double>(0,3) = T.at<double>(0,0);
00150         p.at<double>(1,3) = T.at<double>(1,0);
00151         p.at<double>(2,3) = T.at<double>(2,0);
00152 
00153         cv::Mat pts4D;
00154         //std::vector<double> reprojErrors;
00155         //pcl::PointCloud<pcl::PointXYZ>::Ptr cloud;
00156         //EpipolarGeometry::triangulatePoints(x, xp, p0, p, cloud, reprojErrors);
00157         cv::triangulatePoints(p0, p, x, xp, pts4D);
00158 
00159     //http://en.wikipedia.org/wiki/Essential_matrix#3D_points_from_corresponding_image_points
00160         int nValid = 0;
00161     for(int i=0; i<x.cols; ++i)
00162     {
00163         // the five to ignore when all points are super close to the camera
00164         if(pts4D.at<double>(2,i)/pts4D.at<double>(3,i) > 5)
00165         //if(cloud->at(i).z > 5)
00166         {
00167                 ++nValid;
00168         }
00169     }
00170     UDEBUG("nValid=%d/%d", nValid,  x.cols);
00171 
00172     return nValid;
00173 }
00174 
00175 //Assuming P0 = [eye(3) zeros(3,1)]
00176 // x1 and x2 are 2D points
00177 // return camera matrix P (3x4) matrix
00178 //http://www.robots.ox.ac.uk/~vgg/hzbook/hzbook2/HZepipolar.pdf
00179 cv::Mat EpipolarGeometry::findPFromE(const cv::Mat & E,
00180                 const cv::Mat & x,
00181                 const cv::Mat & xp)
00182 {
00183         UDEBUG("begin");
00184         UASSERT(E.rows == 3 && E.cols == 3);
00185         UASSERT(E.type() == CV_64FC1);
00186         UASSERT(x.rows == 2 && x.cols>0 && x.type() == CV_64FC1);
00187         UASSERT(xp.rows == 2 && xp.cols>0 && x.type() == CV_64FC1);
00188 
00189         // skew matrix 3X3
00190         cv::Mat w = cv::Mat::zeros( 3, 3, CV_64FC1);
00191         w.at<double>(0,1) = -1;
00192         w.at<double>(1,0) = 1;
00193         w.at<double>(2,2) = 1;
00194         //std::cout << "W=" << w << std::endl;
00195 
00196         cv::Mat e = E;
00197         cv::SVD svd(e,cv::SVD::MODIFY_A);
00198         cv::Mat u = svd.u;
00199         cv::Mat vt = svd.vt;
00200         cv::Mat s = svd.w;
00201 
00202         //std::cout << "u=" << u << std::endl;
00203         //std::cout << "vt=" << vt << std::endl;
00204         //std::cout << "s=" << s << std::endl;
00205 
00206         // E = u*diag(1,1,0)*vt
00207         cv::Mat diag = cv::Mat::eye(3,3,CV_64FC1);
00208         diag.at<double>(2,2) = 0;
00209         e = u*diag*vt;
00210         svd(e,cv::SVD::MODIFY_A);
00211         u = svd.u;
00212         vt = svd.vt;
00213         s = svd.w;
00214 
00215         cv::Mat r = u*w*vt;
00216         if(cv::determinant(r)+1.0 < 1e-09) {
00217                 //according to http://en.wikipedia.org/wiki/Essential_matrix#Showing_that_it_is_valid
00218                 UDEBUG("det(R) == -1 [%f]: flip E's sign", cv::determinant(r));
00219                 e = -E;
00220                 svd(e,cv::SVD::MODIFY_A);
00221                 u = svd.u;
00222                 vt = svd.vt;
00223                 s = svd.w;
00224         }
00225         cv::Mat wt = w.t();
00226 
00227         // INFO: There 4 cases of P, only one have all the points in
00228         // front of the two cameras (positive z).
00229 
00230         cv::Mat r1 = u*w*vt;
00231         cv::Mat r2 = u*wt*vt;
00232 
00233         cv::Mat t1 = u.col(2);
00234         cv::Mat t2 = u.col(2)*-1;
00235 
00236         int max = 0;
00237         int maxIndex = 1;
00238         int maxTmp;
00239         cv::Mat R=r1,T=t1;
00240 
00241         // Case 1 : P = [U*W*V' t];
00242         max = inFrontOfBothCameras(x, xp, r1, t1);
00243         // Case 2 : P = [U*W*V' -t];
00244         maxTmp = inFrontOfBothCameras(x, xp, r1, t2);
00245         if(maxTmp > max)
00246         {
00247                 maxIndex = 2;
00248                 max = maxTmp;
00249                 R=r1,T=t2;
00250         }
00251         // Case 3 : P = [U*W'*V' t];
00252         maxTmp = inFrontOfBothCameras(x, xp, r2, t1);
00253         if(maxTmp > max)
00254         {
00255                 maxIndex = 3;
00256                 max = maxTmp;
00257                 R=r2,T=t1;
00258         }
00259         // Case 4 : P = [U*W'*V' -t];
00260         maxTmp = inFrontOfBothCameras(x, xp, r2, t2);
00261         if(maxTmp > max)
00262         {
00263                 maxIndex = 4;
00264                 max = maxTmp;
00265                 R=r2,T=t2;
00266         }
00267 
00268         if(max > 0)
00269         {
00270                 UDEBUG("Case %d", maxIndex);
00271 
00272                 // P matrix 3x4
00273                 cv::Mat p = cv::Mat::zeros(3, 4, CV_64FC1);
00274                 p.at<double>(0,0) = R.at<double>(0,0);
00275                 p.at<double>(0,1) = R.at<double>(0,1);
00276                 p.at<double>(0,2) = R.at<double>(0,2);
00277                 p.at<double>(1,0) = R.at<double>(1,0);
00278                 p.at<double>(1,1) = R.at<double>(1,1);
00279                 p.at<double>(1,2) = R.at<double>(1,2);
00280                 p.at<double>(2,0) = R.at<double>(2,0);
00281                 p.at<double>(2,1) = R.at<double>(2,1);
00282                 p.at<double>(2,2) = R.at<double>(2,2);
00283                 p.at<double>(0,3) = T.at<double>(0);
00284                 p.at<double>(1,3) = T.at<double>(1);
00285                 p.at<double>(2,3) = T.at<double>(2);
00286                 return p;
00287         }
00288 
00289         return cv::Mat();
00290 }
00291 
00292 cv::Mat EpipolarGeometry::findFFromWords(
00293                 const std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs, // id, kpt1, kpt2
00294                 std::vector<uchar> & status,
00295                 double ransacParam1,
00296                 double ransacParam2)
00297 {
00298 
00299         status = std::vector<uchar>(pairs.size(), 0);
00300         //Convert Keypoints to a structure that OpenCV understands
00301         //3 dimensions (Homogeneous vectors)
00302         cv::Mat points1(1, pairs.size(), CV_32FC2);
00303         cv::Mat points2(1, pairs.size(), CV_32FC2);
00304 
00305         float * points1data = points1.ptr<float>(0);
00306         float * points2data = points2.ptr<float>(0);
00307 
00308         // Fill the points here ...
00309         int i=0;
00310         for(std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > >::const_iterator iter = pairs.begin();
00311                 iter != pairs.end();
00312                 ++iter )
00313         {
00314                 points1data[i*2] = (*iter).second.first.pt.x;
00315                 points1data[i*2+1] = (*iter).second.first.pt.y;
00316 
00317                 points2data[i*2] = (*iter).second.second.pt.x;
00318                 points2data[i*2+1] = (*iter).second.second.pt.y;
00319 
00320                 ++i;
00321         }
00322 
00323         UTimer timer;
00324         timer.start();
00325 
00326         // Find the fundamental matrix
00327         cv::Mat fundamentalMatrix = cv::findFundamentalMat(
00328                                 points1,
00329                                 points2,
00330                                 status,
00331                                 cv::FM_RANSAC,
00332                                 ransacParam1,
00333                                 ransacParam2);
00334 
00335         ULOGGER_DEBUG("Find fundamental matrix (OpenCV) time = %fs", timer.ticks());
00336 
00337                 // Fundamental matrix is valid ?
00338         bool fundMatFound = false;
00339         UASSERT(fundamentalMatrix.type() == CV_64FC1);
00340         if(fundamentalMatrix.cols==3 && fundamentalMatrix.rows==3 &&
00341            (fundamentalMatrix.at<double>(0,0) != 0.0 ||
00342             fundamentalMatrix.at<double>(0,1) != 0.0 ||
00343             fundamentalMatrix.at<double>(0,2) != 0.0 ||
00344             fundamentalMatrix.at<double>(1,0) != 0.0 ||
00345             fundamentalMatrix.at<double>(1,1) != 0.0 ||
00346             fundamentalMatrix.at<double>(1,2) != 0.0 ||
00347                 fundamentalMatrix.at<double>(2,0) != 0.0 ||
00348                 fundamentalMatrix.at<double>(2,1) != 0.0 ||
00349                 fundamentalMatrix.at<double>(2,2) != 0.0) )
00350 
00351         {
00352                 fundMatFound = true;
00353         }
00354 
00355         ULOGGER_DEBUG("fm_count=%d...", fundMatFound);
00356 
00357         if(fundMatFound)
00358         {
00359                 // Show the fundamental matrix
00360                 UDEBUG(
00361                         "F = [%f %f %f;%f %f %f;%f %f %f]",
00362                         fundamentalMatrix.ptr<double>(0)[0],
00363                         fundamentalMatrix.ptr<double>(0)[1],
00364                         fundamentalMatrix.ptr<double>(0)[2],
00365                         fundamentalMatrix.ptr<double>(0)[3],
00366                         fundamentalMatrix.ptr<double>(0)[4],
00367                         fundamentalMatrix.ptr<double>(0)[5],
00368                         fundamentalMatrix.ptr<double>(0)[6],
00369                         fundamentalMatrix.ptr<double>(0)[7],
00370                         fundamentalMatrix.ptr<double>(0)[8]);
00371         }
00372         return fundamentalMatrix;
00373 }
00374 
00375 void EpipolarGeometry::findRTFromP(
00376                 const cv::Mat & p,
00377                 cv::Mat & r,
00378                 cv::Mat & t)
00379 {
00380         UASSERT(p.cols == 4 && p.rows == 3);
00381         r = cv::Mat(p, cv::Range(0,3), cv::Range(0,3));
00382         //r = -r.inv();
00383         //t = r*p.col(3);
00384         t = p.col(3);
00385 }
00386 
00387 cv::Mat EpipolarGeometry::findFFromCalibratedStereoCameras(double fx, double fy, double cx, double cy, double Tx, double Ty)
00388 {
00389         cv::Mat R = cv::Mat::eye(3, 3, CV_64FC1);
00390 
00391         double Bx = Tx/-fx;
00392         double By = Ty/-fy;
00393 
00394         cv::Mat tx = (cv::Mat_<double>(3,3) <<
00395                         0, 0, By,
00396                         0, 0, -Bx,
00397                         -By, Bx, 0);
00398 
00399         cv::Mat K = (cv::Mat_<double>(3,3) <<
00400                         fx, 0, cx,
00401                         0, fy, cy,
00402                         0, 0, 1);
00403 
00404         cv::Mat E = tx*R;
00405 
00406         return K.inv().t()*E*K.inv();
00407 }
00408 
00413 int EpipolarGeometry::findPairs(
00414                 const std::map<int, cv::KeyPoint> & wordsA,
00415                 const std::map<int, cv::KeyPoint> & wordsB,
00416                 std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs,
00417                 bool ignoreInvalidIds)
00418 {
00419         int realPairsCount = 0;
00420         pairs.clear();
00421         for(std::map<int, cv::KeyPoint>::const_iterator i=wordsA.begin(); i!=wordsA.end(); ++i)
00422         {
00423                 if(!ignoreInvalidIds || (ignoreInvalidIds && i->first>=0))
00424                 {
00425                         std::map<int, cv::KeyPoint>::const_iterator ptB = wordsB.find(i->first);
00426                         if(ptB != wordsB.end())
00427                         {
00428                                 pairs.push_back(std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> >(i->first, std::pair<cv::KeyPoint, cv::KeyPoint>(i->second, ptB->second)));
00429                                 ++realPairsCount;
00430                         }
00431                 }
00432         }
00433         return realPairsCount;
00434 }
00435 
00440 int EpipolarGeometry::findPairs(const std::multimap<int, cv::KeyPoint> & wordsA,
00441                 const std::multimap<int, cv::KeyPoint> & wordsB,
00442                 std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs,
00443                 bool ignoreInvalidIds)
00444 {
00445         const std::list<int> & ids = uUniqueKeys(wordsA);
00446         std::multimap<int, cv::KeyPoint>::const_iterator iterA;
00447         std::multimap<int, cv::KeyPoint>::const_iterator iterB;
00448         pairs.clear();
00449         int realPairsCount = 0;
00450         for(std::list<int>::const_iterator i=ids.begin(); i!=ids.end(); ++i)
00451         {
00452                 if(!ignoreInvalidIds || (ignoreInvalidIds && *i >= 0))
00453                 {
00454                         iterA = wordsA.find(*i);
00455                         iterB = wordsB.find(*i);
00456                         while(iterA != wordsA.end() && iterB != wordsB.end() && (*iterA).first == (*iterB).first && (*iterA).first == *i)
00457                         {
00458                                 pairs.push_back(std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> >(*i, std::pair<cv::KeyPoint, cv::KeyPoint>((*iterA).second, (*iterB).second)));
00459                                 ++iterA;
00460                                 ++iterB;
00461                                 ++realPairsCount;
00462                         }
00463                 }
00464         }
00465         return realPairsCount;
00466 }
00467 
00472 int EpipolarGeometry::findPairsUnique(
00473                 const std::multimap<int, cv::KeyPoint> & wordsA,
00474                 const std::multimap<int, cv::KeyPoint> & wordsB,
00475                 std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs,
00476                 bool ignoreInvalidIds)
00477 {
00478         const std::list<int> & ids = uUniqueKeys(wordsA);
00479         int realPairsCount = 0;
00480         pairs.clear();
00481         for(std::list<int>::const_iterator i=ids.begin(); i!=ids.end(); ++i)
00482         {
00483                 if(!ignoreInvalidIds || (ignoreInvalidIds && *i>=0))
00484                 {
00485                         std::list<cv::KeyPoint> ptsA = uValues(wordsA, *i);
00486                         std::list<cv::KeyPoint> ptsB = uValues(wordsB, *i);
00487                         if(ptsA.size() == 1 && ptsB.size() == 1)
00488                         {
00489                                 pairs.push_back(std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> >(*i, std::pair<cv::KeyPoint, cv::KeyPoint>(ptsA.front(), ptsB.front())));
00490                                 ++realPairsCount;
00491                         }
00492                         else if(ptsA.size()>1 && ptsB.size()>1)
00493                         {
00494                                 // just update the count
00495                                 realPairsCount += ptsA.size() > ptsB.size() ? ptsB.size() : ptsA.size();
00496                         }
00497                 }
00498         }
00499         return realPairsCount;
00500 }
00501 
00506 int EpipolarGeometry::findPairsAll(const std::multimap<int, cv::KeyPoint> & wordsA,
00507                 const std::multimap<int, cv::KeyPoint> & wordsB,
00508                 std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs,
00509                 bool ignoreInvalidIds)
00510 {
00511         UTimer timer;
00512         timer.start();
00513         const std::list<int> & ids = uUniqueKeys(wordsA);
00514         pairs.clear();
00515         int realPairsCount = 0;;
00516         for(std::list<int>::const_iterator iter=ids.begin(); iter!=ids.end(); ++iter)
00517         {
00518                 if(!ignoreInvalidIds || (ignoreInvalidIds && *iter>=0))
00519                 {
00520                         std::list<cv::KeyPoint> ptsA = uValues(wordsA, *iter);
00521                         std::list<cv::KeyPoint> ptsB = uValues(wordsB, *iter);
00522 
00523                         realPairsCount += ptsA.size() > ptsB.size() ? ptsB.size() : ptsA.size();
00524 
00525                         for(std::list<cv::KeyPoint>::iterator jter=ptsA.begin(); jter!=ptsA.end(); ++jter)
00526                         {
00527                                 for(std::list<cv::KeyPoint>::iterator kter=ptsB.begin(); kter!=ptsB.end(); ++kter)
00528                                 {
00529                                         pairs.push_back(std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> >(*iter, std::pair<cv::KeyPoint, cv::KeyPoint>(*jter, *kter)));
00530                                 }
00531                         }
00532                 }
00533         }
00534         ULOGGER_DEBUG("time = %f", timer.ticks());
00535         return realPairsCount;
00536 }
00537 
00538 
00539 
00545 cv::Mat EpipolarGeometry::linearLSTriangulation(
00546                 cv::Point3d u,   //homogenous image point (u,v,1)
00547                 cv::Matx34d P,       //camera 1 matrix 3x4 double
00548                 cv::Point3d u1,  //homogenous image point in 2nd camera
00549                 cv::Matx34d P1       //camera 2 matrix 3x4 double
00550                                    )
00551 {
00552     //build matrix A for homogenous equation system Ax = 0
00553     //assume X = (x,y,z,1), for Linear-LS method
00554     //which turns it into a AX = B system, where A is 4x3, X is 3x1 and B is 4x1
00555     cv::Mat A = (cv::Mat_<double>(4,3) <<
00556                 u.x*P(2,0)-P(0,0),    u.x*P(2,1)-P(0,1),      u.x*P(2,2)-P(0,2),
00557                         u.y*P(2,0)-P(1,0),    u.y*P(2,1)-P(1,1),      u.y*P(2,2)-P(1,2),
00558                         u1.x*P1(2,0)-P1(0,0), u1.x*P1(2,1)-P1(0,1),   u1.x*P1(2,2)-P1(0,2),
00559                         u1.y*P1(2,0)-P1(1,0), u1.y*P1(2,1)-P1(1,1),   u1.y*P1(2,2)-P1(1,2)
00560               );
00561     cv::Mat B = (cv::Mat_<double>(4,1) <<
00562                         -(u.x*P(2,3)    -P(0,3)),
00563                         -(u.y*P(2,3)  -P(1,3)),
00564                         -(u1.x*P1(2,3)    -P1(0,3)),
00565                         -(u1.y*P1(2,3)    -P1(1,3)));
00566 
00567     cv::Mat X;
00568     solve(A,B,X,cv::DECOMP_SVD);
00569 
00570     return X; // return 1x3 double
00571 }
00572 
00578 cv::Mat EpipolarGeometry::iterativeLinearLSTriangulation(
00579                 cv::Point3d u,            //homogenous image point (u,v,1)
00580                 const cv::Matx34d & P,   //camera 1 matrix 3x4 double
00581                 cv::Point3d u1,           //homogenous image point in 2nd camera
00582                 const cv::Matx34d & P1)   //camera 2 matrix 3x4 double
00583 {
00584     double wi = 1, wi1 = 1;
00585         double EPSILON = 0.0001;
00586 
00587         cv::Mat X(4,1,CV_64FC1);
00588         cv::Mat X_ = linearLSTriangulation(u,P,u1,P1);
00589         X.at<double>(0) = X_.at<double>(0);
00590         X.at<double>(1) = X_.at<double>(1);
00591         X.at<double>(2) = X_.at<double>(2);
00592         X.at<double>(3) = 1.0;
00593         for (int i=0; i<10; i++)  //Hartley suggests 10 iterations at most
00594         {
00595         //recalculate weights
00596         double p2x = cv::Mat(cv::Mat(P).row(2)*X).at<double>(0);
00597         double p2x1 = cv::Mat(cv::Mat(P1).row(2)*X).at<double>(0);
00598 
00599         //breaking point
00600         if(fabs(wi - p2x) <= EPSILON && fabs(wi1 - p2x1) <= EPSILON) break;
00601 
00602         wi = p2x;
00603         wi1 = p2x1;
00604 
00605         //reweight equations and solve
00606         cv::Mat A = (cv::Mat_<double>(4,3) <<
00607                         (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,
00608                                 (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,
00609                                 (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,
00610                                 (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);
00611         cv::Mat B = (cv::Mat_<double>(4,1) <<
00612                         -(u.x*P(2,3)    -P(0,3))/wi,
00613                                 -(u.y*P(2,3)  -P(1,3))/wi,
00614                                 -(u1.x*P1(2,3)    -P1(0,3))/wi1,
00615                                 -(u1.y*P1(2,3)    -P1(1,3))/wi1);
00616 
00617         solve(A,B,X_,cv::DECOMP_SVD);
00618         X.at<double>(0) = X_.at<double>(0);
00619                 X.at<double>(1) = X_.at<double>(1);
00620                 X.at<double>(2) = X_.at<double>(2);
00621                 X.at<double>(3) = 1.0;
00622     }
00623     return X; //  return 4x1 double
00624 }
00625 
00629 //Triagulate points
00630 double EpipolarGeometry::triangulatePoints(
00631                 const cv::Mat& pt_set, //2xN double
00632                 const cv::Mat& pt_set1, //2xN double
00633                 const cv::Mat& P, // 3x4 double
00634                 const cv::Mat& P1, // 3x4 double
00635                 pcl::PointCloud<pcl::PointXYZ>::Ptr & pointcloud,
00636                 std::vector<double> & reproj_errors)
00637 {
00638         pointcloud.reset(new pcl::PointCloud<pcl::PointXYZ>);
00639 
00640         unsigned int pts_size = pt_set.cols;
00641 
00642         pointcloud->resize(pts_size);
00643         reproj_errors.resize(pts_size);
00644 
00645         for(unsigned int i=0; i<pts_size; i++)
00646         {
00647                 cv::Point3d u(pt_set.at<double>(0,i),pt_set.at<double>(1,i),1.0);
00648                 cv::Point3d u1(pt_set1.at<double>(0,i),pt_set1.at<double>(1,i),1.0);
00649 
00650                 cv::Mat X = iterativeLinearLSTriangulation(u,P,u1,P1);
00651 
00652                 cv::Mat x_proj = P * X;                         //reproject
00653                 x_proj = x_proj / x_proj.at<double>(2);
00654                 cv::Point3d xPt_img_(x_proj.at<double>(0), x_proj.at<double>(1), 1.0);
00655 
00656                 double reprj_err = norm(xPt_img_ - u);
00657                 reproj_errors[i] = reprj_err;
00658                 pointcloud->at(i) = pcl::PointXYZ(X.at<double>(0),X.at<double>(1),X.at<double>(2));
00659         }
00660 
00661         return cv::mean(reproj_errors)[0]; // mean reproj error
00662 }
00663 
00664 } // namespace rtabmap


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:19