Public Types | Public 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 }
 
typedef pcl::PointCloud< PointTPointCloud
 
typedef pcl::PointXYZRGBA PointT
 

Public Member Functions

void ActivateLocalizationMode ()
 
void DeactivateLocalizationMode ()
 
LocalMappinggetLocalMapping ()
 
LoopClosinggetLoopClosing ()
 
MapgetMap ()
 
shared_ptr< PointCloudMappingGetPointCloudMapping ()
 
DataCache< cv::Mat > * GetTcwDataCache ()
 
int32_t GetTcwDataCacheIndex ()
 
std::vector< cv::KeyPoint > GetTrackedKeyPointsUn ()
 
std::vector< MapPoint * > GetTrackedMapPoints ()
 
TrackinggetTracker ()
 
int GetTrackingState ()
 
bool MapChanged ()
 
void Reset ()
 
void Save2dMapPointsTUM (const string &filename, const int x, const int y)
 
void SaveGridMapTUM (const string &filename)
 
void SaveKeyFrameTrajectoryTUM (const string &filename)
 
void SaveTrajectoryKITTI (const string &filename)
 
void SaveTrajectoryTUM (const string &filename)
 
void Shutdown ()
 
 System (const string &strVocFile, const string &strSettingsFile, const eSensor sensor, const bool bUseViewer=true)
 
cv::Mat TrackMonocular (const cv::Mat &im, const double &timestamp)
 
cv::Mat TrackRGBD (const cv::Mat &im, const cv::Mat &depthmap, const double &timestamp)
 
cv::Mat TrackStereo (const cv::Mat &imLeft, const cv::Mat &imRight, const double &timestamp)
 

Private Attributes

bool mbActivateLocalizationMode
 
bool mbDeactivateLocalizationMode
 
bool mbReset
 
int32_t miDataCacheIndex
 
std::mutex mMutexMode
 
std::mutex mMutexReset
 
std::mutex mMutexState
 
FrameDrawermpFrameDrawer
 
KeyFrameDatabasempKeyFrameDatabase
 
LocalMappingmpLocalMapper
 
LoopClosingmpLoopCloser
 
MapmpMap
 
MapDrawermpMapDrawer
 
shared_ptr< PointCloudMappingmpPointCloudMapping
 
DataCache< cv::Mat > * mpTcwDataCache
 
std::thread * mptLocalMapping
 
std::thread * mptLoopClosing
 
TrackingmpTracker
 
std::thread * mptViewer
 
ViewermpViewer
 
ORBVocabularympVocabulary
 
eSensor mSensor
 
std::vector< cv::KeyPoint > mTrackedKeyPointsUn
 
std::vector< MapPoint * > mTrackedMapPoints
 
int mTrackingState
 

Detailed Description

Definition at line 62 of file System.h.

Member Typedef Documentation

typedef pcl::PointCloud<PointT> ORB_SLAM2::System::PointCloud

Definition at line 72 of file System.h.

typedef pcl::PointXYZRGBA ORB_SLAM2::System::PointT

Definition at line 71 of file System.h.

Member Enumeration Documentation

Enumerator
MONOCULAR 
STEREO 
RGBD 

Definition at line 66 of file System.h.

Constructor & Destructor Documentation

ORB_SLAM2::System::System ( const string &  strVocFile,
const string &  strSettingsFile,
const eSensor  sensor,
const bool  bUseViewer = true 
)

Member Function Documentation

void ORB_SLAM2::System::ActivateLocalizationMode ( )
void ORB_SLAM2::System::DeactivateLocalizationMode ( )
LocalMapping* ORB_SLAM2::System::getLocalMapping ( )
inline

Definition at line 82 of file System.h.

LoopClosing* ORB_SLAM2::System::getLoopClosing ( )
inline

Definition at line 83 of file System.h.

Map* ORB_SLAM2::System::getMap ( )
inline

Definition at line 78 of file System.h.

shared_ptr<PointCloudMapping> ORB_SLAM2::System::GetPointCloudMapping ( )
DataCache<cv::Mat>* ORB_SLAM2::System::GetTcwDataCache ( )
int32_t ORB_SLAM2::System::GetTcwDataCacheIndex ( )
std::vector<cv::KeyPoint> ORB_SLAM2::System::GetTrackedKeyPointsUn ( )
std::vector<MapPoint*> ORB_SLAM2::System::GetTrackedMapPoints ( )
Tracking* ORB_SLAM2::System::getTracker ( )
inline

Definition at line 81 of file System.h.

int ORB_SLAM2::System::GetTrackingState ( )
bool ORB_SLAM2::System::MapChanged ( )
void ORB_SLAM2::System::Reset ( )
void ORB_SLAM2::System::Save2dMapPointsTUM ( const string &  filename,
const int  x,
const int  y 
)
void ORB_SLAM2::System::SaveGridMapTUM ( const string &  filename)
void ORB_SLAM2::System::SaveKeyFrameTrajectoryTUM ( const string &  filename)
void ORB_SLAM2::System::SaveTrajectoryKITTI ( const string &  filename)
void ORB_SLAM2::System::SaveTrajectoryTUM ( const string &  filename)
void ORB_SLAM2::System::Shutdown ( )
cv::Mat ORB_SLAM2::System::TrackMonocular ( const cv::Mat &  im,
const double &  timestamp 
)
cv::Mat ORB_SLAM2::System::TrackRGBD ( const cv::Mat &  im,
const cv::Mat &  depthmap,
const double &  timestamp 
)
cv::Mat ORB_SLAM2::System::TrackStereo ( const cv::Mat &  imLeft,
const cv::Mat &  imRight,
const double &  timestamp 
)

Member Data Documentation

bool ORB_SLAM2::System::mbActivateLocalizationMode
private

Definition at line 202 of file System.h.

bool ORB_SLAM2::System::mbDeactivateLocalizationMode
private

Definition at line 203 of file System.h.

bool ORB_SLAM2::System::mbReset
private

Definition at line 198 of file System.h.

int32_t ORB_SLAM2::System::miDataCacheIndex
private

Definition at line 158 of file System.h.

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

Definition at line 201 of file System.h.

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

Definition at line 197 of file System.h.

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

Definition at line 209 of file System.h.

FrameDrawer* ORB_SLAM2::System::mpFrameDrawer
private

Definition at line 187 of file System.h.

KeyFrameDatabase* ORB_SLAM2::System::mpKeyFrameDatabase
private

Definition at line 167 of file System.h.

LocalMapping* ORB_SLAM2::System::mpLocalMapper
private

Definition at line 178 of file System.h.

LoopClosing* ORB_SLAM2::System::mpLoopCloser
private

Definition at line 182 of file System.h.

Map* ORB_SLAM2::System::mpMap
private

Definition at line 170 of file System.h.

MapDrawer* ORB_SLAM2::System::mpMapDrawer
private

Definition at line 188 of file System.h.

shared_ptr<PointCloudMapping> ORB_SLAM2::System::mpPointCloudMapping
private

Definition at line 212 of file System.h.

DataCache<cv::Mat>* ORB_SLAM2::System::mpTcwDataCache
private

Definition at line 157 of file System.h.

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

Definition at line 192 of file System.h.

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

Definition at line 193 of file System.h.

Tracking* ORB_SLAM2::System::mpTracker
private

Definition at line 175 of file System.h.

std::thread* ORB_SLAM2::System::mptViewer
private

Definition at line 194 of file System.h.

Viewer* ORB_SLAM2::System::mpViewer
private

Definition at line 185 of file System.h.

ORBVocabulary* ORB_SLAM2::System::mpVocabulary
private

Definition at line 164 of file System.h.

eSensor ORB_SLAM2::System::mSensor
private

Definition at line 161 of file System.h.

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

Definition at line 208 of file System.h.

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

Definition at line 207 of file System.h.

int ORB_SLAM2::System::mTrackingState
private

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