26 #include <opencv2/core/core.hpp>    38     mnIterations(0), mnBestInliers(0), mbFixScale(bFixScale)
    45     mN1 = vpMatched12.size();
    62     for(
int i1=0; i1<
mN1; i1++)
    78             if(indexKF1<0 || indexKF2<0)
    81             const cv::KeyPoint &kp1 = pKF1->
mvKeysUn[indexKF1];
    82             const cv::KeyPoint &kp2 = pKF2->
mvKeysUn[indexKF2];
    95             mvX3Dc1.push_back(Rcw1*X3D1w+tcw1);
    98             mvX3Dc2.push_back(Rcw2*X3D2w+tcw2);
   133         nIterations = ceil(log(1-
mRansacProb)/log(1-pow(epsilon,3)));
   143     vbInliers = vector<bool>(
mN1,
false);
   152     vector<size_t> vAvailableIndices;
   154     cv::Mat P3Dc1i(3,3,CV_32F);
   155     cv::Mat P3Dc2i(3,3,CV_32F);
   157     int nCurrentIterations = 0;
   160         nCurrentIterations++;
   166         for(
short i = 0; i < 3; ++i)
   170             int idx = vAvailableIndices[randi];
   172             mvX3Dc1[idx].copyTo(P3Dc1i.col(i));
   173             mvX3Dc2[idx].copyTo(P3Dc2i.col(i));
   175             vAvailableIndices[randi] = vAvailableIndices.back();
   176             vAvailableIndices.pop_back();
   195                 for(
int i=0; i<
N; i++)
   217     cv::reduce(P,C,1,CV_REDUCE_SUM);
   220     for(
int i=0; i<P.cols; i++)
   222         Pr.col(i)=P.col(i)-C;
   233     cv::Mat Pr1(P1.size(),P1.type()); 
   234     cv::Mat Pr2(P2.size(),P2.type()); 
   235     cv::Mat O1(3,1,Pr1.type()); 
   236     cv::Mat O2(3,1,Pr2.type()); 
   243     cv::Mat M = Pr2*Pr1.t();
   247     double N11, N12, N13, N14, N22, N23, N24, N33, N34, N44;
   249     cv::Mat 
N(4,4,P1.type());
   251     N11 = M.at<
float>(0,0)+M.at<
float>(1,1)+M.at<
float>(2,2);
   252     N12 = M.at<
float>(1,2)-M.at<
float>(2,1);
   253     N13 = M.at<
float>(2,0)-M.at<
float>(0,2);
   254     N14 = M.at<
float>(0,1)-M.at<
float>(1,0);
   255     N22 = M.at<
float>(0,0)-M.at<
float>(1,1)-M.at<
float>(2,2);
   256     N23 = M.at<
float>(0,1)+M.at<
float>(1,0);
   257     N24 = M.at<
float>(2,0)+M.at<
float>(0,2);
   258     N33 = -M.at<
float>(0,0)+M.at<
float>(1,1)-M.at<
float>(2,2);
   259     N34 = M.at<
float>(1,2)+M.at<
float>(2,1);
   260     N44 = -M.at<
float>(0,0)-M.at<
float>(1,1)+M.at<
float>(2,2);
   262     N = (cv::Mat_<float>(4,4) << N11, N12, N13, N14,
   272     cv::eigen(N,eval,evec); 
   274     cv::Mat vec(1,3,evec.type());
   275     (evec.row(0).colRange(1,4)).copyTo(vec); 
   278     double ang=atan2(norm(vec),evec.at<
float>(0,0));
   280     vec = 2*ang*vec/norm(vec); 
   282     mR12i.create(3,3,P1.type());
   284     cv::Rodrigues(vec,
mR12i); 
   288     cv::Mat P3 = 
mR12i*Pr2;
   294         double nom = Pr1.dot(P3);
   295         cv::Mat aux_P3(P3.size(),P3.type());
   297         cv::pow(P3,2,aux_P3);
   300         for(
int i=0; i<aux_P3.rows; i++)
   302             for(
int j=0; j<aux_P3.cols; j++)
   304                 den+=aux_P3.at<
float>(i,j);
   315     mt12i.create(1,3,P1.type());
   321     mT12i = cv::Mat::eye(4,4,P1.type());
   325     sR.copyTo(
mT12i.rowRange(0,3).colRange(0,3));
   330     mT21i = cv::Mat::eye(4,4,P1.type());
   332     cv::Mat sRinv = (1.0/
ms12i)*mR12i.t();
   334     sRinv.copyTo(
mT21i.rowRange(0,3).colRange(0,3));
   335     cv::Mat tinv = -sRinv*
mt12i;
   336     tinv.copyTo(
mT21i.rowRange(0,3).col(3));
   342     vector<cv::Mat> vP1im2, vP2im1;
   348     for(
size_t i=0; i<
mvP1im1.size(); i++)
   350         cv::Mat dist1 = 
mvP1im1[i]-vP2im1[i];
   351         cv::Mat dist2 = vP1im2[i]-
mvP2im2[i];
   353         const float err1 = dist1.dot(dist1);
   354         const float err2 = dist2.dot(dist2);
   384     cv::Mat Rcw = Tcw.rowRange(0,3).colRange(0,3);
   385     cv::Mat tcw = Tcw.rowRange(0,3).col(3);
   386     const float &fx = K.at<
float>(0,0);
   387     const float &fy = K.at<
float>(1,1);
   388     const float &cx = K.at<
float>(0,2);
   389     const float &cy = K.at<
float>(1,2);
   392     vP2D.reserve(vP3Dw.size());
   394     for(
size_t i=0, iend=vP3Dw.size(); i<iend; i++)
   396         cv::Mat P3Dc = Rcw*vP3Dw[i]+tcw;
   397         const float invz = 1/(P3Dc.at<
float>(2));
   398         const float x = P3Dc.at<
float>(0)*invz;
   399         const float y = P3Dc.at<
float>(1)*invz;
   401         vP2D.push_back((cv::Mat_<float>(2,1) << fx*x+cx, fy*y+cy));
   407     const float &fx = K.at<
float>(0,0);
   408     const float &fy = K.at<
float>(1,1);
   409     const float &cx = K.at<
float>(0,2);
   410     const float &cy = K.at<
float>(1,2);
   413     vP2D.reserve(vP3Dc.size());
   415     for(
size_t i=0, iend=vP3Dc.size(); i<iend; i++)
   417         const float invz = 1/(vP3Dc[i].at<
float>(2));
   418         const float x = vP3Dc[i].at<
float>(0)*invz;
   419         const float y = vP3Dc[i].at<
float>(1)*invz;
   421         vP2D.push_back((cv::Mat_<float>(2,1) << fx*x+cx, fy*y+cy));
 
std::vector< size_t > mvnMaxError2
std::vector< cv::Mat > mvP2im2
const std::vector< cv::KeyPoint > mvKeysUn
cv::Mat find(std::vector< bool > &vbInliers12, int &nInliers)
std::vector< cv::Mat > mvX3Dc1
cv::Mat iterate(int nIterations, bool &bNoMore, std::vector< bool > &vbInliers, int &nInliers)
void Project(const std::vector< cv::Mat > &vP3Dw, std::vector< cv::Mat > &vP2D, cv::Mat Tcw, cv::Mat K)
const std::vector< float > mvLevelSigma2
std::vector< size_t > mvnMaxError1
std::vector< MapPoint * > GetMapPointMatches()
void ComputeSim3(cv::Mat &P1, cv::Mat &P2)
TFSIMD_FORCE_INLINE const tfScalar & y() const 
std::vector< MapPoint * > mvpMatches12
std::vector< cv::Mat > mvP1im1
cv::Mat GetEstimatedRotation()
Sim3Solver(KeyFrame *pKF1, KeyFrame *pKF2, const std::vector< MapPoint * > &vpMatched12, const bool bFixScale=true)
std::vector< bool > mvbInliersi
float GetEstimatedScale()
void FromCameraToImage(const std::vector< cv::Mat > &vP3Dc, std::vector< cv::Mat > &vP2D, cv::Mat K)
TFSIMD_FORCE_INLINE const tfScalar & x() const 
std::vector< MapPoint * > mvpMapPoints2
static int RandomInt(int min, int max)
void ComputeCentroid(cv::Mat &P, cv::Mat &Pr, cv::Mat &C)
void SetRansacParameters(double probability=0.99, int minInliers=6, int maxIterations=300)
std::vector< MapPoint * > mvpMapPoints1
std::vector< cv::Mat > mvX3Dc2
std::vector< size_t > mvnIndices1
int GetIndexInKeyFrame(KeyFrame *pKF)
std::vector< size_t > mvAllIndices
std::vector< bool > mvbBestInliers
cv::Mat GetEstimatedTranslation()