35     mK = ReferenceFrame.
mK.clone();
    45                              vector<cv::Point3f> &vP3D, vector<bool> &vbTriangulated)
    54     for(
size_t i=0, iend=vMatches12.size();i<iend; i++)
    68     vector<size_t> vAllIndices;
    69     vAllIndices.reserve(N);
    70     vector<size_t> vAvailableIndices;
    72     for(
int i=0; i<N; i++)
    74         vAllIndices.push_back(i);
    84         vAvailableIndices = vAllIndices;
    87         for(
size_t j=0; j<8; j++)
    90             int idx = vAvailableIndices[randi];
    94             vAvailableIndices[randi] = vAvailableIndices.back();
    95             vAvailableIndices.pop_back();
   100     vector<bool> vbMatchesInliersH, vbMatchesInliersF;
   112     float RH = SH/(SH+SF);
   116         return ReconstructH(vbMatchesInliersH,H,
mK,R21,t21,vP3D,vbTriangulated,1.0,50);
   118         return ReconstructF(vbMatchesInliersF,F,
mK,R21,t21,vP3D,vbTriangulated,1.0,50);
   130     vector<cv::Point2f> vPn1, vPn2;
   134     cv::Mat T2inv = T2.inv();
   138     vbMatchesInliers = vector<bool>(N,
false);
   141     vector<cv::Point2f> vPn1i(8);
   142     vector<cv::Point2f> vPn2i(8);
   144     vector<bool> vbCurrentInliers(N,
false);
   151         for(
size_t j=0; j<8; j++)
   156             vPn2i[j] = vPn2[mvMatches12[idx].second];
   165         if(currentScore>score)
   168             vbMatchesInliers = vbCurrentInliers;
   169             score = currentScore;
   178     const int N = vbMatchesInliers.size();
   181     vector<cv::Point2f> vPn1, vPn2;
   185     cv::Mat T2t = T2.t();
   189     vbMatchesInliers = vector<bool>(N,
false);
   192     vector<cv::Point2f> vPn1i(8);
   193     vector<cv::Point2f> vPn2i(8);
   195     vector<bool> vbCurrentInliers(N,
false);
   202         for(
int j=0; j<8; j++)
   207             vPn2i[j] = vPn2[mvMatches12[idx].second];
   216         if(currentScore>score)
   219             vbMatchesInliers = vbCurrentInliers;
   220             score = currentScore;
   228     const int N = vP1.size();
   230     cv::Mat A(2*N,9,CV_32F);
   232     for(
int i=0; i<N; i++)
   234         const float u1 = vP1[i].x;
   235         const float v1 = vP1[i].y;
   236         const float u2 = vP2[i].x;
   237         const float v2 = vP2[i].y;
   239         A.at<
float>(2*i,0) = 0.0;
   240         A.at<
float>(2*i,1) = 0.0;
   241         A.at<
float>(2*i,2) = 0.0;
   242         A.at<
float>(2*i,3) = -u1;
   243         A.at<
float>(2*i,4) = -v1;
   244         A.at<
float>(2*i,5) = -1;
   245         A.at<
float>(2*i,6) = v2*u1;
   246         A.at<
float>(2*i,7) = v2*v1;
   247         A.at<
float>(2*i,8) = v2;
   249         A.at<
float>(2*i+1,0) = u1;
   250         A.at<
float>(2*i+1,1) = v1;
   251         A.at<
float>(2*i+1,2) = 1;
   252         A.at<
float>(2*i+1,3) = 0.0;
   253         A.at<
float>(2*i+1,4) = 0.0;
   254         A.at<
float>(2*i+1,5) = 0.0;
   255         A.at<
float>(2*i+1,6) = -u2*u1;
   256         A.at<
float>(2*i+1,7) = -u2*v1;
   257         A.at<
float>(2*i+1,8) = -u2;
   263     cv::SVDecomp(A,w,u,vt,cv::SVD::MODIFY_A | cv::SVD::FULL_UV);
   265     return vt.row(8).reshape(0, 3);
   270     const int N = vP1.size();
   272     cv::Mat A(N,9,CV_32F);
   274     for(
int i=0; i<N; i++)
   276         const float u1 = vP1[i].x;
   277         const float v1 = vP1[i].y;
   278         const float u2 = vP2[i].x;
   279         const float v2 = vP2[i].y;
   281         A.at<
float>(i,0) = u2*u1;
   282         A.at<
float>(i,1) = u2*v1;
   283         A.at<
float>(i,2) = u2;
   284         A.at<
float>(i,3) = v2*u1;
   285         A.at<
float>(i,4) = v2*v1;
   286         A.at<
float>(i,5) = v2;
   287         A.at<
float>(i,6) = u1;
   288         A.at<
float>(i,7) = v1;
   289         A.at<
float>(i,8) = 1;
   294     cv::SVDecomp(A,w,u,vt,cv::SVD::MODIFY_A | cv::SVD::FULL_UV);
   296     cv::Mat Fpre = vt.row(8).reshape(0, 3);
   298     cv::SVDecomp(Fpre,w,u,vt,cv::SVD::MODIFY_A | cv::SVD::FULL_UV);
   302     return  u*cv::Mat::diag(w)*vt;
   309     const float h11 = H21.at<
float>(0,0);
   310     const float h12 = H21.at<
float>(0,1);
   311     const float h13 = H21.at<
float>(0,2);
   312     const float h21 = H21.at<
float>(1,0);
   313     const float h22 = H21.at<
float>(1,1);
   314     const float h23 = H21.at<
float>(1,2);
   315     const float h31 = H21.at<
float>(2,0);
   316     const float h32 = H21.at<
float>(2,1);
   317     const float h33 = H21.at<
float>(2,2);
   319     const float h11inv = H12.at<
float>(0,0);
   320     const float h12inv = H12.at<
float>(0,1);
   321     const float h13inv = H12.at<
float>(0,2);
   322     const float h21inv = H12.at<
float>(1,0);
   323     const float h22inv = H12.at<
float>(1,1);
   324     const float h23inv = H12.at<
float>(1,2);
   325     const float h31inv = H12.at<
float>(2,0);
   326     const float h32inv = H12.at<
float>(2,1);
   327     const float h33inv = H12.at<
float>(2,2);
   329     vbMatchesInliers.resize(N);
   333     const float th = 5.991;
   335     const float invSigmaSquare = 1.0/(sigma*sigma);
   337     for(
int i=0; i<N; i++)
   342         const cv::KeyPoint &kp2 = 
mvKeys2[mvMatches12[i].second];
   344         const float u1 = kp1.pt.x;
   345         const float v1 = kp1.pt.y;
   346         const float u2 = kp2.pt.x;
   347         const float v2 = kp2.pt.y;
   352         const float w2in1inv = 1.0/(h31inv*u2+h32inv*v2+h33inv);
   353         const float u2in1 = (h11inv*u2+h12inv*v2+h13inv)*w2in1inv;
   354         const float v2in1 = (h21inv*u2+h22inv*v2+h23inv)*w2in1inv;
   356         const float squareDist1 = (u1-u2in1)*(u1-u2in1)+(v1-v2in1)*(v1-v2in1);
   358         const float chiSquare1 = squareDist1*invSigmaSquare;
   363             score += th - chiSquare1;
   368         const float w1in2inv = 1.0/(h31*u1+h32*v1+h33);
   369         const float u1in2 = (h11*u1+h12*v1+h13)*w1in2inv;
   370         const float v1in2 = (h21*u1+h22*v1+h23)*w1in2inv;
   372         const float squareDist2 = (u2-u1in2)*(u2-u1in2)+(v2-v1in2)*(v2-v1in2);
   374         const float chiSquare2 = squareDist2*invSigmaSquare;
   379             score += th - chiSquare2;
   382             vbMatchesInliers[i]=
true;
   384             vbMatchesInliers[i]=
false;
   394     const float f11 = F21.at<
float>(0,0);
   395     const float f12 = F21.at<
float>(0,1);
   396     const float f13 = F21.at<
float>(0,2);
   397     const float f21 = F21.at<
float>(1,0);
   398     const float f22 = F21.at<
float>(1,1);
   399     const float f23 = F21.at<
float>(1,2);
   400     const float f31 = F21.at<
float>(2,0);
   401     const float f32 = F21.at<
float>(2,1);
   402     const float f33 = F21.at<
float>(2,2);
   404     vbMatchesInliers.resize(N);
   408     const float th = 3.841;
   409     const float thScore = 5.991;
   411     const float invSigmaSquare = 1.0/(sigma*sigma);
   413     for(
int i=0; i<N; i++)
   418         const cv::KeyPoint &kp2 = 
mvKeys2[mvMatches12[i].second];
   420         const float u1 = kp1.pt.x;
   421         const float v1 = kp1.pt.y;
   422         const float u2 = kp2.pt.x;
   423         const float v2 = kp2.pt.y;
   428         const float a2 = f11*u1+f12*v1+f13;
   429         const float b2 = f21*u1+f22*v1+f23;
   430         const float c2 = f31*u1+f32*v1+f33;
   432         const float num2 = a2*u2+b2*v2+c2;
   434         const float squareDist1 = num2*num2/(a2*a2+b2*b2);
   436         const float chiSquare1 = squareDist1*invSigmaSquare;
   441             score += thScore - chiSquare1;
   446         const float a1 = f11*u2+f21*v2+f31;
   447         const float b1 = f12*u2+f22*v2+f32;
   448         const float c1 = f13*u2+f23*v2+f33;
   450         const float num1 = a1*u1+b1*v1+c1;
   452         const float squareDist2 = num1*num1/(a1*a1+b1*b1);
   454         const float chiSquare2 = squareDist2*invSigmaSquare;
   459             score += thScore - chiSquare2;
   462             vbMatchesInliers[i]=
true;
   464             vbMatchesInliers[i]=
false;
   471                             cv::Mat &R21, cv::Mat &t21, vector<cv::Point3f> &vP3D, vector<bool> &vbTriangulated, 
float minParallax, 
int minTriangulated)
   474     for(
size_t i=0, iend = vbMatchesInliers.size() ; i<iend; i++)
   475         if(vbMatchesInliers[i])
   479     cv::Mat E21 = K.t()*F21*K;
   490     vector<cv::Point3f> vP3D1, vP3D2, vP3D3, vP3D4;
   491     vector<bool> vbTriangulated1,vbTriangulated2,vbTriangulated3, vbTriangulated4;
   492     float parallax1,parallax2, parallax3, parallax4;
   494     int nGood1 = 
CheckRT(R1,t1,
mvKeys1,
mvKeys2,
mvMatches12,vbMatchesInliers,K, vP3D1, 4.0*
mSigma2, vbTriangulated1, parallax1);
   495     int nGood2 = 
CheckRT(R2,t1,
mvKeys1,
mvKeys2,
mvMatches12,vbMatchesInliers,K, vP3D2, 4.0*
mSigma2, vbTriangulated2, parallax2);
   496     int nGood3 = 
CheckRT(R1,t2,
mvKeys1,
mvKeys2,
mvMatches12,vbMatchesInliers,K, vP3D3, 4.0*
mSigma2, vbTriangulated3, parallax3);
   497     int nGood4 = 
CheckRT(R2,t2,
mvKeys1,
mvKeys2,
mvMatches12,vbMatchesInliers,K, vP3D4, 4.0*
mSigma2, vbTriangulated4, parallax4);
   499     int maxGood = max(nGood1,max(nGood2,max(nGood3,nGood4)));
   504     int nMinGood = max(static_cast<int>(0.9*N),minTriangulated);
   507     if(nGood1>0.7*maxGood)
   509     if(nGood2>0.7*maxGood)
   511     if(nGood3>0.7*maxGood)
   513     if(nGood4>0.7*maxGood)
   517     if(maxGood<nMinGood || nsimilar>1)
   525         if(parallax1>minParallax)
   528             vbTriangulated = vbTriangulated1;
   534     }
else if(maxGood==nGood2)
   536         if(parallax2>minParallax)
   539             vbTriangulated = vbTriangulated2;
   545     }
else if(maxGood==nGood3)
   547         if(parallax3>minParallax)
   550             vbTriangulated = vbTriangulated3;
   556     }
else if(maxGood==nGood4)
   558         if(parallax4>minParallax)
   561             vbTriangulated = vbTriangulated4;
   573                       cv::Mat &R21, cv::Mat &t21, vector<cv::Point3f> &vP3D, vector<bool> &vbTriangulated, 
float minParallax, 
int minTriangulated)
   576     for(
size_t i=0, iend = vbMatchesInliers.size() ; i<iend; i++)
   577         if(vbMatchesInliers[i])
   584     cv::Mat invK = K.inv();
   585     cv::Mat A = invK*H21*K;
   588     cv::SVD::compute(A,w,U,Vt,cv::SVD::FULL_UV);
   591     float s = cv::determinant(U)*cv::determinant(Vt);
   593     float d1 = w.at<
float>(0);
   594     float d2 = w.at<
float>(1);
   595     float d3 = w.at<
float>(2);
   597     if(d1/d2<1.00001 || d2/d3<1.00001)
   602     vector<cv::Mat> vR, vt, vn;
   608     float aux1 = sqrt((d1*d1-d2*d2)/(d1*d1-d3*d3));
   609     float aux3 = sqrt((d2*d2-d3*d3)/(d1*d1-d3*d3));
   610     float x1[] = {aux1,aux1,-aux1,-aux1};
   611     float x3[] = {aux3,-aux3,aux3,-aux3};
   614     float aux_stheta = sqrt((d1*d1-d2*d2)*(d2*d2-d3*d3))/((d1+d3)*d2);
   616     float ctheta = (d2*d2+d1*d3)/((d1+d3)*d2);
   617     float stheta[] = {aux_stheta, -aux_stheta, -aux_stheta, aux_stheta};
   619     for(
int i=0; i<4; i++)
   621         cv::Mat Rp=cv::Mat::eye(3,3,CV_32F);
   622         Rp.at<
float>(0,0)=ctheta;
   623         Rp.at<
float>(0,2)=-stheta[i];
   624         Rp.at<
float>(2,0)=stheta[i];
   625         Rp.at<
float>(2,2)=ctheta;
   627         cv::Mat R = s*U*Rp*Vt;
   630         cv::Mat tp(3,1,CV_32F);
   631         tp.at<
float>(0)=x1[i];
   633         tp.at<
float>(2)=-x3[i];
   637         vt.push_back(t/cv::norm(t));
   639         cv::Mat np(3,1,CV_32F);
   640         np.at<
float>(0)=x1[i];
   642         np.at<
float>(2)=x3[i];
   651     float aux_sphi = sqrt((d1*d1-d2*d2)*(d2*d2-d3*d3))/((d1-d3)*d2);
   653     float cphi = (d1*d3-d2*d2)/((d1-d3)*d2);
   654     float sphi[] = {aux_sphi, -aux_sphi, -aux_sphi, aux_sphi};
   656     for(
int i=0; i<4; i++)
   658         cv::Mat Rp=cv::Mat::eye(3,3,CV_32F);
   659         Rp.at<
float>(0,0)=cphi;
   660         Rp.at<
float>(0,2)=sphi[i];
   661         Rp.at<
float>(1,1)=-1;
   662         Rp.at<
float>(2,0)=sphi[i];
   663         Rp.at<
float>(2,2)=-cphi;
   665         cv::Mat R = s*U*Rp*Vt;
   668         cv::Mat tp(3,1,CV_32F);
   669         tp.at<
float>(0)=x1[i];
   671         tp.at<
float>(2)=x3[i];
   675         vt.push_back(t/cv::norm(t));
   677         cv::Mat np(3,1,CV_32F);
   678         np.at<
float>(0)=x1[i];
   680         np.at<
float>(2)=x3[i];
   690     int secondBestGood = 0;    
   691     int bestSolutionIdx = -1;
   692     float bestParallax = -1;
   693     vector<cv::Point3f> bestP3D;
   694     vector<bool> bestTriangulated;
   698     for(
size_t i=0; i<8; i++)
   701         vector<cv::Point3f> vP3Di;
   702         vector<bool> vbTriangulatedi;
   703         int nGood = 
CheckRT(vR[i],vt[i],
mvKeys1,
mvKeys2,
mvMatches12,vbMatchesInliers,K,vP3Di, 4.0*
mSigma2, vbTriangulatedi, parallaxi);
   707             secondBestGood = bestGood;
   710             bestParallax = parallaxi;
   712             bestTriangulated = vbTriangulatedi;
   714         else if(nGood>secondBestGood)
   716             secondBestGood = nGood;
   721     if(secondBestGood<0.75*bestGood && bestParallax>=minParallax && bestGood>minTriangulated && bestGood>0.9*N)
   723         vR[bestSolutionIdx].copyTo(R21);
   724         vt[bestSolutionIdx].copyTo(t21);
   726         vbTriangulated = bestTriangulated;
   734 void Initializer::Triangulate(
const cv::KeyPoint &kp1, 
const cv::KeyPoint &kp2, 
const cv::Mat &P1, 
const cv::Mat &P2, cv::Mat &x3D)
   736     cv::Mat A(4,4,CV_32F);
   738     A.row(0) = kp1.pt.x*P1.row(2)-P1.row(0);
   739     A.row(1) = kp1.pt.y*P1.row(2)-P1.row(1);
   740     A.row(2) = kp2.pt.x*P2.row(2)-P2.row(0);
   741     A.row(3) = kp2.pt.y*P2.row(2)-P2.row(1);
   744     cv::SVD::compute(A,w,u,vt,cv::SVD::MODIFY_A| cv::SVD::FULL_UV);
   746     x3D = x3D.rowRange(0,3)/x3D.at<
float>(3);
   753     const int N = vKeys.size();
   755     vNormalizedPoints.resize(N);
   757     for(
int i=0; i<N; i++)
   759         meanX += vKeys[i].pt.x;
   760         meanY += vKeys[i].pt.y;
   769     for(
int i=0; i<N; i++)
   771         vNormalizedPoints[i].x = vKeys[i].pt.x - meanX;
   772         vNormalizedPoints[i].y = vKeys[i].pt.y - meanY;
   774         meanDevX += fabs(vNormalizedPoints[i].
x);
   775         meanDevY += fabs(vNormalizedPoints[i].
y);
   778     meanDevX = meanDevX/N;
   779     meanDevY = meanDevY/N;
   781     float sX = 1.0/meanDevX;
   782     float sY = 1.0/meanDevY;
   784     for(
int i=0; i<N; i++)
   786         vNormalizedPoints[i].x = vNormalizedPoints[i].x * sX;
   787         vNormalizedPoints[i].y = vNormalizedPoints[i].y * sY;
   790     T = cv::Mat::eye(3,3,CV_32F);
   791     T.at<
float>(0,0) = sX;
   792     T.at<
float>(1,1) = sY;
   793     T.at<
float>(0,2) = -meanX*sX;
   794     T.at<
float>(1,2) = -meanY*sY;
   798 int Initializer::CheckRT(
const cv::Mat &R, 
const cv::Mat &t, 
const vector<cv::KeyPoint> &vKeys1, 
const vector<cv::KeyPoint> &vKeys2,
   799                        const vector<Match> &vMatches12, vector<bool> &vbMatchesInliers,
   800                        const cv::Mat &K, vector<cv::Point3f> &vP3D, 
float th2, vector<bool> &vbGood, 
float ¶llax)
   803     const float fx = K.at<
float>(0,0);
   804     const float fy = K.at<
float>(1,1);
   805     const float cx = K.at<
float>(0,2);
   806     const float cy = K.at<
float>(1,2);
   808     vbGood = vector<bool>(vKeys1.size(),
false);
   809     vP3D.resize(vKeys1.size());
   811     vector<float> vCosParallax;
   812     vCosParallax.reserve(vKeys1.size());
   815     cv::Mat P1(3,4,CV_32F,cv::Scalar(0));
   816     K.copyTo(P1.rowRange(0,3).colRange(0,3));
   818     cv::Mat O1 = cv::Mat::zeros(3,1,CV_32F);
   821     cv::Mat P2(3,4,CV_32F);
   822     R.copyTo(P2.rowRange(0,3).colRange(0,3));
   823     t.copyTo(P2.rowRange(0,3).col(3));
   826     cv::Mat O2 = -R.t()*t;
   830     for(
size_t i=0, iend=vMatches12.size();i<iend;i++)
   832         if(!vbMatchesInliers[i])
   835         const cv::KeyPoint &kp1 = vKeys1[vMatches12[i].first];
   836         const cv::KeyPoint &kp2 = vKeys2[vMatches12[i].second];
   841         if(!isfinite(p3dC1.at<
float>(0)) || !isfinite(p3dC1.at<
float>(1)) || !isfinite(p3dC1.at<
float>(2)))
   843             vbGood[vMatches12[i].first]=
false;
   848         cv::Mat normal1 = p3dC1 - O1;
   849         float dist1 = cv::norm(normal1);
   851         cv::Mat normal2 = p3dC1 - O2;
   852         float dist2 = cv::norm(normal2);
   854         float cosParallax = normal1.dot(normal2)/(dist1*dist2);
   857         if(p3dC1.at<
float>(2)<=0 && cosParallax<0.99998)
   861         cv::Mat p3dC2 = R*p3dC1+t;
   863         if(p3dC2.at<
float>(2)<=0 && cosParallax<0.99998)
   868         float invZ1 = 1.0/p3dC1.at<
float>(2);
   869         im1x = fx*p3dC1.at<
float>(0)*invZ1+cx;
   870         im1y = fy*p3dC1.at<
float>(1)*invZ1+cy;
   872         float squareError1 = (im1x-kp1.pt.x)*(im1x-kp1.pt.x)+(im1y-kp1.pt.y)*(im1y-kp1.pt.y);
   879         float invZ2 = 1.0/p3dC2.at<
float>(2);
   880         im2x = fx*p3dC2.at<
float>(0)*invZ2+cx;
   881         im2y = fy*p3dC2.at<
float>(1)*invZ2+cy;
   883         float squareError2 = (im2x-kp2.pt.x)*(im2x-kp2.pt.x)+(im2y-kp2.pt.y)*(im2y-kp2.pt.y);
   888         vCosParallax.push_back(cosParallax);
   889         vP3D[vMatches12[i].first] = cv::Point3f(p3dC1.at<
float>(0),p3dC1.at<
float>(1),p3dC1.at<
float>(2));
   892         if(cosParallax<0.99998)
   893             vbGood[vMatches12[i].first]=
true;
   898         sort(vCosParallax.begin(),vCosParallax.end());
   900         size_t idx = 
min(50,
int(vCosParallax.size()-1));
   901         parallax = acos(vCosParallax[idx])*180/CV_PI;
   912     cv::SVD::compute(E,w,u,vt);
   917     cv::Mat W(3,3,CV_32F,cv::Scalar(0));
   923     if(cv::determinant(R1)<0)
   927     if(cv::determinant(R2)<0)
 
static void SeedRandOnce()
void FindFundamental(vector< bool > &vbInliers, float &score, cv::Mat &F21)
void DecomposeE(const cv::Mat &E, cv::Mat &R1, cv::Mat &R2, cv::Mat &t)
TFSIMD_FORCE_INLINE const tfScalar & y() const 
vector< cv::KeyPoint > mvKeys1
cv::Mat ComputeF21(const vector< cv::Point2f > &vP1, const vector< cv::Point2f > &vP2)
std::vector< cv::KeyPoint > mvKeysUn
int CheckRT(const cv::Mat &R, const cv::Mat &t, const vector< cv::KeyPoint > &vKeys1, const vector< cv::KeyPoint > &vKeys2, const vector< Match > &vMatches12, vector< bool > &vbInliers, const cv::Mat &K, vector< cv::Point3f > &vP3D, float th2, vector< bool > &vbGood, float ¶llax)
float CheckFundamental(const cv::Mat &F21, vector< bool > &vbMatchesInliers, float sigma)
vector< vector< size_t > > mvSets
void Normalize(const vector< cv::KeyPoint > &vKeys, vector< cv::Point2f > &vNormalizedPoints, cv::Mat &T)
void Triangulate(const cv::KeyPoint &kp1, const cv::KeyPoint &kp2, const cv::Mat &P1, const cv::Mat &P2, cv::Mat &x3D)
float CheckHomography(const cv::Mat &H21, const cv::Mat &H12, vector< bool > &vbMatchesInliers, float sigma)
TFSIMD_FORCE_INLINE const tfScalar & x() const 
static int RandomInt(int min, int max)
TFSIMD_FORCE_INLINE const tfScalar & w() const 
Initializer(const Frame &ReferenceFrame, float sigma=1.0, int iterations=200)
vector< bool > mvbMatched1
bool ReconstructH(vector< bool > &vbMatchesInliers, cv::Mat &H21, cv::Mat &K, cv::Mat &R21, cv::Mat &t21, vector< cv::Point3f > &vP3D, vector< bool > &vbTriangulated, float minParallax, int minTriangulated)
cv::Mat ComputeH21(const vector< cv::Point2f > &vP1, const vector< cv::Point2f > &vP2)
bool Initialize(const Frame &CurrentFrame, const vector< int > &vMatches12, cv::Mat &R21, cv::Mat &t21, vector< cv::Point3f > &vP3D, vector< bool > &vbTriangulated)
vector< cv::KeyPoint > mvKeys2
vector< Match > mvMatches12
bool ReconstructF(vector< bool > &vbMatchesInliers, cv::Mat &F21, cv::Mat &K, cv::Mat &R21, cv::Mat &t21, vector< cv::Point3f > &vP3D, vector< bool > &vbTriangulated, float minParallax, int minTriangulated)
void FindHomography(vector< bool > &vbMatchesInliers, float &score, cv::Mat &H21)