Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
ORB_SLAM2::Sim3Solver Class Reference

#include <Sim3Solver.h>

Public Member Functions

cv::Mat find (std::vector< bool > &vbInliers12, int &nInliers)
 
cv::Mat GetEstimatedRotation ()
 
float GetEstimatedScale ()
 
cv::Mat GetEstimatedTranslation ()
 
cv::Mat iterate (int nIterations, bool &bNoMore, std::vector< bool > &vbInliers, int &nInliers)
 
void SetRansacParameters (double probability=0.99, int minInliers=6, int maxIterations=300)
 
 Sim3Solver (KeyFrame *pKF1, KeyFrame *pKF2, const std::vector< MapPoint * > &vpMatched12, const bool bFixScale=true)
 

Protected Member Functions

void CheckInliers ()
 
void ComputeCentroid (cv::Mat &P, cv::Mat &Pr, cv::Mat &C)
 
void ComputeSim3 (cv::Mat &P1, cv::Mat &P2)
 
void FromCameraToImage (const std::vector< cv::Mat > &vP3Dc, std::vector< cv::Mat > &vP2D, cv::Mat K)
 
void Project (const std::vector< cv::Mat > &vP3Dw, std::vector< cv::Mat > &vP2D, cv::Mat Tcw, cv::Mat K)
 

Protected Attributes

cv::Mat mBestRotation
 
float mBestScale
 
cv::Mat mBestT12
 
cv::Mat mBestTranslation
 
bool mbFixScale
 
cv::Mat mK1
 
cv::Mat mK2
 
int mN1
 
int mnBestInliers
 
int mnInliersi
 
int mnIterations
 
KeyFramempKF1
 
KeyFramempKF2
 
cv::Mat mR12i
 
int mRansacMaxIts
 
int mRansacMinInliers
 
double mRansacProb
 
float ms12i
 
float mSigma2
 
cv::Mat mt12i
 
cv::Mat mT12i
 
cv::Mat mT21i
 
float mTh
 
std::vector< size_t > mvAllIndices
 
std::vector< bool > mvbBestInliers
 
std::vector< bool > mvbInliersi
 
std::vector< size_t > mvnIndices1
 
std::vector< size_t > mvnMaxError1
 
std::vector< size_t > mvnMaxError2
 
std::vector< cv::Mat > mvP1im1
 
std::vector< cv::Mat > mvP2im2
 
std::vector< MapPoint * > mvpMapPoints1
 
std::vector< MapPoint * > mvpMapPoints2
 
std::vector< MapPoint * > mvpMatches12
 
std::vector< size_t > mvSigmaSquare1
 
std::vector< size_t > mvSigmaSquare2
 
std::vector< cv::Mat > mvX3Dc1
 
std::vector< cv::Mat > mvX3Dc2
 
int N
 

Detailed Description

Definition at line 36 of file Sim3Solver.h.

Constructor & Destructor Documentation

ORB_SLAM2::Sim3Solver::Sim3Solver ( KeyFrame pKF1,
KeyFrame pKF2,
const std::vector< MapPoint * > &  vpMatched12,
const bool  bFixScale = true 
)

Definition at line 37 of file Sim3Solver.cc.

Member Function Documentation

void ORB_SLAM2::Sim3Solver::CheckInliers ( )
protected

Definition at line 340 of file Sim3Solver.cc.

void ORB_SLAM2::Sim3Solver::ComputeCentroid ( cv::Mat &  P,
cv::Mat &  Pr,
cv::Mat &  C 
)
protected

Definition at line 215 of file Sim3Solver.cc.

void ORB_SLAM2::Sim3Solver::ComputeSim3 ( cv::Mat &  P1,
cv::Mat &  P2 
)
protected

Definition at line 226 of file Sim3Solver.cc.

cv::Mat ORB_SLAM2::Sim3Solver::find ( std::vector< bool > &  vbInliers12,
int &  nInliers 
)

Definition at line 209 of file Sim3Solver.cc.

void ORB_SLAM2::Sim3Solver::FromCameraToImage ( const std::vector< cv::Mat > &  vP3Dc,
std::vector< cv::Mat > &  vP2D,
cv::Mat  K 
)
protected

Definition at line 405 of file Sim3Solver.cc.

cv::Mat ORB_SLAM2::Sim3Solver::GetEstimatedRotation ( )

Definition at line 367 of file Sim3Solver.cc.

float ORB_SLAM2::Sim3Solver::GetEstimatedScale ( )

Definition at line 377 of file Sim3Solver.cc.

cv::Mat ORB_SLAM2::Sim3Solver::GetEstimatedTranslation ( )

Definition at line 372 of file Sim3Solver.cc.

cv::Mat ORB_SLAM2::Sim3Solver::iterate ( int  nIterations,
bool &  bNoMore,
std::vector< bool > &  vbInliers,
int &  nInliers 
)

Definition at line 140 of file Sim3Solver.cc.

void ORB_SLAM2::Sim3Solver::Project ( const std::vector< cv::Mat > &  vP3Dw,
std::vector< cv::Mat > &  vP2D,
cv::Mat  Tcw,
cv::Mat  K 
)
protected

Definition at line 382 of file Sim3Solver.cc.

void ORB_SLAM2::Sim3Solver::SetRansacParameters ( double  probability = 0.99,
int  minInliers = 6,
int  maxIterations = 300 
)

Definition at line 114 of file Sim3Solver.cc.

Member Data Documentation

cv::Mat ORB_SLAM2::Sim3Solver::mBestRotation
protected

Definition at line 99 of file Sim3Solver.h.

float ORB_SLAM2::Sim3Solver::mBestScale
protected

Definition at line 101 of file Sim3Solver.h.

cv::Mat ORB_SLAM2::Sim3Solver::mBestT12
protected

Definition at line 98 of file Sim3Solver.h.

cv::Mat ORB_SLAM2::Sim3Solver::mBestTranslation
protected

Definition at line 100 of file Sim3Solver.h.

bool ORB_SLAM2::Sim3Solver::mbFixScale
protected

Definition at line 104 of file Sim3Solver.h.

cv::Mat ORB_SLAM2::Sim3Solver::mK1
protected

Definition at line 127 of file Sim3Solver.h.

cv::Mat ORB_SLAM2::Sim3Solver::mK2
protected

Definition at line 128 of file Sim3Solver.h.

int ORB_SLAM2::Sim3Solver::mN1
protected

Definition at line 83 of file Sim3Solver.h.

int ORB_SLAM2::Sim3Solver::mnBestInliers
protected

Definition at line 97 of file Sim3Solver.h.

int ORB_SLAM2::Sim3Solver::mnInliersi
protected

Definition at line 92 of file Sim3Solver.h.

int ORB_SLAM2::Sim3Solver::mnIterations
protected

Definition at line 95 of file Sim3Solver.h.

KeyFrame* ORB_SLAM2::Sim3Solver::mpKF1
protected

Definition at line 68 of file Sim3Solver.h.

KeyFrame* ORB_SLAM2::Sim3Solver::mpKF2
protected

Definition at line 69 of file Sim3Solver.h.

cv::Mat ORB_SLAM2::Sim3Solver::mR12i
protected

Definition at line 86 of file Sim3Solver.h.

int ORB_SLAM2::Sim3Solver::mRansacMaxIts
protected

Definition at line 120 of file Sim3Solver.h.

int ORB_SLAM2::Sim3Solver::mRansacMinInliers
protected

Definition at line 117 of file Sim3Solver.h.

double ORB_SLAM2::Sim3Solver::mRansacProb
protected

Definition at line 114 of file Sim3Solver.h.

float ORB_SLAM2::Sim3Solver::ms12i
protected

Definition at line 88 of file Sim3Solver.h.

float ORB_SLAM2::Sim3Solver::mSigma2
protected

Definition at line 124 of file Sim3Solver.h.

cv::Mat ORB_SLAM2::Sim3Solver::mt12i
protected

Definition at line 87 of file Sim3Solver.h.

cv::Mat ORB_SLAM2::Sim3Solver::mT12i
protected

Definition at line 89 of file Sim3Solver.h.

cv::Mat ORB_SLAM2::Sim3Solver::mT21i
protected

Definition at line 90 of file Sim3Solver.h.

float ORB_SLAM2::Sim3Solver::mTh
protected

Definition at line 123 of file Sim3Solver.h.

std::vector<size_t> ORB_SLAM2::Sim3Solver::mvAllIndices
protected

Definition at line 107 of file Sim3Solver.h.

std::vector<bool> ORB_SLAM2::Sim3Solver::mvbBestInliers
protected

Definition at line 96 of file Sim3Solver.h.

std::vector<bool> ORB_SLAM2::Sim3Solver::mvbInliersi
protected

Definition at line 91 of file Sim3Solver.h.

std::vector<size_t> ORB_SLAM2::Sim3Solver::mvnIndices1
protected

Definition at line 76 of file Sim3Solver.h.

std::vector<size_t> ORB_SLAM2::Sim3Solver::mvnMaxError1
protected

Definition at line 79 of file Sim3Solver.h.

std::vector<size_t> ORB_SLAM2::Sim3Solver::mvnMaxError2
protected

Definition at line 80 of file Sim3Solver.h.

std::vector<cv::Mat> ORB_SLAM2::Sim3Solver::mvP1im1
protected

Definition at line 110 of file Sim3Solver.h.

std::vector<cv::Mat> ORB_SLAM2::Sim3Solver::mvP2im2
protected

Definition at line 111 of file Sim3Solver.h.

std::vector<MapPoint*> ORB_SLAM2::Sim3Solver::mvpMapPoints1
protected

Definition at line 73 of file Sim3Solver.h.

std::vector<MapPoint*> ORB_SLAM2::Sim3Solver::mvpMapPoints2
protected

Definition at line 74 of file Sim3Solver.h.

std::vector<MapPoint*> ORB_SLAM2::Sim3Solver::mvpMatches12
protected

Definition at line 75 of file Sim3Solver.h.

std::vector<size_t> ORB_SLAM2::Sim3Solver::mvSigmaSquare1
protected

Definition at line 77 of file Sim3Solver.h.

std::vector<size_t> ORB_SLAM2::Sim3Solver::mvSigmaSquare2
protected

Definition at line 78 of file Sim3Solver.h.

std::vector<cv::Mat> ORB_SLAM2::Sim3Solver::mvX3Dc1
protected

Definition at line 71 of file Sim3Solver.h.

std::vector<cv::Mat> ORB_SLAM2::Sim3Solver::mvX3Dc2
protected

Definition at line 72 of file Sim3Solver.h.

int ORB_SLAM2::Sim3Solver::N
protected

Definition at line 82 of file Sim3Solver.h.


The documentation for this class was generated from the following files:


orb_slam2_ros
Author(s):
autogenerated on Wed Apr 21 2021 02:53:06