forked from Fernweh-yang/SLAM_Code_Learning
-
Notifications
You must be signed in to change notification settings - Fork 0
/
LocalMapping.h
128 lines (93 loc) · 2.72 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
/**
* This file is part of ORB-SLAM2.
*
* Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza)
* For more information see <https://github.com/raulmur/ORB_SLAM2>
*
* ORB-SLAM2 is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* ORB-SLAM2 is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with ORB-SLAM2. If not, see <http://www.gnu.org/licenses/>.
*/
#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();
void ProcessNewKeyFrame();
void CreateNewMapPoints();
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