forked from raulmur/ORB_SLAM
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Tracking.h
187 lines (140 loc) · 4.34 KB
/
Tracking.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
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
/**
* 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 TRACKING_H
#define TRACKING_H
#include<opencv2/core/core.hpp>
#include<opencv2/features2d/features2d.hpp>
#include<sensor_msgs/Image.h>
#include<sensor_msgs/image_encodings.h>
#include"FramePublisher.h"
#include"Map.h"
#include"LocalMapping.h"
#include"LoopClosing.h"
#include"Frame.h"
#include "ORBVocabulary.h"
#include"KeyFrameDatabase.h"
#include"ORBextractor.h"
#include "Initializer.h"
#include "MapPublisher.h"
#include<tf/transform_broadcaster.h>
namespace ORB_SLAM
{
class FramePublisher;
class Map;
class LocalMapping;
class LoopClosing;
class Tracking
{
public:
Tracking(ORBVocabulary* pVoc, FramePublisher* pFramePublisher, MapPublisher* pMapPublisher, Map* pMap, string strSettingPath);
enum eTrackingState{
SYSTEM_NOT_READY=-1,
NO_IMAGES_YET=0,
NOT_INITIALIZED=1,
INITIALIZING=2,
WORKING=3,
LOST=4
};
void SetLocalMapper(LocalMapping* pLocalMapper);
void SetLoopClosing(LoopClosing* pLoopClosing);
void SetKeyFrameDatabase(KeyFrameDatabase* pKFDB);
// This is the main function of the Tracking Thread
void Run();
void ForceRelocalisation();
eTrackingState mState;
eTrackingState mLastProcessedState;
// Current Frame
Frame mCurrentFrame;
// Initialization Variables
std::vector<int> mvIniLastMatches;
std::vector<int> mvIniMatches;
std::vector<cv::Point2f> mvbPrevMatched;
std::vector<cv::Point3f> mvIniP3D;
Frame mInitialFrame;
void CheckResetByPublishers();
protected:
void GrabImage(const sensor_msgs::ImageConstPtr& msg);
void FirstInitialization();
void Initialize();
void CreateInitialMap(cv::Mat &Rcw, cv::Mat &tcw);
void Reset();
bool TrackPreviousFrame();
bool TrackWithMotionModel();
bool RelocalisationRequested();
bool Relocalisation();
void UpdateReference();
void UpdateReferencePoints();
void UpdateReferenceKeyFrames();
bool TrackLocalMap();
void SearchReferencePointsInFrustum();
bool NeedNewKeyFrame();
void CreateNewKeyFrame();
//Other Thread Pointers
LocalMapping* mpLocalMapper;
LoopClosing* mpLoopClosing;
//ORB
ORBextractor* mpORBextractor;
ORBextractor* mpIniORBextractor;
//BoW
ORBVocabulary* mpORBVocabulary;
KeyFrameDatabase* mpKeyFrameDB;
// Initalization
Initializer* mpInitializer;
//Local Map
KeyFrame* mpReferenceKF;
std::vector<KeyFrame*> mvpLocalKeyFrames;
std::vector<MapPoint*> mvpLocalMapPoints;
//Publishers
FramePublisher* mpFramePublisher;
MapPublisher* mpMapPublisher;
//Map
Map* mpMap;
//Calibration matrix
cv::Mat mK;
cv::Mat mDistCoef;
//New KeyFrame rules (according to fps)
int mMinFrames;
int mMaxFrames;
//Current matches in frame
int mnMatchesInliers;
//Last Frame, KeyFrame and Relocalisation Info
KeyFrame* mpLastKeyFrame;
Frame mLastFrame;
unsigned int mnLastKeyFrameId;
unsigned int mnLastRelocFrameId;
//Mutex
boost::mutex mMutexTrack;
boost::mutex mMutexForceRelocalisation;
//Reset
bool mbPublisherStopped;
bool mbReseting;
boost::mutex mMutexReset;
//Is relocalisation requested by an external thread? (loop closing)
bool mbForceRelocalisation;
//Motion Model
bool mbMotionModel;
cv::Mat mVelocity;
//Color order (true RGB, false BGR, ignored if grayscale)
bool mbRGB;
// Transfor broadcaster (for visualization in rviz)
tf::TransformBroadcaster mTfBr;
};
} //namespace ORB_SLAM
#endif // TRACKING_H