Public Member Functions | Public Attributes | Static Public Attributes | Private Member Functions | Private Attributes | List of all members
ORB_SLAM2::Frame Class Reference

#include <Frame.h>

Public Member Functions

void ComputeBoW ()
 
void ComputeStereoFromRGBD (const cv::Mat &imDepth)
 
void ComputeStereoMatches ()
 
void ExtractORB (int flag, const cv::Mat &im)
 
 Frame ()
 
 Frame (const Frame &frame)
 
 Frame (const cv::Mat &imLeft, const cv::Mat &imRight, const double &timeStamp, ORBextractor *extractorLeft, ORBextractor *extractorRight, ORBVocabulary *voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth)
 
 Frame (const cv::Mat &imGray, const cv::Mat &imDepth, const double &timeStamp, ORBextractor *extractor, ORBVocabulary *voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth)
 
 Frame (const cv::Mat &imGray, const double &timeStamp, ORBextractor *extractor, ORBVocabulary *voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth)
 
cv::Mat GetCameraCenter ()
 
vector< size_t > GetFeaturesInArea (const float &x, const float &y, const float &r, const int minLevel=-1, const int maxLevel=-1) const
 
cv::Mat GetRotationInverse ()
 
bool isInFrustum (MapPoint *pMP, float viewingCosLimit)
 
bool PosInGrid (const cv::KeyPoint &kp, int &posX, int &posY)
 
void SetPose (cv::Mat Tcw)
 
cv::Mat UnprojectStereo (const int &i)
 
void UpdatePoseMatrices ()
 

Public Attributes

bool is_keyframe
 
float mb
 
float mbf
 
DBoW2::BowVector mBowVec
 
cv::Mat mDescriptors
 
cv::Mat mDescriptorsRight
 
cv::Mat mDistCoef
 
DBoW2::FeatureVector mFeatVec
 
float mfLogScaleFactor
 
float mfScaleFactor
 
std::vector< std::size_t > mGrid [FRAME_GRID_COLS][FRAME_GRID_ROWS]
 
cv::Mat mK
 
long unsigned int mnId
 
int mnScaleLevels
 
ORBextractormpORBextractorLeft
 
ORBextractormpORBextractorRight
 
ORBVocabularympORBvocabulary
 
KeyFramempReferenceKF
 
cv::Mat mTcw
 
float mThDepth
 
double mTimeStamp
 
std::vector< bool > mvbOutlier
 
std::vector< float > mvDepth
 
vector< float > mvInvLevelSigma2
 
vector< float > mvInvScaleFactors
 
std::vector< cv::KeyPoint > mvKeys
 
std::vector< cv::KeyPoint > mvKeysRight
 
std::vector< cv::KeyPoint > mvKeysUn
 
vector< float > mvLevelSigma2
 
std::vector< MapPoint * > mvpMapPoints
 
vector< float > mvScaleFactors
 
std::vector< float > mvuRight
 
int N
 

Static Public Attributes

static float cx
 
static float cy
 
static float fx
 
static float fy
 
static float invfx
 
static float invfy
 
static bool mbInitialComputations
 
static float mfGridElementHeightInv
 
static float mfGridElementWidthInv
 
static float mnMaxX
 
static float mnMaxY
 
static float mnMinX
 
static float mnMinY
 
static long unsigned int nNextId
 

Private Member Functions

void AssignFeaturesToGrid ()
 
void ComputeImageBounds (const cv::Mat &imLeft)
 
void UndistortKeyPoints ()
 

Private Attributes

cv::Mat mOw
 
cv::Mat mRcw
 
cv::Mat mRwc
 
cv::Mat mtcw
 

Detailed Description

Definition at line 43 of file Frame.h.

Constructor & Destructor Documentation

ORB_SLAM2::Frame::Frame ( )
ORB_SLAM2::Frame::Frame ( const Frame frame)
ORB_SLAM2::Frame::Frame ( const cv::Mat &  imLeft,
const cv::Mat &  imRight,
const double &  timeStamp,
ORBextractor extractorLeft,
ORBextractor extractorRight,
ORBVocabulary voc,
cv::Mat &  K,
cv::Mat &  distCoef,
const float &  bf,
const float &  thDepth 
)
ORB_SLAM2::Frame::Frame ( const cv::Mat &  imGray,
const cv::Mat &  imDepth,
const double &  timeStamp,
ORBextractor extractor,
ORBVocabulary voc,
cv::Mat &  K,
cv::Mat &  distCoef,
const float &  bf,
const float &  thDepth 
)
ORB_SLAM2::Frame::Frame ( const cv::Mat &  imGray,
const double &  timeStamp,
ORBextractor extractor,
ORBVocabulary voc,
cv::Mat &  K,
cv::Mat &  distCoef,
const float &  bf,
const float &  thDepth 
)

Member Function Documentation

void ORB_SLAM2::Frame::AssignFeaturesToGrid ( )
private
void ORB_SLAM2::Frame::ComputeBoW ( )
void ORB_SLAM2::Frame::ComputeImageBounds ( const cv::Mat &  imLeft)
private
void ORB_SLAM2::Frame::ComputeStereoFromRGBD ( const cv::Mat &  imDepth)
void ORB_SLAM2::Frame::ComputeStereoMatches ( )
void ORB_SLAM2::Frame::ExtractORB ( int  flag,
const cv::Mat &  im 
)
cv::Mat ORB_SLAM2::Frame::GetCameraCenter ( )
inline

Definition at line 73 of file Frame.h.

vector<size_t> ORB_SLAM2::Frame::GetFeaturesInArea ( const float &  x,
const float &  y,
const float &  r,
const int  minLevel = -1,
const int  maxLevel = -1 
) const
cv::Mat ORB_SLAM2::Frame::GetRotationInverse ( )
inline

Definition at line 78 of file Frame.h.

bool ORB_SLAM2::Frame::isInFrustum ( MapPoint pMP,
float  viewingCosLimit 
)
bool ORB_SLAM2::Frame::PosInGrid ( const cv::KeyPoint &  kp,
int &  posX,
int &  posY 
)
void ORB_SLAM2::Frame::SetPose ( cv::Mat  Tcw)
void ORB_SLAM2::Frame::UndistortKeyPoints ( )
private
cv::Mat ORB_SLAM2::Frame::UnprojectStereo ( const int &  i)
void ORB_SLAM2::Frame::UpdatePoseMatrices ( )

Member Data Documentation

float ORB_SLAM2::Frame::cx
static

Definition at line 117 of file Frame.h.

float ORB_SLAM2::Frame::cy
static

Definition at line 118 of file Frame.h.

float ORB_SLAM2::Frame::fx
static

Definition at line 115 of file Frame.h.

float ORB_SLAM2::Frame::fy
static

Definition at line 116 of file Frame.h.

float ORB_SLAM2::Frame::invfx
static

Definition at line 119 of file Frame.h.

float ORB_SLAM2::Frame::invfy
static

Definition at line 120 of file Frame.h.

bool ORB_SLAM2::Frame::is_keyframe

Definition at line 103 of file Frame.h.

float ORB_SLAM2::Frame::mb

Definition at line 127 of file Frame.h.

float ORB_SLAM2::Frame::mbf

Definition at line 124 of file Frame.h.

bool ORB_SLAM2::Frame::mbInitialComputations
static

Definition at line 190 of file Frame.h.

DBoW2::BowVector ORB_SLAM2::Frame::mBowVec

Definition at line 148 of file Frame.h.

cv::Mat ORB_SLAM2::Frame::mDescriptors

Definition at line 152 of file Frame.h.

cv::Mat ORB_SLAM2::Frame::mDescriptorsRight

Definition at line 152 of file Frame.h.

cv::Mat ORB_SLAM2::Frame::mDistCoef

Definition at line 121 of file Frame.h.

DBoW2::FeatureVector ORB_SLAM2::Frame::mFeatVec

Definition at line 149 of file Frame.h.

float ORB_SLAM2::Frame::mfGridElementHeightInv
static

Definition at line 162 of file Frame.h.

float ORB_SLAM2::Frame::mfGridElementWidthInv
static

Definition at line 161 of file Frame.h.

float ORB_SLAM2::Frame::mfLogScaleFactor

Definition at line 178 of file Frame.h.

float ORB_SLAM2::Frame::mfScaleFactor

Definition at line 177 of file Frame.h.

std::vector<std::size_t> ORB_SLAM2::Frame::mGrid[FRAME_GRID_COLS][FRAME_GRID_ROWS]

Definition at line 163 of file Frame.h.

cv::Mat ORB_SLAM2::Frame::mK

Definition at line 114 of file Frame.h.

long unsigned int ORB_SLAM2::Frame::mnId

Definition at line 170 of file Frame.h.

float ORB_SLAM2::Frame::mnMaxX
static

Definition at line 186 of file Frame.h.

float ORB_SLAM2::Frame::mnMaxY
static

Definition at line 188 of file Frame.h.

float ORB_SLAM2::Frame::mnMinX
static

Definition at line 185 of file Frame.h.

float ORB_SLAM2::Frame::mnMinY
static

Definition at line 187 of file Frame.h.

int ORB_SLAM2::Frame::mnScaleLevels

Definition at line 176 of file Frame.h.

cv::Mat ORB_SLAM2::Frame::mOw
private

Definition at line 210 of file Frame.h.

ORBextractor* ORB_SLAM2::Frame::mpORBextractorLeft

Definition at line 108 of file Frame.h.

ORBextractor * ORB_SLAM2::Frame::mpORBextractorRight

Definition at line 108 of file Frame.h.

ORBVocabulary* ORB_SLAM2::Frame::mpORBvocabulary

Definition at line 105 of file Frame.h.

KeyFrame* ORB_SLAM2::Frame::mpReferenceKF

Definition at line 173 of file Frame.h.

cv::Mat ORB_SLAM2::Frame::mRcw
private

Definition at line 207 of file Frame.h.

cv::Mat ORB_SLAM2::Frame::mRwc
private

Definition at line 209 of file Frame.h.

cv::Mat ORB_SLAM2::Frame::mTcw

Definition at line 166 of file Frame.h.

cv::Mat ORB_SLAM2::Frame::mtcw
private

Definition at line 208 of file Frame.h.

float ORB_SLAM2::Frame::mThDepth

Definition at line 131 of file Frame.h.

double ORB_SLAM2::Frame::mTimeStamp

Definition at line 111 of file Frame.h.

std::vector<bool> ORB_SLAM2::Frame::mvbOutlier

Definition at line 158 of file Frame.h.

std::vector<float> ORB_SLAM2::Frame::mvDepth

Definition at line 145 of file Frame.h.

vector<float> ORB_SLAM2::Frame::mvInvLevelSigma2

Definition at line 182 of file Frame.h.

vector<float> ORB_SLAM2::Frame::mvInvScaleFactors

Definition at line 180 of file Frame.h.

std::vector<cv::KeyPoint> ORB_SLAM2::Frame::mvKeys

Definition at line 139 of file Frame.h.

std::vector<cv::KeyPoint> ORB_SLAM2::Frame::mvKeysRight

Definition at line 139 of file Frame.h.

std::vector<cv::KeyPoint> ORB_SLAM2::Frame::mvKeysUn

Definition at line 140 of file Frame.h.

vector<float> ORB_SLAM2::Frame::mvLevelSigma2

Definition at line 181 of file Frame.h.

std::vector<MapPoint*> ORB_SLAM2::Frame::mvpMapPoints

Definition at line 155 of file Frame.h.

vector<float> ORB_SLAM2::Frame::mvScaleFactors

Definition at line 179 of file Frame.h.

std::vector<float> ORB_SLAM2::Frame::mvuRight

Definition at line 144 of file Frame.h.

int ORB_SLAM2::Frame::N

Definition at line 134 of file Frame.h.

long unsigned int ORB_SLAM2::Frame::nNextId
static

Definition at line 169 of file Frame.h.


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


orb_slam2_with_maps_odom
Author(s): teng zhang
autogenerated on Fri Sep 25 2020 03:24:47