forked from xiaoxifuhongse/ORB-SLAM-RGBD-with-Octomap
-
Notifications
You must be signed in to change notification settings - Fork 16
/
LoopClosing.h
146 lines (106 loc) · 3.46 KB
/
LoopClosing.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
142
143
144
145
146
/**
* 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 LOOPCLOSING_H
#define LOOPCLOSING_H
#include "KeyFrame.h"
#include "LocalMapping.h"
#include "Map.h"
#include "ORBVocabulary.h"
#include "Tracking.h"
#include "KeyFrameDatabase.h"
#include <thread>
#include <mutex>
#include "Thirdparty/g2o/g2o/types/types_seven_dof_expmap.h"
namespace ORB_SLAM2
{
class Tracking;
class LocalMapping;
class KeyFrameDatabase;
class LoopClosing
{
public:
typedef pair<set<KeyFrame*>,int> ConsistentGroup;
typedef map<KeyFrame*,g2o::Sim3,std::less<KeyFrame*>,
Eigen::aligned_allocator<std::pair<const KeyFrame*, g2o::Sim3> > > KeyFrameAndPose;
public:
LoopClosing(Map* pMap, KeyFrameDatabase* pDB, ORBVocabulary* pVoc,const bool bFixScale);
void SetTracker(Tracking* pTracker);
void SetLocalMapper(LocalMapping* pLocalMapper);
// Main function
void Run();
void InsertKeyFrame(KeyFrame *pKF);
void RequestReset();
// This function will run in a separate thread
void RunGlobalBundleAdjustment(unsigned long nLoopKF);
bool isRunningGBA(){
unique_lock<std::mutex> lock(mMutexGBA);
return mbRunningGBA;
}
bool isFinishedGBA(){
unique_lock<std::mutex> lock(mMutexGBA);
return mbFinishedGBA;
}
void RequestFinish();
bool isFinished();
protected:
bool CheckNewKeyFrames();
bool DetectLoop();
bool ComputeSim3();
void SearchAndFuse(const KeyFrameAndPose &CorrectedPosesMap);
void CorrectLoop();
void ResetIfRequested();
bool mbResetRequested;
std::mutex mMutexReset;
bool CheckFinish();
void SetFinish();
bool mbFinishRequested;
bool mbFinished;
std::mutex mMutexFinish;
Map* mpMap;
Tracking* mpTracker;
KeyFrameDatabase* mpKeyFrameDB;
ORBVocabulary* mpORBVocabulary;
LocalMapping *mpLocalMapper;
std::list<KeyFrame*> mlpLoopKeyFrameQueue;
std::mutex mMutexLoopQueue;
// Loop detector parameters
float mnCovisibilityConsistencyTh;
// Loop detector variables
KeyFrame* mpCurrentKF;
KeyFrame* mpMatchedKF;
std::vector<ConsistentGroup> mvConsistentGroups;
std::vector<KeyFrame*> mvpEnoughConsistentCandidates;
std::vector<KeyFrame*> mvpCurrentConnectedKFs;
std::vector<MapPoint*> mvpCurrentMatchedPoints;
std::vector<MapPoint*> mvpLoopMapPoints;
cv::Mat mScw;
g2o::Sim3 mg2oScw;
long unsigned int mLastLoopKFid;
// Variables related to Global Bundle Adjustment
bool mbRunningGBA;
bool mbFinishedGBA;
bool mbStopGBA;
std::mutex mMutexGBA;
std::thread* mpThreadGBA;
// Fix scale in the stereo/RGB-D case
bool mbFixScale;
};
} //namespace ORB_SLAM
#endif // LOOPCLOSING_H