ORB SLA2
LocalMapping.h
1 
21 #ifndef LOCALMAPPING_H
22 #define LOCALMAPPING_H
23 
24 #include "KeyFrame.h"
25 #include "Map.h"
26 #include "LoopClosing.h"
27 #include "Tracking.h"
28 #include "KeyFrameDatabase.h"
29 
30 #include <mutex>
31 
32 
33 namespace ORB_SLAM2
34 {
35 
36 class Tracking;
37 class LoopClosing;
38 class Map;
39 
41 {
42 public:
43  LocalMapping(Map* pMap, const float bMonocular);
44 
45  void SetLoopCloser(LoopClosing* pLoopCloser);
46 
47  void SetTracker(Tracking* pTracker);
48 
49  // Main function
50  void Run();
51 
52  void InsertKeyFrame(KeyFrame* pKF);
53 
54  // Thread Synch
55  void RequestStop();
56  void RequestReset();
57  bool Stop();
58  void Release();
59  bool isStopped();
60  bool stopRequested();
61  bool AcceptKeyFrames();
62  void SetAcceptKeyFrames(bool flag);
63  bool SetNotStop(bool flag);
64 
65  void InterruptBA();
66 
67  void RequestFinish();
68  bool isFinished();
69 
70  int KeyframesInQueue(){
71  unique_lock<std::mutex> lock(mMutexNewKFs);
72  return mlNewKeyFrames.size();
73  }
74 
75 protected:
76 
77  bool CheckNewKeyFrames();
78  void ProcessNewKeyFrame();
79  void CreateNewMapPoints();
80 
81  void MapPointCulling();
82  void SearchInNeighbors();
83 
84  void KeyFrameCulling();
85 
86  cv::Mat ComputeF12(KeyFrame* &pKF1, KeyFrame* &pKF2);
87 
88  cv::Mat SkewSymmetricMatrix(const cv::Mat &v);
89 
90  bool mbMonocular;
91 
92  void ResetIfRequested();
93  bool mbResetRequested;
94  std::mutex mMutexReset;
95 
96  bool CheckFinish();
97  void SetFinish();
98  bool mbFinishRequested;
99  bool mbFinished;
100  std::mutex mMutexFinish;
101 
102  Map* mpMap;
103 
104  LoopClosing* mpLoopCloser;
105  Tracking* mpTracker;
106 
107  std::list<KeyFrame*> mlNewKeyFrames;
108 
109  KeyFrame* mpCurrentKeyFrame;
110 
111  std::list<MapPoint*> mlpRecentAddedMapPoints;
112 
113  std::mutex mMutexNewKFs;
114 
115  bool mbAbortBA;
116 
117  bool mbStopped;
118  bool mbStopRequested;
119  bool mbNotStop;
120  std::mutex mMutexStop;
121 
122  bool mbAcceptKeyFrames;
123  std::mutex mMutexAccept;
124 };
125 
126 } //namespace ORB_SLAM
127 
128 #endif // LOCALMAPPING_H
Definition: Tracking.h:53
Definition: KeyFrame.h:43
Definition: LoopClosing.h:44
Definition: Converter.cpp:24
Definition: Map.h:38
Definition: LocalMapping.h:40