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

#include <LoopClosing.h>

Public Types

typedef pair< set< KeyFrame * >, int > ConsistentGroup
 
typedef map< KeyFrame *, g2o::Sim3, std::less< KeyFrame * >, Eigen::aligned_allocator< std::pair< KeyFrame *const, g2o::Sim3 > > > KeyFrameAndPose
 

Public Member Functions

void InsertKeyFrame (KeyFrame *pKF)
 
bool isFinished ()
 
bool isFinishedGBA ()
 
bool isRunningGBA ()
 
 LoopClosing (Map *pMap, KeyFrameDatabase *pDB, ORBVocabulary *pVoc, const bool bFixScale)
 
void RequestFinish ()
 
void RequestReset ()
 
void Run ()
 
void RunGlobalBundleAdjustment (unsigned long nLoopKF)
 
void SetLocalMapper (LocalMapping *pLocalMapper)
 
void SetTracker (Tracking *pTracker)
 

Protected Member Functions

bool CheckFinish ()
 
bool CheckNewKeyFrames ()
 
bool ComputeSim3 ()
 
void CorrectLoop ()
 
bool DetectLoop ()
 
void ResetIfRequested ()
 
void SearchAndFuse (const KeyFrameAndPose &CorrectedPosesMap)
 
void SetFinish ()
 

Protected Attributes

bool mbFinished
 
bool mbFinishedGBA
 
bool mbFinishRequested
 
bool mbFixScale
 
bool mbResetRequested
 
bool mbRunningGBA
 
bool mbStopGBA
 
g2o::Sim3 mg2oScw
 
long unsigned int mLastLoopKFid
 
std::list< KeyFrame * > mlpLoopKeyFrameQueue
 
std::mutex mMutexFinish
 
std::mutex mMutexGBA
 
std::mutex mMutexLoopQueue
 
std::mutex mMutexReset
 
float mnCovisibilityConsistencyTh
 
bool mnFullBAIdx
 
KeyFramempCurrentKF
 
KeyFrameDatabasempKeyFrameDB
 
LocalMappingmpLocalMapper
 
MapmpMap
 
KeyFramempMatchedKF
 
ORBVocabularympORBVocabulary
 
std::thread * mpThreadGBA
 
TrackingmpTracker
 
cv::Mat mScw
 
std::vector< ConsistentGroupmvConsistentGroups
 
std::vector< KeyFrame * > mvpCurrentConnectedKFs
 
std::vector< MapPoint * > mvpCurrentMatchedPoints
 
std::vector< KeyFrame * > mvpEnoughConsistentCandidates
 
std::vector< MapPoint * > mvpLoopMapPoints
 

Detailed Description

Definition at line 44 of file LoopClosing.h.

Member Typedef Documentation

Definition at line 48 of file LoopClosing.h.

typedef map<KeyFrame*,g2o::Sim3,std::less<KeyFrame*>, Eigen::aligned_allocator<std::pair<KeyFrame* const, g2o::Sim3> > > ORB_SLAM2::LoopClosing::KeyFrameAndPose

Definition at line 50 of file LoopClosing.h.

Constructor & Destructor Documentation

ORB_SLAM2::LoopClosing::LoopClosing ( Map pMap,
KeyFrameDatabase pDB,
ORBVocabulary pVoc,
const bool  bFixScale 
)

Definition at line 38 of file LoopClosing.cc.

Member Function Documentation

bool ORB_SLAM2::LoopClosing::CheckFinish ( )
protected

Definition at line 757 of file LoopClosing.cc.

bool ORB_SLAM2::LoopClosing::CheckNewKeyFrames ( )
protected

Definition at line 97 of file LoopClosing.cc.

bool ORB_SLAM2::LoopClosing::ComputeSim3 ( )
protected

Definition at line 231 of file LoopClosing.cc.

void ORB_SLAM2::LoopClosing::CorrectLoop ( )
protected

Definition at line 402 of file LoopClosing.cc.

bool ORB_SLAM2::LoopClosing::DetectLoop ( )
protected

Definition at line 103 of file LoopClosing.cc.

void ORB_SLAM2::LoopClosing::InsertKeyFrame ( KeyFrame pKF)

Definition at line 90 of file LoopClosing.cc.

bool ORB_SLAM2::LoopClosing::isFinished ( )

Definition at line 769 of file LoopClosing.cc.

bool ORB_SLAM2::LoopClosing::isFinishedGBA ( )
inline

Definition at line 74 of file LoopClosing.h.

bool ORB_SLAM2::LoopClosing::isRunningGBA ( )
inline

Definition at line 70 of file LoopClosing.h.

void ORB_SLAM2::LoopClosing::RequestFinish ( )

Definition at line 751 of file LoopClosing.cc.

void ORB_SLAM2::LoopClosing::RequestReset ( )

Definition at line 616 of file LoopClosing.cc.

void ORB_SLAM2::LoopClosing::ResetIfRequested ( )
protected

Definition at line 634 of file LoopClosing.cc.

void ORB_SLAM2::LoopClosing::Run ( )

Definition at line 57 of file LoopClosing.cc.

void ORB_SLAM2::LoopClosing::RunGlobalBundleAdjustment ( unsigned long  nLoopKF)

Definition at line 645 of file LoopClosing.cc.

void ORB_SLAM2::LoopClosing::SearchAndFuse ( const KeyFrameAndPose CorrectedPosesMap)
protected

Definition at line 587 of file LoopClosing.cc.

void ORB_SLAM2::LoopClosing::SetFinish ( )
protected

Definition at line 763 of file LoopClosing.cc.

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

Definition at line 51 of file LoopClosing.cc.

void ORB_SLAM2::LoopClosing::SetTracker ( Tracking pTracker)

Definition at line 46 of file LoopClosing.cc.

Member Data Documentation

bool ORB_SLAM2::LoopClosing::mbFinished
protected

Definition at line 104 of file LoopClosing.h.

bool ORB_SLAM2::LoopClosing::mbFinishedGBA
protected

Definition at line 137 of file LoopClosing.h.

bool ORB_SLAM2::LoopClosing::mbFinishRequested
protected

Definition at line 103 of file LoopClosing.h.

bool ORB_SLAM2::LoopClosing::mbFixScale
protected

Definition at line 143 of file LoopClosing.h.

bool ORB_SLAM2::LoopClosing::mbResetRequested
protected

Definition at line 98 of file LoopClosing.h.

bool ORB_SLAM2::LoopClosing::mbRunningGBA
protected

Definition at line 136 of file LoopClosing.h.

bool ORB_SLAM2::LoopClosing::mbStopGBA
protected

Definition at line 138 of file LoopClosing.h.

g2o::Sim3 ORB_SLAM2::LoopClosing::mg2oScw
protected

Definition at line 131 of file LoopClosing.h.

long unsigned int ORB_SLAM2::LoopClosing::mLastLoopKFid
protected

Definition at line 133 of file LoopClosing.h.

std::list<KeyFrame*> ORB_SLAM2::LoopClosing::mlpLoopKeyFrameQueue
protected

Definition at line 115 of file LoopClosing.h.

std::mutex ORB_SLAM2::LoopClosing::mMutexFinish
protected

Definition at line 105 of file LoopClosing.h.

std::mutex ORB_SLAM2::LoopClosing::mMutexGBA
protected

Definition at line 139 of file LoopClosing.h.

std::mutex ORB_SLAM2::LoopClosing::mMutexLoopQueue
protected

Definition at line 117 of file LoopClosing.h.

std::mutex ORB_SLAM2::LoopClosing::mMutexReset
protected

Definition at line 99 of file LoopClosing.h.

float ORB_SLAM2::LoopClosing::mnCovisibilityConsistencyTh
protected

Definition at line 120 of file LoopClosing.h.

bool ORB_SLAM2::LoopClosing::mnFullBAIdx
protected

Definition at line 146 of file LoopClosing.h.

KeyFrame* ORB_SLAM2::LoopClosing::mpCurrentKF
protected

Definition at line 123 of file LoopClosing.h.

KeyFrameDatabase* ORB_SLAM2::LoopClosing::mpKeyFrameDB
protected

Definition at line 110 of file LoopClosing.h.

LocalMapping* ORB_SLAM2::LoopClosing::mpLocalMapper
protected

Definition at line 113 of file LoopClosing.h.

Map* ORB_SLAM2::LoopClosing::mpMap
protected

Definition at line 107 of file LoopClosing.h.

KeyFrame* ORB_SLAM2::LoopClosing::mpMatchedKF
protected

Definition at line 124 of file LoopClosing.h.

ORBVocabulary* ORB_SLAM2::LoopClosing::mpORBVocabulary
protected

Definition at line 111 of file LoopClosing.h.

std::thread* ORB_SLAM2::LoopClosing::mpThreadGBA
protected

Definition at line 140 of file LoopClosing.h.

Tracking* ORB_SLAM2::LoopClosing::mpTracker
protected

Definition at line 108 of file LoopClosing.h.

cv::Mat ORB_SLAM2::LoopClosing::mScw
protected

Definition at line 130 of file LoopClosing.h.

std::vector<ConsistentGroup> ORB_SLAM2::LoopClosing::mvConsistentGroups
protected

Definition at line 125 of file LoopClosing.h.

std::vector<KeyFrame*> ORB_SLAM2::LoopClosing::mvpCurrentConnectedKFs
protected

Definition at line 127 of file LoopClosing.h.

std::vector<MapPoint*> ORB_SLAM2::LoopClosing::mvpCurrentMatchedPoints
protected

Definition at line 128 of file LoopClosing.h.

std::vector<KeyFrame*> ORB_SLAM2::LoopClosing::mvpEnoughConsistentCandidates
protected

Definition at line 126 of file LoopClosing.h.

std::vector<MapPoint*> ORB_SLAM2::LoopClosing::mvpLoopMapPoints
protected

Definition at line 129 of file LoopClosing.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