/**
* This file is part of ORB-SLAM3
*
* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
*
* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public
* License as published by the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even
* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along with ORB-SLAM3.
* If not, see .
*/
#include "Sim3Solver.h"
#include
#include
#include
#include "KeyFrame.h"
#include "ORBmatcher.h"
#include "Thirdparty/DBoW2/DUtils/Random.h"
namespace ORB_SLAM3
{
Sim3Solver::Sim3Solver(KeyFrame *pKF1, KeyFrame *pKF2, const vector &vpMatched12, const bool bFixScale,
vector vpKeyFrameMatchedMP):
mnIterations(0), mnBestInliers(0), mbFixScale(bFixScale),
pCamera1(pKF1->mpCamera), pCamera2(pKF2->mpCamera)
{
bool bDifferentKFs = false;
if(vpKeyFrameMatchedMP.empty())
{
bDifferentKFs = true;
vpKeyFrameMatchedMP = vector(vpMatched12.size(), pKF2);
}
mpKF1 = pKF1;
mpKF2 = pKF2;
vector vpKeyFrameMP1 = pKF1->GetMapPointMatches();
mN1 = vpMatched12.size();
mvpMapPoints1.reserve(mN1);
mvpMapPoints2.reserve(mN1);
mvpMatches12 = vpMatched12;
mvnIndices1.reserve(mN1);
mvX3Dc1.reserve(mN1);
mvX3Dc2.reserve(mN1);
Eigen::Matrix3f Rcw1 = pKF1->GetRotation();
Eigen::Vector3f tcw1 = pKF1->GetTranslation();
Eigen::Matrix3f Rcw2 = pKF2->GetRotation();
Eigen::Vector3f tcw2 = pKF2->GetTranslation();
mvAllIndices.reserve(mN1);
size_t idx=0;
KeyFrame* pKFm = pKF2; //Default variable
for(int i1=0; i1isBad() || pMP2->isBad())
continue;
if(bDifferentKFs)
pKFm = vpKeyFrameMatchedMP[i1];
int indexKF1 = get<0>(pMP1->GetIndexInKeyFrame(pKF1));
int indexKF2 = get<0>(pMP2->GetIndexInKeyFrame(pKFm));
if(indexKF1<0 || indexKF2<0)
continue;
const cv::KeyPoint &kp1 = pKF1->mvKeysUn[indexKF1];
const cv::KeyPoint &kp2 = pKFm->mvKeysUn[indexKF2];
const float sigmaSquare1 = pKF1->mvLevelSigma2[kp1.octave];
const float sigmaSquare2 = pKFm->mvLevelSigma2[kp2.octave];
mvnMaxError1.push_back(9.210*sigmaSquare1);
mvnMaxError2.push_back(9.210*sigmaSquare2);
mvpMapPoints1.push_back(pMP1);
mvpMapPoints2.push_back(pMP2);
mvnIndices1.push_back(i1);
Eigen::Vector3f X3D1w = pMP1->GetWorldPos();
mvX3Dc1.push_back(Rcw1*X3D1w+tcw1);
Eigen::Vector3f X3D2w = pMP2->GetWorldPos();
mvX3Dc2.push_back(Rcw2*X3D2w+tcw2);
mvAllIndices.push_back(idx);
idx++;
}
}
FromCameraToImage(mvX3Dc1,mvP1im1,pCamera1);
FromCameraToImage(mvX3Dc2,mvP2im2,pCamera2);
SetRansacParameters();
}
void Sim3Solver::SetRansacParameters(double probability, int minInliers, int maxIterations)
{
mRansacProb = probability;
mRansacMinInliers = minInliers;
mRansacMaxIts = maxIterations;
N = mvpMapPoints1.size(); // number of correspondences
mvbInliersi.resize(N);
// Adjust Parameters according to number of correspondences
float epsilon = (float)mRansacMinInliers/N;
// Set RANSAC iterations according to probability, epsilon, and max iterations
int nIterations;
if(mRansacMinInliers==N)
nIterations=1;
else
nIterations = ceil(log(1-mRansacProb)/log(1-pow(epsilon,3)));
mRansacMaxIts = max(1,min(nIterations,mRansacMaxIts));
mnIterations = 0;
}
Eigen::Matrix4f Sim3Solver::iterate(int nIterations, bool &bNoMore, vector &vbInliers, int &nInliers)
{
bNoMore = false;
vbInliers = vector(mN1,false);
nInliers=0;
if(N vAvailableIndices;
Eigen::Matrix3f P3Dc1i;
Eigen::Matrix3f P3Dc2i;
int nCurrentIterations = 0;
while(mnIterations=mnBestInliers)
{
mvbBestInliers = mvbInliersi;
mnBestInliers = mnInliersi;
mBestT12 = mT12i;
mBestRotation = mR12i;
mBestTranslation = mt12i;
mBestScale = ms12i;
if(mnInliersi>mRansacMinInliers)
{
nInliers = mnInliersi;
for(int i=0; i=mRansacMaxIts)
bNoMore=true;
return Eigen::Matrix4f::Identity();
}
Eigen::Matrix4f Sim3Solver::iterate(int nIterations, bool &bNoMore, vector &vbInliers, int &nInliers, bool &bConverge)
{
bNoMore = false;
bConverge = false;
vbInliers = vector(mN1,false);
nInliers=0;
if(N vAvailableIndices;
Eigen::Matrix3f P3Dc1i;
Eigen::Matrix3f P3Dc2i;
int nCurrentIterations = 0;
Eigen::Matrix4f bestSim3;
while(mnIterations=mnBestInliers)
{
mvbBestInliers = mvbInliersi;
mnBestInliers = mnInliersi;
mBestT12 = mT12i;
mBestRotation = mR12i;
mBestTranslation = mt12i;
mBestScale = ms12i;
if(mnInliersi>mRansacMinInliers)
{
nInliers = mnInliersi;
for(int i=0; i=mRansacMaxIts)
bNoMore=true;
return bestSim3;
}
Eigen::Matrix4f Sim3Solver::find(vector &vbInliers12, int &nInliers)
{
bool bFlag;
return iterate(mRansacMaxIts,bFlag,vbInliers12,nInliers);
}
void Sim3Solver::ComputeCentroid(Eigen::Matrix3f &P, Eigen::Matrix3f &Pr, Eigen::Vector3f &C)
{
C = P.rowwise().sum();
C = C / P.cols();
for(int i=0; i eigSolver;
eigSolver.compute(N);
Eigen::Vector4f eval = eigSolver.eigenvalues().real();
Eigen::Matrix4f evec = eigSolver.eigenvectors().real(); //evec[0] is the quaternion of the desired rotation
int maxIndex; // should be zero
eval.maxCoeff(&maxIndex);
Eigen::Vector3f vec = evec.block<3,1>(1,maxIndex); //extract imaginary part of the quaternion (sin*axis)
// Rotation angle. sin is the norm of the imaginary part, cos is the real part
double ang=atan2(vec.norm(),evec(0,maxIndex));
vec = 2*ang*vec/vec.norm(); //Angle-axis representation. quaternion angle is the half
mR12i = Sophus::SO3f::exp(vec).matrix();
// Step 5: Rotate set 2
Eigen::Matrix3f P3 = mR12i*Pr2;
// Step 6: Scale
if(!mbFixScale)
{
double cvnom = Converter::toCvMat(Pr1).dot(Converter::toCvMat(P3));
double nom = (Pr1.array() * P3.array()).sum();
if (abs(nom-cvnom)>1e-3)
std::cout << "sim3 solver: " << abs(nom-cvnom) << std::endl << nom << std::endl;
Eigen::Array aux_P3;
aux_P3 = P3.array() * P3.array();
double den = aux_P3.sum();
ms12i = nom/den;
}
else
ms12i = 1.0f;
// Step 7: Translation
mt12i = O1 - ms12i * mR12i * O2;
// Step 8: Transformation
// Step 8.1 T12
mT12i.setIdentity();
Eigen::Matrix3f sR = ms12i*mR12i;
mT12i.block<3,3>(0,0) = sR;
mT12i.block<3,1>(0,3) = mt12i;
// Step 8.2 T21
mT21i.setIdentity();
Eigen::Matrix3f sRinv = (1.0/ms12i)*mR12i.transpose();
// sRinv.copyTo(mT21i.rowRange(0,3).colRange(0,3));
mT21i.block<3,3>(0,0) = sRinv;
Eigen::Vector3f tinv = -sRinv * mt12i;
mT21i.block<3,1>(0,3) = tinv;
}
void Sim3Solver::CheckInliers()
{
vector vP1im2, vP2im1;
Project(mvX3Dc2,vP2im1,mT12i,pCamera1);
Project(mvX3Dc1,vP1im2,mT21i,pCamera2);
mnInliersi=0;
for(size_t i=0; i &vP3Dw, vector &vP2D, Eigen::Matrix4f Tcw, GeometricCamera* pCamera)
{
Eigen::Matrix3f Rcw = Tcw.block<3,3>(0,0);
Eigen::Vector3f tcw = Tcw.block<3,1>(0,3);
vP2D.clear();
vP2D.reserve(vP3Dw.size());
for(size_t i=0, iend=vP3Dw.size(); iproject(P3Dc);
vP2D.push_back(pt2D);
}
}
void Sim3Solver::FromCameraToImage(const vector &vP3Dc, vector &vP2D, GeometricCamera* pCamera)
{
vP2D.clear();
vP2D.reserve(vP3Dc.size());
for(size_t i=0, iend=vP3Dc.size(); iproject(vP3Dc[i]);
vP2D.push_back(pt2D);
}
}
} //namespace ORB_SLAM