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 SetViewer (Viewer *pViewer)
 
 Tracking (System *pSys, ORBVocabulary *pVoc, FrameDrawer *pFrameDrawer, MapDrawer *pMapDrawer, Map *pMap, shared_ptr< PointCloudMapping > pPointCloud, KeyFrameDatabase *pKFDB, const string &strSettingPath, const int sensor)
 

Public Attributes

bool loop_detected
 
bool mbOnlyTracking
 
Frame mCurrentFrame
 
cv::Mat mImDepth
 
cv::Mat mImGray
 
cv::Mat mImRGB_ZT
 
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

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
 
FrameDrawermpFrameDrawer
 
ORBextractormpIniORBextractor
 
InitializermpInitializer
 
KeyFrameDatabasempKeyFrameDB
 
KeyFramempLastKeyFrame
 
LocalMappingmpLocalMapper
 
LoopClosingmpLoopClosing
 
MapmpMap
 
MapDrawermpMapDrawer
 
ORBextractormpORBextractorLeft
 
ORBextractormpORBextractorRight
 
ORBVocabularympORBVocabulary
 
shared_ptr< PointCloudMappingmpPointCloudMapping
 
KeyFramempReferenceKF
 
SystemmpSystem
 
ViewermpViewer
 
float mThDepth
 
cv::Mat mVelocity
 
std::vector< KeyFrame * > mvpLocalKeyFrames
 
std::vector< MapPoint * > mvpLocalMapPoints
 

Detailed Description

Definition at line 59 of file Tracking.h.

Member Enumeration Documentation

Enumerator
SYSTEM_NOT_READY 
NO_IMAGES_YET 
NOT_INITIALIZED 
OK 
LOST 

Definition at line 90 of file Tracking.h.

Constructor & Destructor Documentation

ORB_SLAM2::Tracking::Tracking ( System pSys,
ORBVocabulary pVoc,
FrameDrawer pFrameDrawer,
MapDrawer pMapDrawer,
Map pMap,
shared_ptr< PointCloudMapping pPointCloud,
KeyFrameDatabase pKFDB,
const string &  strSettingPath,
const int  sensor 
)

Member Function Documentation

void ORB_SLAM2::Tracking::ChangeCalibration ( const string &  strSettingPath)
void ORB_SLAM2::Tracking::CheckReplacedInLastFrame ( )
protected
void ORB_SLAM2::Tracking::CreateInitialMapMonocular ( )
protected
void ORB_SLAM2::Tracking::CreateNewKeyFrame ( )
protected
cv::Mat ORB_SLAM2::Tracking::GrabImageMonocular ( const cv::Mat &  im,
const double &  timestamp 
)
cv::Mat ORB_SLAM2::Tracking::GrabImageRGBD ( const cv::Mat &  imRGB,
const cv::Mat &  imD,
const double &  timestamp 
)
cv::Mat ORB_SLAM2::Tracking::GrabImageStereo ( const cv::Mat &  imRectLeft,
const cv::Mat &  imRectRight,
const double &  timestamp 
)
void ORB_SLAM2::Tracking::InformOnlyTracking ( const bool &  flag)
void ORB_SLAM2::Tracking::MonocularInitialization ( )
protected
bool ORB_SLAM2::Tracking::NeedNewKeyFrame ( )
protected
bool ORB_SLAM2::Tracking::Relocalization ( )
protected
void ORB_SLAM2::Tracking::Reset ( )
void ORB_SLAM2::Tracking::SearchLocalPoints ( )
protected
void ORB_SLAM2::Tracking::SetLocalMapper ( LocalMapping pLocalMapper)
void ORB_SLAM2::Tracking::SetLoopClosing ( LoopClosing pLoopClosing)
void ORB_SLAM2::Tracking::SetViewer ( Viewer pViewer)
void ORB_SLAM2::Tracking::StereoInitialization ( )
protected
void ORB_SLAM2::Tracking::Track ( )
protected
bool ORB_SLAM2::Tracking::TrackLocalMap ( )
protected
bool ORB_SLAM2::Tracking::TrackReferenceKeyFrame ( )
protected
bool ORB_SLAM2::Tracking::TrackWithMotionModel ( )
protected
void ORB_SLAM2::Tracking::UpdateLastFrame ( )
protected
void ORB_SLAM2::Tracking::UpdateLocalKeyFrames ( )
protected
void ORB_SLAM2::Tracking::UpdateLocalMap ( )
protected
void ORB_SLAM2::Tracking::UpdateLocalPoints ( )
protected

Member Data Documentation

bool ORB_SLAM2::Tracking::loop_detected

Definition at line 87 of file Tracking.h.

float ORB_SLAM2::Tracking::mbf
protected

Definition at line 198 of file Tracking.h.

bool ORB_SLAM2::Tracking::mbOnlyTracking

Definition at line 125 of file Tracking.h.

bool ORB_SLAM2::Tracking::mbRGB
protected

Definition at line 225 of file Tracking.h.

bool ORB_SLAM2::Tracking::mbVO
protected

Definition at line 162 of file Tracking.h.

Frame ORB_SLAM2::Tracking::mCurrentFrame

Definition at line 105 of file Tracking.h.

float ORB_SLAM2::Tracking::mDepthMapFactor
protected

Definition at line 210 of file Tracking.h.

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

Definition at line 197 of file Tracking.h.

cv::Mat ORB_SLAM2::Tracking::mImDepth

Definition at line 108 of file Tracking.h.

cv::Mat ORB_SLAM2::Tracking::mImGray

Definition at line 106 of file Tracking.h.

cv::Mat ORB_SLAM2::Tracking::mImRGB_ZT

Definition at line 107 of file Tracking.h.

Frame ORB_SLAM2::Tracking::mInitialFrame

Definition at line 115 of file Tracking.h.

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

Definition at line 196 of file Tracking.h.

Frame ORB_SLAM2::Tracking::mLastFrame
protected

Definition at line 217 of file Tracking.h.

eTrackingState ORB_SLAM2::Tracking::mLastProcessedState

Definition at line 99 of file Tracking.h.

list<bool> ORB_SLAM2::Tracking::mlbLost

Definition at line 122 of file Tracking.h.

list<double> ORB_SLAM2::Tracking::mlFrameTimes

Definition at line 121 of file Tracking.h.

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

Definition at line 120 of file Tracking.h.

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

Definition at line 227 of file Tracking.h.

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

Definition at line 119 of file Tracking.h.

int ORB_SLAM2::Tracking::mMaxFrames
protected

Definition at line 202 of file Tracking.h.

int ORB_SLAM2::Tracking::mMinFrames
protected

Definition at line 201 of file Tracking.h.

unsigned int ORB_SLAM2::Tracking::mnLastKeyFrameId
protected

Definition at line 218 of file Tracking.h.

unsigned int ORB_SLAM2::Tracking::mnLastRelocFrameId
protected

Definition at line 219 of file Tracking.h.

int ORB_SLAM2::Tracking::mnMatchesInliers
protected

Definition at line 213 of file Tracking.h.

FrameDrawer* ORB_SLAM2::Tracking::mpFrameDrawer
protected

Definition at line 189 of file Tracking.h.

ORBextractor* ORB_SLAM2::Tracking::mpIniORBextractor
protected

Definition at line 170 of file Tracking.h.

Initializer* ORB_SLAM2::Tracking::mpInitializer
protected

Definition at line 177 of file Tracking.h.

KeyFrameDatabase* ORB_SLAM2::Tracking::mpKeyFrameDB
protected

Definition at line 174 of file Tracking.h.

KeyFrame* ORB_SLAM2::Tracking::mpLastKeyFrame
protected

Definition at line 216 of file Tracking.h.

LocalMapping* ORB_SLAM2::Tracking::mpLocalMapper
protected

Definition at line 165 of file Tracking.h.

LoopClosing* ORB_SLAM2::Tracking::mpLoopClosing
protected

Definition at line 166 of file Tracking.h.

Map* ORB_SLAM2::Tracking::mpMap
protected

Definition at line 193 of file Tracking.h.

MapDrawer* ORB_SLAM2::Tracking::mpMapDrawer
protected

Definition at line 190 of file Tracking.h.

ORBextractor* ORB_SLAM2::Tracking::mpORBextractorLeft
protected

Definition at line 169 of file Tracking.h.

ORBextractor * ORB_SLAM2::Tracking::mpORBextractorRight
protected

Definition at line 169 of file Tracking.h.

ORBVocabulary* ORB_SLAM2::Tracking::mpORBVocabulary
protected

Definition at line 173 of file Tracking.h.

shared_ptr<PointCloudMapping> ORB_SLAM2::Tracking::mpPointCloudMapping
protected

Definition at line 230 of file Tracking.h.

KeyFrame* ORB_SLAM2::Tracking::mpReferenceKF
protected

Definition at line 180 of file Tracking.h.

System* ORB_SLAM2::Tracking::mpSystem
protected

Definition at line 185 of file Tracking.h.

Viewer* ORB_SLAM2::Tracking::mpViewer
protected

Definition at line 188 of file Tracking.h.

int ORB_SLAM2::Tracking::mSensor

Definition at line 102 of file Tracking.h.

eTrackingState ORB_SLAM2::Tracking::mState

Definition at line 98 of file Tracking.h.

float ORB_SLAM2::Tracking::mThDepth
protected

Definition at line 207 of file Tracking.h.

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

Definition at line 113 of file Tracking.h.

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

Definition at line 222 of file Tracking.h.

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

Definition at line 111 of file Tracking.h.

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

Definition at line 112 of file Tracking.h.

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

Definition at line 114 of file Tracking.h.

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

Definition at line 181 of file Tracking.h.

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

Definition at line 182 of file Tracking.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