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

#include <ORBextractor.h>

Public Types

enum  { HARRIS_SCORE =0, FAST_SCORE =1 }
 

Public Member Functions

std::vector< float > GetInverseScaleFactors ()
 
std::vector< float > GetInverseScaleSigmaSquares ()
 
int GetLevels ()
 
float GetScaleFactor ()
 
std::vector< float > GetScaleFactors ()
 
std::vector< float > GetScaleSigmaSquares ()
 
void operator() (cv::InputArray image, cv::InputArray mask, std::vector< cv::KeyPoint > &keypoints, cv::OutputArray descriptors)
 
 ORBextractor (int nfeatures, float scaleFactor, int nlevels, int iniThFAST, int minThFAST)
 
 ~ORBextractor ()
 

Public Attributes

std::vector< cv::Mat > mvImagePyramid
 

Protected Member Functions

void ComputeKeyPointsOctTree (std::vector< std::vector< cv::KeyPoint > > &allKeypoints)
 
void ComputeKeyPointsOld (std::vector< std::vector< cv::KeyPoint > > &allKeypoints)
 
void ComputePyramid (cv::Mat image)
 
std::vector< cv::KeyPoint > DistributeOctTree (const std::vector< cv::KeyPoint > &vToDistributeKeys, const int &minX, const int &maxX, const int &minY, const int &maxY, const int &nFeatures, const int &level)
 

Protected Attributes

int iniThFAST
 
int minThFAST
 
std::vector< int > mnFeaturesPerLevel
 
std::vector< float > mvInvLevelSigma2
 
std::vector< float > mvInvScaleFactor
 
std::vector< float > mvLevelSigma2
 
std::vector< float > mvScaleFactor
 
int nfeatures
 
int nlevels
 
std::vector< cv::Pointpattern
 
double scaleFactor
 
std::vector< int > umax
 

Detailed Description

Definition at line 45 of file ORBextractor.h.

Member Enumeration Documentation

anonymous enum
Enumerator
HARRIS_SCORE 
FAST_SCORE 

Definition at line 49 of file ORBextractor.h.

Constructor & Destructor Documentation

ORB_SLAM2::ORBextractor::ORBextractor ( int  nfeatures,
float  scaleFactor,
int  nlevels,
int  iniThFAST,
int  minThFAST 
)

Definition at line 410 of file ORBextractor.cc.

ORB_SLAM2::ORBextractor::~ORBextractor ( )
inline

Definition at line 54 of file ORBextractor.h.

Member Function Documentation

void ORB_SLAM2::ORBextractor::ComputeKeyPointsOctTree ( std::vector< std::vector< cv::KeyPoint > > &  allKeypoints)
protected

Definition at line 765 of file ORBextractor.cc.

void ORB_SLAM2::ORBextractor::ComputeKeyPointsOld ( std::vector< std::vector< cv::KeyPoint > > &  allKeypoints)
protected

Definition at line 855 of file ORBextractor.cc.

void ORB_SLAM2::ORBextractor::ComputePyramid ( cv::Mat  image)
protected

Definition at line 1107 of file ORBextractor.cc.

vector< cv::KeyPoint > ORB_SLAM2::ORBextractor::DistributeOctTree ( const std::vector< cv::KeyPoint > &  vToDistributeKeys,
const int &  minX,
const int &  maxX,
const int &  minY,
const int &  maxY,
const int &  nFeatures,
const int &  level 
)
protected

Definition at line 539 of file ORBextractor.cc.

std::vector<float> ORB_SLAM2::ORBextractor::GetInverseScaleFactors ( )
inline

Definition at line 73 of file ORBextractor.h.

std::vector<float> ORB_SLAM2::ORBextractor::GetInverseScaleSigmaSquares ( )
inline

Definition at line 81 of file ORBextractor.h.

int ORB_SLAM2::ORBextractor::GetLevels ( )
inline

Definition at line 63 of file ORBextractor.h.

float ORB_SLAM2::ORBextractor::GetScaleFactor ( )
inline

Definition at line 66 of file ORBextractor.h.

std::vector<float> ORB_SLAM2::ORBextractor::GetScaleFactors ( )
inline

Definition at line 69 of file ORBextractor.h.

std::vector<float> ORB_SLAM2::ORBextractor::GetScaleSigmaSquares ( )
inline

Definition at line 77 of file ORBextractor.h.

void ORB_SLAM2::ORBextractor::operator() ( cv::InputArray  image,
cv::InputArray  mask,
std::vector< cv::KeyPoint > &  keypoints,
cv::OutputArray  descriptors 
)

Definition at line 1043 of file ORBextractor.cc.

Member Data Documentation

int ORB_SLAM2::ORBextractor::iniThFAST
protected

Definition at line 100 of file ORBextractor.h.

int ORB_SLAM2::ORBextractor::minThFAST
protected

Definition at line 101 of file ORBextractor.h.

std::vector<int> ORB_SLAM2::ORBextractor::mnFeaturesPerLevel
protected

Definition at line 103 of file ORBextractor.h.

std::vector<cv::Mat> ORB_SLAM2::ORBextractor::mvImagePyramid

Definition at line 85 of file ORBextractor.h.

std::vector<float> ORB_SLAM2::ORBextractor::mvInvLevelSigma2
protected

Definition at line 110 of file ORBextractor.h.

std::vector<float> ORB_SLAM2::ORBextractor::mvInvScaleFactor
protected

Definition at line 108 of file ORBextractor.h.

std::vector<float> ORB_SLAM2::ORBextractor::mvLevelSigma2
protected

Definition at line 109 of file ORBextractor.h.

std::vector<float> ORB_SLAM2::ORBextractor::mvScaleFactor
protected

Definition at line 107 of file ORBextractor.h.

int ORB_SLAM2::ORBextractor::nfeatures
protected

Definition at line 97 of file ORBextractor.h.

int ORB_SLAM2::ORBextractor::nlevels
protected

Definition at line 99 of file ORBextractor.h.

std::vector<cv::Point> ORB_SLAM2::ORBextractor::pattern
protected

Definition at line 95 of file ORBextractor.h.

double ORB_SLAM2::ORBextractor::scaleFactor
protected

Definition at line 98 of file ORBextractor.h.

std::vector<int> ORB_SLAM2::ORBextractor::umax
protected

Definition at line 105 of file ORBextractor.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