00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
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
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
00099
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
00121
00122
00123 e1[0] = v.at<double>(0,2);
00124 e1[1] = v.at<double>(1,2);
00125 e1[2] = v.at<double>(2,2);
00126
00127 e2[0] = u.at<double>(0,2);
00128 e2[1] = u.at<double>(1,2);
00129 e2[2] = u.at<double>(2,2);
00130 }
00131
00132 int inFrontOfBothCameras(const cv::Mat & x, const cv::Mat & xp, const cv::Mat & R, const cv::Mat & T)
00133 {
00134
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
00155
00156
00157 cv::triangulatePoints(p0, p, x, xp, pts4D);
00158
00159
00160 int nValid = 0;
00161 for(int i=0; i<x.cols; ++i)
00162 {
00163
00164 if(pts4D.at<double>(2,i)/pts4D.at<double>(3,i) > 5)
00165
00166 {
00167 ++nValid;
00168 }
00169 }
00170 UDEBUG("nValid=%d/%d", nValid, x.cols);
00171
00172 return nValid;
00173 }
00174
00175
00176
00177
00178
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
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
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
00203
00204
00205
00206
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
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
00228
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
00242 max = inFrontOfBothCameras(x, xp, r1, t1);
00243
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
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
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
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,
00294 std::vector<uchar> & status,
00295 double ransacParam1,
00296 double ransacParam2)
00297 {
00298
00299 status = std::vector<uchar>(pairs.size(), 0);
00300
00301
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
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
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
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
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
00383
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 {
00418 int realPairsCount = 0;
00419 pairs.clear();
00420 for(std::map<int, cv::KeyPoint>::const_iterator i=wordsA.begin(); i!=wordsA.end(); ++i)
00421 {
00422 std::map<int, cv::KeyPoint>::const_iterator ptB = wordsB.find(i->first);
00423 if(ptB != wordsB.end())
00424 {
00425 pairs.push_back(std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> >(i->first, std::pair<cv::KeyPoint, cv::KeyPoint>(i->second, ptB->second)));
00426 ++realPairsCount;
00427 }
00428 }
00429 return realPairsCount;
00430 }
00431
00436 int EpipolarGeometry::findPairs(const std::multimap<int, cv::KeyPoint> & wordsA,
00437 const std::multimap<int, cv::KeyPoint> & wordsB,
00438 std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs)
00439 {
00440 const std::list<int> & ids = uUniqueKeys(wordsA);
00441 std::multimap<int, cv::KeyPoint>::const_iterator iterA;
00442 std::multimap<int, cv::KeyPoint>::const_iterator iterB;
00443 pairs.clear();
00444 int realPairsCount = 0;
00445 for(std::list<int>::const_iterator i=ids.begin(); i!=ids.end(); ++i)
00446 {
00447 iterA = wordsA.find(*i);
00448 iterB = wordsB.find(*i);
00449 while(iterA != wordsA.end() && iterB != wordsB.end() && (*iterA).first == (*iterB).first && (*iterA).first == *i)
00450 {
00451 pairs.push_back(std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> >(*i, std::pair<cv::KeyPoint, cv::KeyPoint>((*iterA).second, (*iterB).second)));
00452 ++iterA;
00453 ++iterB;
00454 ++realPairsCount;
00455 }
00456 }
00457 return realPairsCount;
00458 }
00459
00464 int EpipolarGeometry::findPairsUnique(
00465 const std::multimap<int, cv::KeyPoint> & wordsA,
00466 const std::multimap<int, cv::KeyPoint> & wordsB,
00467 std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs)
00468 {
00469 const std::list<int> & ids = uUniqueKeys(wordsA);
00470 int realPairsCount = 0;
00471 pairs.clear();
00472 for(std::list<int>::const_iterator i=ids.begin(); i!=ids.end(); ++i)
00473 {
00474 std::list<cv::KeyPoint> ptsA = uValues(wordsA, *i);
00475 std::list<cv::KeyPoint> ptsB = uValues(wordsB, *i);
00476 if(ptsA.size() == 1 && ptsB.size() == 1)
00477 {
00478 pairs.push_back(std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> >(*i, std::pair<cv::KeyPoint, cv::KeyPoint>(ptsA.front(), ptsB.front())));
00479 ++realPairsCount;
00480 }
00481 else if(ptsA.size()>1 && ptsB.size()>1)
00482 {
00483
00484 realPairsCount += ptsA.size() > ptsB.size() ? ptsB.size() : ptsA.size();
00485 }
00486 }
00487 return realPairsCount;
00488 }
00489
00494 int EpipolarGeometry::findPairsAll(const std::multimap<int, cv::KeyPoint> & wordsA,
00495 const std::multimap<int, cv::KeyPoint> & wordsB,
00496 std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs)
00497 {
00498 UTimer timer;
00499 timer.start();
00500 const std::list<int> & ids = uUniqueKeys(wordsA);
00501 pairs.clear();
00502 int realPairsCount = 0;;
00503 for(std::list<int>::const_iterator iter=ids.begin(); iter!=ids.end(); ++iter)
00504 {
00505 std::list<cv::KeyPoint> ptsA = uValues(wordsA, *iter);
00506 std::list<cv::KeyPoint> ptsB = uValues(wordsB, *iter);
00507
00508 realPairsCount += ptsA.size() > ptsB.size() ? ptsB.size() : ptsA.size();
00509
00510 for(std::list<cv::KeyPoint>::iterator jter=ptsA.begin(); jter!=ptsA.end(); ++jter)
00511 {
00512 for(std::list<cv::KeyPoint>::iterator kter=ptsB.begin(); kter!=ptsB.end(); ++kter)
00513 {
00514 pairs.push_back(std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> >(*iter, std::pair<cv::KeyPoint, cv::KeyPoint>(*jter, *kter)));
00515 }
00516 }
00517 }
00518 ULOGGER_DEBUG("time = %f", timer.ticks());
00519 return realPairsCount;
00520 }
00521
00522
00523
00529 cv::Mat EpipolarGeometry::linearLSTriangulation(
00530 cv::Point3d u,
00531 cv::Matx34d P,
00532 cv::Point3d u1,
00533 cv::Matx34d P1
00534 )
00535 {
00536
00537
00538
00539 cv::Mat A = (cv::Mat_<double>(4,3) <<
00540 u.x*P(2,0)-P(0,0), u.x*P(2,1)-P(0,1), u.x*P(2,2)-P(0,2),
00541 u.y*P(2,0)-P(1,0), u.y*P(2,1)-P(1,1), u.y*P(2,2)-P(1,2),
00542 u1.x*P1(2,0)-P1(0,0), u1.x*P1(2,1)-P1(0,1), u1.x*P1(2,2)-P1(0,2),
00543 u1.y*P1(2,0)-P1(1,0), u1.y*P1(2,1)-P1(1,1), u1.y*P1(2,2)-P1(1,2)
00544 );
00545 cv::Mat B = (cv::Mat_<double>(4,1) <<
00546 -(u.x*P(2,3) -P(0,3)),
00547 -(u.y*P(2,3) -P(1,3)),
00548 -(u1.x*P1(2,3) -P1(0,3)),
00549 -(u1.y*P1(2,3) -P1(1,3)));
00550
00551 cv::Mat X;
00552 solve(A,B,X,cv::DECOMP_SVD);
00553
00554 return X;
00555 }
00556
00562 cv::Mat EpipolarGeometry::iterativeLinearLSTriangulation(
00563 cv::Point3d u,
00564 const cv::Matx34d & P,
00565 cv::Point3d u1,
00566 const cv::Matx34d & P1)
00567 {
00568 double wi = 1, wi1 = 1;
00569 double EPSILON = 0.0001;
00570
00571 cv::Mat X(4,1,CV_64FC1);
00572 cv::Mat X_ = linearLSTriangulation(u,P,u1,P1);
00573 X.at<double>(0) = X_.at<double>(0);
00574 X.at<double>(1) = X_.at<double>(1);
00575 X.at<double>(2) = X_.at<double>(2);
00576 X.at<double>(3) = 1.0;
00577 for (int i=0; i<10; i++)
00578 {
00579
00580 double p2x = cv::Mat(cv::Mat(P).row(2)*X).at<double>(0);
00581 double p2x1 = cv::Mat(cv::Mat(P1).row(2)*X).at<double>(0);
00582
00583
00584 if(fabs(wi - p2x) <= EPSILON && fabs(wi1 - p2x1) <= EPSILON) break;
00585
00586 wi = p2x;
00587 wi1 = p2x1;
00588
00589
00590 cv::Mat A = (cv::Mat_<double>(4,3) <<
00591 (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,
00592 (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,
00593 (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,
00594 (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);
00595 cv::Mat B = (cv::Mat_<double>(4,1) <<
00596 -(u.x*P(2,3) -P(0,3))/wi,
00597 -(u.y*P(2,3) -P(1,3))/wi,
00598 -(u1.x*P1(2,3) -P1(0,3))/wi1,
00599 -(u1.y*P1(2,3) -P1(1,3))/wi1);
00600
00601 solve(A,B,X_,cv::DECOMP_SVD);
00602 X.at<double>(0) = X_.at<double>(0);
00603 X.at<double>(1) = X_.at<double>(1);
00604 X.at<double>(2) = X_.at<double>(2);
00605 X.at<double>(3) = 1.0;
00606 }
00607 return X;
00608 }
00609
00613
00614 double EpipolarGeometry::triangulatePoints(
00615 const cv::Mat& pt_set,
00616 const cv::Mat& pt_set1,
00617 const cv::Mat& P,
00618 const cv::Mat& P1,
00619 pcl::PointCloud<pcl::PointXYZ>::Ptr & pointcloud,
00620 std::vector<double> & reproj_errors)
00621 {
00622 pointcloud.reset(new pcl::PointCloud<pcl::PointXYZ>);
00623
00624 unsigned int pts_size = pt_set.cols;
00625
00626 pointcloud->resize(pts_size);
00627 reproj_errors.resize(pts_size);
00628
00629 for(unsigned int i=0; i<pts_size; i++)
00630 {
00631 cv::Point3d u(pt_set.at<double>(0,i),pt_set.at<double>(1,i),1.0);
00632 cv::Point3d u1(pt_set1.at<double>(0,i),pt_set1.at<double>(1,i),1.0);
00633
00634 cv::Mat X = iterativeLinearLSTriangulation(u,P,u1,P1);
00635
00636 cv::Mat x_proj = P * X;
00637 x_proj = x_proj / x_proj.at<double>(2);
00638 cv::Point3d xPt_img_(x_proj.at<double>(0), x_proj.at<double>(1), 1.0);
00639
00640 double reprj_err = norm(xPt_img_ - u);
00641 reproj_errors[i] = reprj_err;
00642 pointcloud->at(i) = pcl::PointXYZ(X.at<double>(0),X.at<double>(1),X.at<double>(2));
00643 }
00644
00645 return cv::mean(reproj_errors)[0];
00646 }
00647
00648 }