LoopClosing.h
Go to the documentation of this file.
1 
21 #ifndef LOOPCLOSING_H
22 #define LOOPCLOSING_H
23 
24 #include "KeyFrame.h"
25 #include "LocalMapping.h"
26 #include "Map.h"
27 #include "ORBVocabulary.h"
28 #include "Tracking.h"
29 
30 #include "KeyFrameDatabase.h"
31 
32 #include <thread>
33 #include <mutex>
35 
36 namespace ORB_SLAM2
37 {
38 
39 class Tracking;
40 class LocalMapping;
41 class KeyFrameDatabase;
42 
43 
45 {
46 public:
47 
48  typedef pair<set<KeyFrame*>,int> ConsistentGroup;
49  typedef map<KeyFrame*,g2o::Sim3,std::less<KeyFrame*>,
50  Eigen::aligned_allocator<std::pair<KeyFrame* const, g2o::Sim3> > > KeyFrameAndPose;
51 
52 public:
53 
54  LoopClosing(Map* pMap, KeyFrameDatabase* pDB, ORBVocabulary* pVoc,const bool bFixScale);
55 
56  void SetTracker(Tracking* pTracker);
57 
58  void SetLocalMapper(LocalMapping* pLocalMapper);
59 
60  // Main function
61  void Run();
62 
63  void InsertKeyFrame(KeyFrame *pKF);
64 
65  void RequestReset();
66 
67  // This function will run in a separate thread
68  void RunGlobalBundleAdjustment(unsigned long nLoopKF);
69 
70  bool isRunningGBA(){
71  unique_lock<std::mutex> lock(mMutexGBA);
72  return mbRunningGBA;
73  }
74  bool isFinishedGBA(){
75  unique_lock<std::mutex> lock(mMutexGBA);
76  return mbFinishedGBA;
77  }
78 
79  void RequestFinish();
80 
81  bool isFinished();
82 
83  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
84 
85 protected:
86 
87  bool CheckNewKeyFrames();
88 
89  bool DetectLoop();
90 
91  bool ComputeSim3();
92 
93  void SearchAndFuse(const KeyFrameAndPose &CorrectedPosesMap);
94 
95  void CorrectLoop();
96 
97  void ResetIfRequested();
99  std::mutex mMutexReset;
100 
101  bool CheckFinish();
102  void SetFinish();
105  std::mutex mMutexFinish;
106 
109 
112 
114 
115  std::list<KeyFrame*> mlpLoopKeyFrameQueue;
116 
117  std::mutex mMutexLoopQueue;
118 
119  // Loop detector parameters
121 
122  // Loop detector variables
125  std::vector<ConsistentGroup> mvConsistentGroups;
126  std::vector<KeyFrame*> mvpEnoughConsistentCandidates;
127  std::vector<KeyFrame*> mvpCurrentConnectedKFs;
128  std::vector<MapPoint*> mvpCurrentMatchedPoints;
129  std::vector<MapPoint*> mvpLoopMapPoints;
130  cv::Mat mScw;
132 
133  long unsigned int mLastLoopKFid;
134 
135  // Variables related to Global Bundle Adjustment
138  bool mbStopGBA;
139  std::mutex mMutexGBA;
140  std::thread* mpThreadGBA;
141 
142  // Fix scale in the stereo/RGB-D case
144 
145 
147 };
148 
149 } //namespace ORB_SLAM
150 
151 #endif // LOOPCLOSING_H
Definition: sim3.h:41
map< KeyFrame *, g2o::Sim3, std::less< KeyFrame * >, Eigen::aligned_allocator< std::pair< KeyFrame *const, g2o::Sim3 > > > KeyFrameAndPose
Definition: LoopClosing.h:50
std::vector< KeyFrame * > mvpCurrentConnectedKFs
Definition: LoopClosing.h:127
LoopClosing(Map *pMap, KeyFrameDatabase *pDB, ORBVocabulary *pVoc, const bool bFixScale)
Definition: LoopClosing.cc:38
void InsertKeyFrame(KeyFrame *pKF)
Definition: LoopClosing.cc:90
ORBVocabulary * mpORBVocabulary
Definition: LoopClosing.h:111
LocalMapping * mpLocalMapper
Definition: LoopClosing.h:113
void SearchAndFuse(const KeyFrameAndPose &CorrectedPosesMap)
Definition: LoopClosing.cc:587
void SetLocalMapper(LocalMapping *pLocalMapper)
Definition: LoopClosing.cc:51
KeyFrameDatabase * mpKeyFrameDB
Definition: LoopClosing.h:110
long unsigned int mLastLoopKFid
Definition: LoopClosing.h:133
pair< set< KeyFrame * >, int > ConsistentGroup
Definition: LoopClosing.h:48
std::vector< KeyFrame * > mvpEnoughConsistentCandidates
Definition: LoopClosing.h:126
void SetTracker(Tracking *pTracker)
Definition: LoopClosing.cc:46
void RunGlobalBundleAdjustment(unsigned long nLoopKF)
Definition: LoopClosing.cc:645
std::list< KeyFrame * > mlpLoopKeyFrameQueue
Definition: LoopClosing.h:115
std::mutex mMutexLoopQueue
Definition: LoopClosing.h:117
std::mutex mMutexReset
Definition: LoopClosing.h:99
std::vector< MapPoint * > mvpLoopMapPoints
Definition: LoopClosing.h:129
std::thread * mpThreadGBA
Definition: LoopClosing.h:140
std::vector< MapPoint * > mvpCurrentMatchedPoints
Definition: LoopClosing.h:128
std::vector< ConsistentGroup > mvConsistentGroups
Definition: LoopClosing.h:125


orb_slam2_ros
Author(s):
autogenerated on Wed Apr 21 2021 02:53:05