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

#include <ORBmatcher.h>

Public Member Functions

int Fuse (KeyFrame *pKF, const vector< MapPoint * > &vpMapPoints, const float th=3.0)
 
int Fuse (KeyFrame *pKF, cv::Mat Scw, const std::vector< MapPoint * > &vpPoints, float th, vector< MapPoint * > &vpReplacePoint)
 
 ORBmatcher (float nnratio=0.6, bool checkOri=true)
 
int SearchByBoW (KeyFrame *pKF, Frame &F, std::vector< MapPoint * > &vpMapPointMatches)
 
int SearchByBoW (KeyFrame *pKF1, KeyFrame *pKF2, std::vector< MapPoint * > &vpMatches12)
 
int SearchByProjection (Frame &F, const std::vector< MapPoint * > &vpMapPoints, const float th=3)
 
int SearchByProjection (Frame &CurrentFrame, const Frame &LastFrame, const float th, const bool bMono)
 
int SearchByProjection (Frame &CurrentFrame, KeyFrame *pKF, const std::set< MapPoint * > &sAlreadyFound, const float th, const int ORBdist)
 
int SearchByProjection (KeyFrame *pKF, cv::Mat Scw, const std::vector< MapPoint * > &vpPoints, std::vector< MapPoint * > &vpMatched, int th)
 
int SearchBySim3 (KeyFrame *pKF1, KeyFrame *pKF2, std::vector< MapPoint * > &vpMatches12, const float &s12, const cv::Mat &R12, const cv::Mat &t12, const float th)
 
int SearchForInitialization (Frame &F1, Frame &F2, std::vector< cv::Point2f > &vbPrevMatched, std::vector< int > &vnMatches12, int windowSize=10)
 
int SearchForTriangulation (KeyFrame *pKF1, KeyFrame *pKF2, cv::Mat F12, std::vector< pair< size_t, size_t > > &vMatchedPairs, const bool bOnlyStereo)
 

Static Public Member Functions

static int DescriptorDistance (const cv::Mat &a, const cv::Mat &b)
 

Static Public Attributes

static const int HISTO_LENGTH = 30
 
static const int TH_HIGH = 100
 
static const int TH_LOW = 50
 

Protected Member Functions

bool CheckDistEpipolarLine (const cv::KeyPoint &kp1, const cv::KeyPoint &kp2, const cv::Mat &F12, const KeyFrame *pKF)
 
void ComputeThreeMaxima (std::vector< int > *histo, const int L, int &ind1, int &ind2, int &ind3)
 
float RadiusByViewingCos (const float &viewCos)
 

Protected Attributes

bool mbCheckOrientation
 
float mfNNratio
 

Detailed Description

Definition at line 37 of file ORBmatcher.h.

Constructor & Destructor Documentation

ORB_SLAM2::ORBmatcher::ORBmatcher ( float  nnratio = 0.6,
bool  checkOri = true 
)

Definition at line 41 of file ORBmatcher.cc.

Member Function Documentation

bool ORB_SLAM2::ORBmatcher::CheckDistEpipolarLine ( const cv::KeyPoint &  kp1,
const cv::KeyPoint &  kp2,
const cv::Mat &  F12,
const KeyFrame pKF 
)
protected

Definition at line 140 of file ORBmatcher.cc.

void ORB_SLAM2::ORBmatcher::ComputeThreeMaxima ( std::vector< int > *  histo,
const int  L,
int &  ind1,
int &  ind2,
int &  ind3 
)
protected

Definition at line 1601 of file ORBmatcher.cc.

int ORB_SLAM2::ORBmatcher::DescriptorDistance ( const cv::Mat &  a,
const cv::Mat &  b 
)
static

Definition at line 1647 of file ORBmatcher.cc.

int ORB_SLAM2::ORBmatcher::Fuse ( KeyFrame pKF,
const vector< MapPoint * > &  vpMapPoints,
const float  th = 3.0 
)

Definition at line 825 of file ORBmatcher.cc.

int ORB_SLAM2::ORBmatcher::Fuse ( KeyFrame pKF,
cv::Mat  Scw,
const std::vector< MapPoint * > &  vpPoints,
float  th,
vector< MapPoint * > &  vpReplacePoint 
)
float ORB_SLAM2::ORBmatcher::RadiusByViewingCos ( const float &  viewCos)
protected

Definition at line 131 of file ORBmatcher.cc.

int ORB_SLAM2::ORBmatcher::SearchByBoW ( KeyFrame pKF,
Frame F,
std::vector< MapPoint * > &  vpMapPointMatches 
)
int ORB_SLAM2::ORBmatcher::SearchByBoW ( KeyFrame pKF1,
KeyFrame pKF2,
std::vector< MapPoint * > &  vpMatches12 
)
int ORB_SLAM2::ORBmatcher::SearchByProjection ( Frame F,
const std::vector< MapPoint * > &  vpMapPoints,
const float  th = 3 
)
int ORB_SLAM2::ORBmatcher::SearchByProjection ( Frame CurrentFrame,
const Frame LastFrame,
const float  th,
const bool  bMono 
)

Definition at line 1328 of file ORBmatcher.cc.

int ORB_SLAM2::ORBmatcher::SearchByProjection ( Frame CurrentFrame,
KeyFrame pKF,
const std::set< MapPoint * > &  sAlreadyFound,
const float  th,
const int  ORBdist 
)
int ORB_SLAM2::ORBmatcher::SearchByProjection ( KeyFrame pKF,
cv::Mat  Scw,
const std::vector< MapPoint * > &  vpPoints,
std::vector< MapPoint * > &  vpMatched,
int  th 
)
int ORB_SLAM2::ORBmatcher::SearchBySim3 ( KeyFrame pKF1,
KeyFrame pKF2,
std::vector< MapPoint * > &  vpMatches12,
const float &  s12,
const cv::Mat &  R12,
const cv::Mat &  t12,
const float  th 
)

Definition at line 1102 of file ORBmatcher.cc.

int ORB_SLAM2::ORBmatcher::SearchForInitialization ( Frame F1,
Frame F2,
std::vector< cv::Point2f > &  vbPrevMatched,
std::vector< int > &  vnMatches12,
int  windowSize = 10 
)

Definition at line 405 of file ORBmatcher.cc.

int ORB_SLAM2::ORBmatcher::SearchForTriangulation ( KeyFrame pKF1,
KeyFrame pKF2,
cv::Mat  F12,
std::vector< pair< size_t, size_t > > &  vMatchedPairs,
const bool  bOnlyStereo 
)

Definition at line 657 of file ORBmatcher.cc.

Member Data Documentation

const int ORB_SLAM2::ORBmatcher::HISTO_LENGTH = 30
static

Definition at line 89 of file ORBmatcher.h.

bool ORB_SLAM2::ORBmatcher::mbCheckOrientation
protected

Definition at line 101 of file ORBmatcher.h.

float ORB_SLAM2::ORBmatcher::mfNNratio
protected

Definition at line 100 of file ORBmatcher.h.

const int ORB_SLAM2::ORBmatcher::TH_HIGH = 100
static

Definition at line 88 of file ORBmatcher.h.

const int ORB_SLAM2::ORBmatcher::TH_LOW = 50
static

Definition at line 87 of file ORBmatcher.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