forked from Ewenwan/ORB_SLAM2_SSD_Semantic
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathLocalMapping.h
141 lines (100 loc) · 3.48 KB
/
LocalMapping.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
/**
* This file is part of ORB-SLAM2.
* 局部建图
* LocalMapping作用是将Tracking中送来的关键帧放在mlNewKeyFrame列表中;
* 处理新关键帧,地图点检查剔除,生成新地图点,Local BA,关键帧剔除。
* 主要工作在于维护局部地图,也就是SLAM中的Mapping。
*
* Tracking线程 只是判断当前帧是否需要加入关键帧,并没有真的加入地图,
* 因为Tracking线程的主要功能是局部定位,
*
* 而处理地图中的关键帧,地图点,包括如何加入,
* 如何删除的工作是在LocalMapping线程完成的
*
*/
#ifndef LOCALMAPPING_H
#define LOCALMAPPING_H
#include "KeyFrame.h"
#include "Map.h"
#include "LoopClosing.h"
#include "Tracking.h"
#include "KeyFrameDatabase.h"
#include <mutex>
namespace ORB_SLAM2
{
class Tracking;
class LoopClosing;
class Map;
class LocalMapping
{
public:
LocalMapping(Map* pMap, const float bMonocular);
void SetLoopCloser(LoopClosing* pLoopCloser);
void SetTracker(Tracking* pTracker);
// Main function
void Run();
void InsertKeyFrame(KeyFrame* pKF);
// Thread Synch
void RequestStop();
void RequestReset();
bool Stop();
void Release();
bool isStopped();
bool stopRequested();
bool AcceptKeyFrames();
void SetAcceptKeyFrames(bool flag);
bool SetNotStop(bool flag);
void InterruptBA();
void RequestFinish();
bool isFinished();
int KeyframesInQueue(){
unique_lock<std::mutex> lock(mMutexNewKFs);
return mlNewKeyFrames.size();
}
protected:
bool CheckNewKeyFrames();
// 处理新关键帧:ProcessNewKeyFrame()
/*a. 根据词典 计算当前关键帧Bow,便于后面三角化恢复新地图点;
b. 将TrackLocalMap中跟踪局部地图匹配上的地图点绑定到当前关键帧
(在Tracking线程中只是通过匹配进行局部地图跟踪,优化当前关键帧姿态),
也就是在graph 中加入当前关键帧作为node,并更新edge。
而CreateNewMapPoint()中则通过当前关键帧,在局部地图中添加与新的地图点;
c. 更新加入当前关键帧之后关键帧之间的连接关系,包括更新Covisibility图和Essential图
(最小生成树spanning tree,共视关系好的边subset of edges from covisibility graph
with high covisibility (θ=100), 闭环边)。
*/
void ProcessNewKeyFrame();
// 而CreateNewMapPoint()中则通过当前关键帧,在局部地图中添加与新的地图点;
void CreateNewMapPoints();
// 对于ProcessNewKeyFrame和CreateNewMapPoints中最近添加的MapPoints进行检查剔除
void MapPointCulling();
void SearchInNeighbors();
void KeyFrameCulling();
cv::Mat ComputeF12(KeyFrame* &pKF1, KeyFrame* &pKF2);
cv::Mat SkewSymmetricMatrix(const cv::Mat &v);
bool mbMonocular;
void ResetIfRequested();
bool mbResetRequested;
std::mutex mMutexReset;
bool CheckFinish();
void SetFinish();
bool mbFinishRequested;
bool mbFinished;
std::mutex mMutexFinish;
Map* mpMap;
LoopClosing* mpLoopCloser;
Tracking* mpTracker;
std::list<KeyFrame*> mlNewKeyFrames;
KeyFrame* mpCurrentKeyFrame;
std::list<MapPoint*> mlpRecentAddedMapPoints;
std::mutex mMutexNewKFs;
bool mbAbortBA;
bool mbStopped;
bool mbStopRequested;
bool mbNotStop;
std::mutex mMutexStop;
bool mbAcceptKeyFrames;
std::mutex mMutexAccept;
};
} //namespace ORB_SLAM
#endif // LOCALMAPPING_H