forked from JzHuai0108/ORB_SLAM
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathLocalMapping.h
110 lines (77 loc) · 2.26 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
/**
* This file is part of ORB-SLAM.
*
* Copyright (C) 2014 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza)
* For more information see <http://webdiis.unizar.es/~raulmur/orbslam/>
*
* ORB-SLAM 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-SLAM 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-SLAM. 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 <boost/thread.hpp>
#include "KeyFrameDatabase.h"
namespace ORB_SLAM
{
class Tracking;
class LoopClosing;
class Map;
class LocalMapping
{
public:
LocalMapping(Map* pMap);
void SetLoopCloser(LoopClosing* pLoopCloser);
void SetTracker(Tracking* pTracker);
void Run();
void InsertKeyFrame(KeyFrame* pKF);
// Thread Synch
void RequestStop();
void RequestReset();
void Stop();
void Release();
bool isStopped();
bool stopRequested();
bool AcceptKeyFrames();
void SetAcceptKeyFrames(bool flag);
void InterruptBA();
void ProcessNewKeyFrame();
protected:
bool CheckNewKeyFrames();
void CreateNewMapPoints();
void CreateNewMapPointsStereo();
void MapPointCulling();
void SearchInNeighbors();
void KeyFrameCulling();
void ResetIfRequested();
bool mbResetRequested;
boost::mutex mMutexReset;
Map* mpMap;
LoopClosing* mpLoopCloser;
Tracking* mpTracker;
std::list<KeyFrame*> mlNewKeyFrames;
KeyFrame* mpCurrentKeyFrame;
std::list<MapPoint*> mlpRecentAddedMapPoints;
boost::mutex mMutexNewKFs;
bool mbAbortBA;
bool mbStopped;
bool mbStopRequested;
boost::mutex mMutexStop;
bool mbAcceptKeyFrames;
boost::mutex mMutexAccept;
};
} //namespace ORB_SLAM
#endif // LOCALMAPPING_H