#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 |
KeyFrame * | mpCurrentKF |
KeyFrameDatabase * | mpKeyFrameDB |
LocalMapping * | mpLocalMapper |
Map * | mpMap |
KeyFrame * | mpMatchedKF |
ORBVocabulary * | mpORBVocabulary |
std::thread * | mpThreadGBA |
Tracking * | mpTracker |
cv::Mat | mScw |
std::vector< ConsistentGroup > | mvConsistentGroups |
std::vector< KeyFrame * > | mvpCurrentConnectedKFs |
std::vector< MapPoint * > | mvpCurrentMatchedPoints |
std::vector< KeyFrame * > | mvpEnoughConsistentCandidates |
std::vector< MapPoint * > | mvpLoopMapPoints |
Definition at line 44 of file LoopClosing.h.
typedef pair<set<KeyFrame*>,int> ORB_SLAM2::LoopClosing::ConsistentGroup |
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.
ORB_SLAM2::LoopClosing::LoopClosing | ( | Map * | pMap, |
KeyFrameDatabase * | pDB, | ||
ORBVocabulary * | pVoc, | ||
const bool | bFixScale | ||
) |
Definition at line 38 of file LoopClosing.cc.
|
protected |
Definition at line 757 of file LoopClosing.cc.
|
protected |
Definition at line 97 of file LoopClosing.cc.
|
protected |
Definition at line 231 of file LoopClosing.cc.
|
protected |
Definition at line 402 of file LoopClosing.cc.
|
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.
|
inline |
Definition at line 74 of file LoopClosing.h.
|
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.
|
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.
|
protected |
Definition at line 587 of file LoopClosing.cc.
|
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.
|
protected |
Definition at line 104 of file LoopClosing.h.
|
protected |
Definition at line 137 of file LoopClosing.h.
|
protected |
Definition at line 103 of file LoopClosing.h.
|
protected |
Definition at line 143 of file LoopClosing.h.
|
protected |
Definition at line 98 of file LoopClosing.h.
|
protected |
Definition at line 136 of file LoopClosing.h.
|
protected |
Definition at line 138 of file LoopClosing.h.
|
protected |
Definition at line 131 of file LoopClosing.h.
|
protected |
Definition at line 133 of file LoopClosing.h.
|
protected |
Definition at line 115 of file LoopClosing.h.
|
protected |
Definition at line 105 of file LoopClosing.h.
|
protected |
Definition at line 139 of file LoopClosing.h.
|
protected |
Definition at line 117 of file LoopClosing.h.
|
protected |
Definition at line 99 of file LoopClosing.h.
|
protected |
Definition at line 120 of file LoopClosing.h.
|
protected |
Definition at line 146 of file LoopClosing.h.
|
protected |
Definition at line 123 of file LoopClosing.h.
|
protected |
Definition at line 110 of file LoopClosing.h.
|
protected |
Definition at line 113 of file LoopClosing.h.
|
protected |
Definition at line 107 of file LoopClosing.h.
|
protected |
Definition at line 124 of file LoopClosing.h.
|
protected |
Definition at line 111 of file LoopClosing.h.
|
protected |
Definition at line 140 of file LoopClosing.h.
|
protected |
Definition at line 108 of file LoopClosing.h.
|
protected |
Definition at line 130 of file LoopClosing.h.
|
protected |
Definition at line 125 of file LoopClosing.h.
|
protected |
Definition at line 127 of file LoopClosing.h.
|
protected |
Definition at line 128 of file LoopClosing.h.
|
protected |
Definition at line 126 of file LoopClosing.h.
|
protected |
Definition at line 129 of file LoopClosing.h.