Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
ORB_SLAM2::System Class Reference

#include <System.h>

Public Types

enum  eSensor { MONOCULAR =0, STEREO =1, RGBD =2 }
 

Public Member Functions

cv::Mat DrawCurrentFrame ()
 
void EnableLocalizationOnly (bool localize_only)
 
std::vector< MapPoint * > GetAllMapPoints ()
 
cv::Mat GetCurrentPosition ()
 
std::vector< cv::KeyPoint > GetTrackedKeyPointsUn ()
 
std::vector< MapPoint * > GetTrackedMapPoints ()
 
int GetTrackingState ()
 
bool isRunningGBA ()
 
bool MapChanged ()
 
void Reset ()
 
void SaveKeyFrameTrajectoryTUM (const string &filename)
 
bool SaveMap (const string &filename)
 
void SaveTrajectoryKITTI (const string &filename)
 
void SaveTrajectoryTUM (const string &filename)
 
void SetMinimumKeyFrames (int min_num_kf)
 
void Shutdown ()
 
 System (const string strVocFile, const eSensor sensor, ORBParameters &parameters, const std::string &map_file="", bool load_map=false)
 
void TrackMonocular (const cv::Mat &im, const double &timestamp)
 
void TrackRGBD (const cv::Mat &im, const cv::Mat &depthmap, const double &timestamp)
 
void TrackStereo (const cv::Mat &imLeft, const cv::Mat &imRight, const double &timestamp)
 

Private Member Functions

void ActivateLocalizationMode ()
 
void DeactivateLocalizationMode ()
 
rlim_t GetCurrentCallStackSize ()
 
bool LoadMap (const string &filename)
 
bool SetCallStackSize (const rlim_t kNewStackSize)
 

Private Attributes

cv::Mat current_position_
 
bool currently_localizing_only_
 
bool load_map
 
std::string map_file
 
bool mbActivateLocalizationMode
 
bool mbDeactivateLocalizationMode
 
bool mbReset
 
std::mutex mMutexMode
 
std::mutex mMutexReset
 
std::mutex mMutexState
 
FrameDrawermpFrameDrawer
 
KeyFrameDatabasempKeyFrameDatabase
 
LocalMappingmpLocalMapper
 
LoopClosingmpLoopCloser
 
MapmpMap
 
std::thread * mptLocalMapping
 
std::thread * mptLoopClosing
 
TrackingmpTracker
 
ORBVocabularympVocabulary
 
eSensor mSensor
 
std::vector< cv::KeyPoint > mTrackedKeyPointsUn
 
std::vector< MapPoint * > mTrackedMapPoints
 
int mTrackingState
 

Detailed Description

Definition at line 50 of file System.h.

Member Enumeration Documentation

Enumerator
MONOCULAR 
STEREO 
RGBD 

Definition at line 54 of file System.h.

Constructor & Destructor Documentation

ORB_SLAM2::System::System ( const string  strVocFile,
const eSensor  sensor,
ORBParameters parameters,
const std::string &  map_file = "",
bool  load_map = false 
)

Definition at line 31 of file System.cc.

Member Function Documentation

void ORB_SLAM2::System::ActivateLocalizationMode ( )
private

Definition at line 544 of file System.cc.

void ORB_SLAM2::System::DeactivateLocalizationMode ( )
private

Definition at line 551 of file System.cc.

cv::Mat ORB_SLAM2::System::DrawCurrentFrame ( )

Definition at line 493 of file System.cc.

void ORB_SLAM2::System::EnableLocalizationOnly ( bool  localize_only)

Definition at line 558 of file System.cc.

std::vector< MapPoint * > ORB_SLAM2::System::GetAllMapPoints ( )

Definition at line 497 of file System.cc.

rlim_t ORB_SLAM2::System::GetCurrentCallStackSize ( )
private

Definition at line 530 of file System.cc.

cv::Mat ORB_SLAM2::System::GetCurrentPosition ( )

Definition at line 471 of file System.cc.

vector< cv::KeyPoint > ORB_SLAM2::System::GetTrackedKeyPointsUn ( )

Definition at line 487 of file System.cc.

vector< MapPoint * > ORB_SLAM2::System::GetTrackedMapPoints ( )

Definition at line 481 of file System.cc.

int ORB_SLAM2::System::GetTrackingState ( )

Definition at line 475 of file System.cc.

bool ORB_SLAM2::System::isRunningGBA ( )

Definition at line 292 of file System.cc.

bool ORB_SLAM2::System::LoadMap ( const string &  filename)
private

Definition at line 609 of file System.cc.

bool ORB_SLAM2::System::MapChanged ( )

Definition at line 279 of file System.cc.

void ORB_SLAM2::System::Reset ( )

Definition at line 297 of file System.cc.

void ORB_SLAM2::System::SaveKeyFrameTrajectoryTUM ( const string &  filename)

Definition at line 376 of file System.cc.

bool ORB_SLAM2::System::SaveMap ( const string &  filename)

Definition at line 573 of file System.cc.

void ORB_SLAM2::System::SaveTrajectoryKITTI ( const string &  filename)

Definition at line 412 of file System.cc.

void ORB_SLAM2::System::SaveTrajectoryTUM ( const string &  filename)

Definition at line 315 of file System.cc.

bool ORB_SLAM2::System::SetCallStackSize ( const rlim_t  kNewStackSize)
private

Definition at line 502 of file System.cc.

void ORB_SLAM2::System::SetMinimumKeyFrames ( int  min_num_kf)

Definition at line 467 of file System.cc.

void ORB_SLAM2::System::Shutdown ( )

Definition at line 303 of file System.cc.

void ORB_SLAM2::System::TrackMonocular ( const cv::Mat &  im,
const double &  timestamp 
)

Definition at line 227 of file System.cc.

void ORB_SLAM2::System::TrackRGBD ( const cv::Mat &  im,
const cv::Mat &  depthmap,
const double &  timestamp 
)

Definition at line 176 of file System.cc.

void ORB_SLAM2::System::TrackStereo ( const cv::Mat &  imLeft,
const cv::Mat &  imRight,
const double &  timestamp 
)

Definition at line 125 of file System.cc.

Member Data Documentation

cv::Mat ORB_SLAM2::System::current_position_
private

Definition at line 204 of file System.h.

bool ORB_SLAM2::System::currently_localizing_only_
private

Definition at line 151 of file System.h.

bool ORB_SLAM2::System::load_map
private

Definition at line 153 of file System.h.

std::string ORB_SLAM2::System::map_file
private

Definition at line 155 of file System.h.

bool ORB_SLAM2::System::mbActivateLocalizationMode
private

Definition at line 194 of file System.h.

bool ORB_SLAM2::System::mbDeactivateLocalizationMode
private

Definition at line 195 of file System.h.

bool ORB_SLAM2::System::mbReset
private

Definition at line 190 of file System.h.

std::mutex ORB_SLAM2::System::mMutexMode
private

Definition at line 193 of file System.h.

std::mutex ORB_SLAM2::System::mMutexReset
private

Definition at line 189 of file System.h.

std::mutex ORB_SLAM2::System::mMutexState
private

Definition at line 201 of file System.h.

FrameDrawer* ORB_SLAM2::System::mpFrameDrawer
private

Definition at line 181 of file System.h.

KeyFrameDatabase* ORB_SLAM2::System::mpKeyFrameDatabase
private

Definition at line 164 of file System.h.

LocalMapping* ORB_SLAM2::System::mpLocalMapper
private

Definition at line 175 of file System.h.

LoopClosing* ORB_SLAM2::System::mpLoopCloser
private

Definition at line 179 of file System.h.

Map* ORB_SLAM2::System::mpMap
private

Definition at line 167 of file System.h.

std::thread* ORB_SLAM2::System::mptLocalMapping
private

Definition at line 185 of file System.h.

std::thread* ORB_SLAM2::System::mptLoopClosing
private

Definition at line 186 of file System.h.

Tracking* ORB_SLAM2::System::mpTracker
private

Definition at line 172 of file System.h.

ORBVocabulary* ORB_SLAM2::System::mpVocabulary
private

Definition at line 161 of file System.h.

eSensor ORB_SLAM2::System::mSensor
private

Definition at line 158 of file System.h.

std::vector<cv::KeyPoint> ORB_SLAM2::System::mTrackedKeyPointsUn
private

Definition at line 200 of file System.h.

std::vector<MapPoint*> ORB_SLAM2::System::mTrackedMapPoints
private

Definition at line 199 of file System.h.

int ORB_SLAM2::System::mTrackingState
private

Definition at line 198 of file System.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