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

#include <Tracking.h>

Public Types

enum  eTrackingState {
  SYSTEM_NOT_READY =-1, NO_IMAGES_YET =0, NOT_INITIALIZED =1, OK =2,
  LOST =3
}
 

Public Member Functions

void ChangeCalibration (const string &strSettingPath)
 
cv::Mat GrabImageMonocular (const cv::Mat &im, const double &timestamp)
 
cv::Mat GrabImageRGBD (const cv::Mat &imRGB, const cv::Mat &imD, const double &timestamp)
 
cv::Mat GrabImageStereo (const cv::Mat &imRectLeft, const cv::Mat &imRectRight, const double &timestamp)
 
void InformOnlyTracking (const bool &flag)
 
void Reset ()
 
void SetLocalMapper (LocalMapping *pLocalMapper)
 
void SetLoopClosing (LoopClosing *pLoopClosing)
 
void SetMinimumKeyFrames (int min_num_kf)
 
 Tracking (System *pSys, ORBVocabulary *pVoc, FrameDrawer *pFrameDrawer, Map *pMap, KeyFrameDatabase *pKFDB, const int sensor, ORBParameters &parameters)
 

Public Attributes

bool mbOnlyTracking
 
Frame mCurrentFrame
 
cv::Mat mImGray
 
Frame mInitialFrame
 
eTrackingState mLastProcessedState
 
list< bool > mlbLost
 
list< double > mlFrameTimes
 
list< KeyFrame * > mlpReferences
 
list< cv::Mat > mlRelativeFramePoses
 
int mSensor
 
eTrackingState mState
 
std::vector< cv::Point2f > mvbPrevMatched
 
std::vector< int > mvIniLastMatches
 
std::vector< int > mvIniMatches
 
std::vector< cv::Point3f > mvIniP3D
 

Protected Member Functions

void CheckReplacedInLastFrame ()
 
void CreateInitialMapMonocular ()
 
void CreateNewKeyFrame ()
 
void MonocularInitialization ()
 
bool NeedNewKeyFrame ()
 
bool Relocalization ()
 
void SearchLocalPoints ()
 
void StereoInitialization ()
 
void Track ()
 
bool TrackLocalMap ()
 
bool TrackReferenceKeyFrame ()
 
bool TrackWithMotionModel ()
 
void UpdateLastFrame ()
 
void UpdateLocalKeyFrames ()
 
void UpdateLocalMap ()
 
void UpdateLocalPoints ()
 

Protected Attributes

int fIniThFAST
 
int fMinThFAST
 
float fScaleFactor
 
float mbf
 
bool mbRGB
 
bool mbVO
 
float mDepthMapFactor
 
cv::Mat mDistCoef
 
cv::Mat mK
 
Frame mLastFrame
 
list< MapPoint * > mlpTemporalPoints
 
int mMaxFrames
 
int mMinFrames
 
unsigned int mnLastKeyFrameId
 
unsigned int mnLastRelocFrameId
 
int mnMatchesInliers
 
int mnMinimumKeyFrames
 
FrameDrawermpFrameDrawer
 
ORBextractormpIniORBextractor
 
InitializermpInitializer
 
KeyFrameDatabasempKeyFrameDB
 
KeyFramempLastKeyFrame
 
LocalMappingmpLocalMapper
 
LoopClosingmpLoopClosing
 
MapmpMap
 
ORBextractormpORBextractorLeft
 
ORBextractormpORBextractorRight
 
ORBVocabularympORBVocabulary
 
KeyFramempReferenceKF
 
SystemmpSystem
 
float mThDepth
 
cv::Mat mVelocity
 
std::vector< KeyFrame * > mvpLocalKeyFrames
 
std::vector< MapPoint * > mvpLocalMapPoints
 
int nFeatures
 
int nLevels
 

Detailed Description

Definition at line 65 of file Tracking.h.

Member Enumeration Documentation

◆ eTrackingState

Enumerator
SYSTEM_NOT_READY 
NO_IMAGES_YET 
NOT_INITIALIZED 
OK 
LOST 

Definition at line 93 of file Tracking.h.

Constructor & Destructor Documentation

◆ Tracking()

ORB_SLAM2::Tracking::Tracking ( System pSys,
ORBVocabulary pVoc,
FrameDrawer pFrameDrawer,
Map pMap,
KeyFrameDatabase pKFDB,
const int  sensor,
ORBParameters parameters 
)

Definition at line 46 of file Tracking.cc.

Member Function Documentation

◆ ChangeCalibration()

void ORB_SLAM2::Tracking::ChangeCalibration ( const string &  strSettingPath)

Definition at line 1526 of file Tracking.cc.

◆ CheckReplacedInLastFrame()

void ORB_SLAM2::Tracking::CheckReplacedInLastFrame ( )
protected

Definition at line 720 of file Tracking.cc.

◆ CreateInitialMapMonocular()

void ORB_SLAM2::Tracking::CreateInitialMapMonocular ( )
protected

Definition at line 618 of file Tracking.cc.

◆ CreateNewKeyFrame()

void ORB_SLAM2::Tracking::CreateNewKeyFrame ( )
protected

Definition at line 1044 of file Tracking.cc.

◆ GrabImageMonocular()

cv::Mat ORB_SLAM2::Tracking::GrabImageMonocular ( const cv::Mat &  im,
const double &  timestamp 
)

Definition at line 219 of file Tracking.cc.

◆ GrabImageRGBD()

cv::Mat ORB_SLAM2::Tracking::GrabImageRGBD ( const cv::Mat &  imRGB,
const cv::Mat &  imD,
const double &  timestamp 
)

Definition at line 188 of file Tracking.cc.

◆ GrabImageStereo()

cv::Mat ORB_SLAM2::Tracking::GrabImageStereo ( const cv::Mat &  imRectLeft,
const cv::Mat &  imRectRight,
const double &  timestamp 
)

Definition at line 148 of file Tracking.cc.

◆ InformOnlyTracking()

void ORB_SLAM2::Tracking::InformOnlyTracking ( const bool &  flag)

Definition at line 1559 of file Tracking.cc.

◆ MonocularInitialization()

void ORB_SLAM2::Tracking::MonocularInitialization ( )
protected

Definition at line 544 of file Tracking.cc.

◆ NeedNewKeyFrame()

bool ORB_SLAM2::Tracking::NeedNewKeyFrame ( )
protected

Definition at line 958 of file Tracking.cc.

◆ Relocalization()

bool ORB_SLAM2::Tracking::Relocalization ( )
protected

Definition at line 1322 of file Tracking.cc.

◆ Reset()

void ORB_SLAM2::Tracking::Reset ( )

Definition at line 1486 of file Tracking.cc.

◆ SearchLocalPoints()

void ORB_SLAM2::Tracking::SearchLocalPoints ( )
protected

Definition at line 1124 of file Tracking.cc.

◆ SetLocalMapper()

void ORB_SLAM2::Tracking::SetLocalMapper ( LocalMapping pLocalMapper)

Definition at line 137 of file Tracking.cc.

◆ SetLoopClosing()

void ORB_SLAM2::Tracking::SetLoopClosing ( LoopClosing pLoopClosing)

Definition at line 142 of file Tracking.cc.

◆ SetMinimumKeyFrames()

void ORB_SLAM2::Tracking::SetMinimumKeyFrames ( int  min_num_kf)
inline

Definition at line 79 of file Tracking.h.

◆ StereoInitialization()

void ORB_SLAM2::Tracking::StereoInitialization ( )
protected

Definition at line 490 of file Tracking.cc.

◆ Track()

void ORB_SLAM2::Tracking::Track ( )
protected

Definition at line 248 of file Tracking.cc.

◆ TrackLocalMap()

bool ORB_SLAM2::Tracking::TrackLocalMap ( )
protected

Definition at line 911 of file Tracking.cc.

◆ TrackReferenceKeyFrame()

bool ORB_SLAM2::Tracking::TrackReferenceKeyFrame ( )
protected

Definition at line 738 of file Tracking.cc.

◆ TrackWithMotionModel()

bool ORB_SLAM2::Tracking::TrackWithMotionModel ( )
protected

Definition at line 848 of file Tracking.cc.

◆ UpdateLastFrame()

void ORB_SLAM2::Tracking::UpdateLastFrame ( )
protected

Definition at line 782 of file Tracking.cc.

◆ UpdateLocalKeyFrames()

void ORB_SLAM2::Tracking::UpdateLocalKeyFrames ( )
protected

Definition at line 1212 of file Tracking.cc.

◆ UpdateLocalMap()

void ORB_SLAM2::Tracking::UpdateLocalMap ( )
protected

Definition at line 1176 of file Tracking.cc.

◆ UpdateLocalPoints()

void ORB_SLAM2::Tracking::UpdateLocalPoints ( )
protected

Definition at line 1186 of file Tracking.cc.

Member Data Documentation

◆ fIniThFAST

int ORB_SLAM2::Tracking::fIniThFAST
protected

Definition at line 236 of file Tracking.h.

◆ fMinThFAST

int ORB_SLAM2::Tracking::fMinThFAST
protected

Definition at line 237 of file Tracking.h.

◆ fScaleFactor

float ORB_SLAM2::Tracking::fScaleFactor
protected

Definition at line 234 of file Tracking.h.

◆ mbf

float ORB_SLAM2::Tracking::mbf
protected

Definition at line 200 of file Tracking.h.

◆ mbOnlyTracking

bool ORB_SLAM2::Tracking::mbOnlyTracking

Definition at line 126 of file Tracking.h.

◆ mbRGB

bool ORB_SLAM2::Tracking::mbRGB
protected

Definition at line 227 of file Tracking.h.

◆ mbVO

bool ORB_SLAM2::Tracking::mbVO
protected

Definition at line 163 of file Tracking.h.

◆ mCurrentFrame

Frame ORB_SLAM2::Tracking::mCurrentFrame

Definition at line 108 of file Tracking.h.

◆ mDepthMapFactor

float ORB_SLAM2::Tracking::mDepthMapFactor
protected

Definition at line 212 of file Tracking.h.

◆ mDistCoef

cv::Mat ORB_SLAM2::Tracking::mDistCoef
protected

Definition at line 199 of file Tracking.h.

◆ mImGray

cv::Mat ORB_SLAM2::Tracking::mImGray

Definition at line 109 of file Tracking.h.

◆ mInitialFrame

Frame ORB_SLAM2::Tracking::mInitialFrame

Definition at line 116 of file Tracking.h.

◆ mK

cv::Mat ORB_SLAM2::Tracking::mK
protected

Definition at line 198 of file Tracking.h.

◆ mLastFrame

Frame ORB_SLAM2::Tracking::mLastFrame
protected

Definition at line 219 of file Tracking.h.

◆ mLastProcessedState

eTrackingState ORB_SLAM2::Tracking::mLastProcessedState

Definition at line 102 of file Tracking.h.

◆ mlbLost

list<bool> ORB_SLAM2::Tracking::mlbLost

Definition at line 123 of file Tracking.h.

◆ mlFrameTimes

list<double> ORB_SLAM2::Tracking::mlFrameTimes

Definition at line 122 of file Tracking.h.

◆ mlpReferences

list<KeyFrame*> ORB_SLAM2::Tracking::mlpReferences

Definition at line 121 of file Tracking.h.

◆ mlpTemporalPoints

list<MapPoint*> ORB_SLAM2::Tracking::mlpTemporalPoints
protected

Definition at line 229 of file Tracking.h.

◆ mlRelativeFramePoses

list<cv::Mat> ORB_SLAM2::Tracking::mlRelativeFramePoses

Definition at line 120 of file Tracking.h.

◆ mMaxFrames

int ORB_SLAM2::Tracking::mMaxFrames
protected

Definition at line 204 of file Tracking.h.

◆ mMinFrames

int ORB_SLAM2::Tracking::mMinFrames
protected

Definition at line 203 of file Tracking.h.

◆ mnLastKeyFrameId

unsigned int ORB_SLAM2::Tracking::mnLastKeyFrameId
protected

Definition at line 220 of file Tracking.h.

◆ mnLastRelocFrameId

unsigned int ORB_SLAM2::Tracking::mnLastRelocFrameId
protected

Definition at line 221 of file Tracking.h.

◆ mnMatchesInliers

int ORB_SLAM2::Tracking::mnMatchesInliers
protected

Definition at line 215 of file Tracking.h.

◆ mnMinimumKeyFrames

int ORB_SLAM2::Tracking::mnMinimumKeyFrames
protected

Definition at line 166 of file Tracking.h.

◆ mpFrameDrawer

FrameDrawer* ORB_SLAM2::Tracking::mpFrameDrawer
protected

Definition at line 192 of file Tracking.h.

◆ mpIniORBextractor

ORBextractor* ORB_SLAM2::Tracking::mpIniORBextractor
protected

Definition at line 174 of file Tracking.h.

◆ mpInitializer

Initializer* ORB_SLAM2::Tracking::mpInitializer
protected

Definition at line 181 of file Tracking.h.

◆ mpKeyFrameDB

KeyFrameDatabase* ORB_SLAM2::Tracking::mpKeyFrameDB
protected

Definition at line 178 of file Tracking.h.

◆ mpLastKeyFrame

KeyFrame* ORB_SLAM2::Tracking::mpLastKeyFrame
protected

Definition at line 218 of file Tracking.h.

◆ mpLocalMapper

LocalMapping* ORB_SLAM2::Tracking::mpLocalMapper
protected

Definition at line 169 of file Tracking.h.

◆ mpLoopClosing

LoopClosing* ORB_SLAM2::Tracking::mpLoopClosing
protected

Definition at line 170 of file Tracking.h.

◆ mpMap

Map* ORB_SLAM2::Tracking::mpMap
protected

Definition at line 195 of file Tracking.h.

◆ mpORBextractorLeft

ORBextractor* ORB_SLAM2::Tracking::mpORBextractorLeft
protected

Definition at line 173 of file Tracking.h.

◆ mpORBextractorRight

ORBextractor * ORB_SLAM2::Tracking::mpORBextractorRight
protected

Definition at line 173 of file Tracking.h.

◆ mpORBVocabulary

ORBVocabulary* ORB_SLAM2::Tracking::mpORBVocabulary
protected

Definition at line 177 of file Tracking.h.

◆ mpReferenceKF

KeyFrame* ORB_SLAM2::Tracking::mpReferenceKF
protected

Definition at line 184 of file Tracking.h.

◆ mpSystem

System* ORB_SLAM2::Tracking::mpSystem
protected

Definition at line 189 of file Tracking.h.

◆ mSensor

int ORB_SLAM2::Tracking::mSensor

Definition at line 105 of file Tracking.h.

◆ mState

eTrackingState ORB_SLAM2::Tracking::mState

Definition at line 101 of file Tracking.h.

◆ mThDepth

float ORB_SLAM2::Tracking::mThDepth
protected

Definition at line 209 of file Tracking.h.

◆ mvbPrevMatched

std::vector<cv::Point2f> ORB_SLAM2::Tracking::mvbPrevMatched

Definition at line 114 of file Tracking.h.

◆ mVelocity

cv::Mat ORB_SLAM2::Tracking::mVelocity
protected

Definition at line 224 of file Tracking.h.

◆ mvIniLastMatches

std::vector<int> ORB_SLAM2::Tracking::mvIniLastMatches

Definition at line 112 of file Tracking.h.

◆ mvIniMatches

std::vector<int> ORB_SLAM2::Tracking::mvIniMatches

Definition at line 113 of file Tracking.h.

◆ mvIniP3D

std::vector<cv::Point3f> ORB_SLAM2::Tracking::mvIniP3D

Definition at line 115 of file Tracking.h.

◆ mvpLocalKeyFrames

std::vector<KeyFrame*> ORB_SLAM2::Tracking::mvpLocalKeyFrames
protected

Definition at line 185 of file Tracking.h.

◆ mvpLocalMapPoints

std::vector<MapPoint*> ORB_SLAM2::Tracking::mvpLocalMapPoints
protected

Definition at line 186 of file Tracking.h.

◆ nFeatures

int ORB_SLAM2::Tracking::nFeatures
protected

Definition at line 233 of file Tracking.h.

◆ nLevels

int ORB_SLAM2::Tracking::nLevels
protected

Definition at line 235 of file Tracking.h.


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


orb_slam2_ros
Author(s):
autogenerated on Mon Feb 28 2022 23:03:52