ORB SLA2
Tracking.h
1 
22 #ifndef TRACKING_H
23 #define TRACKING_H
24 
25 #include<opencv2/core/core.hpp>
26 #include<opencv2/features2d/features2d.hpp>
27 
28 #include"Viewer.h"
29 #include"FrameDrawer.h"
30 #include"Map.h"
31 #include"LocalMapping.h"
32 #include"LoopClosing.h"
33 #include"Frame.h"
34 #include "ORBVocabulary.h"
35 #include"KeyFrameDatabase.h"
36 #include"ORBextractor.h"
37 #include "Initializer.h"
38 #include "MapDrawer.h"
39 #include "System.h"
40 
41 #include <mutex>
42 
43 namespace ORB_SLAM2
44 {
45 
46 class Viewer;
47 class FrameDrawer;
48 class Map;
49 class LocalMapping;
50 class LoopClosing;
51 class System;
52 
53 class Tracking
54 {
55 
56 public:
57  Tracking(System* pSys, ORBVocabulary* pVoc, FrameDrawer* pFrameDrawer, MapDrawer* pMapDrawer, Map* pMap,
58  KeyFrameDatabase* pKFDB, const string &strSettingPath, const int sensor);
59 
60  // Preprocess the input and call Track(). Extract features and performs stereo matching.
61  cv::Mat GrabImageStereo(const cv::Mat &imRectLeft,const cv::Mat &imRectRight, const double &timestamp);
62  cv::Mat GrabImageRGBD(const cv::Mat &imRGB,const cv::Mat &imD, const double &timestamp);
63  cv::Mat GrabImageMonocular(const cv::Mat &im, const double &timestamp);
64 
65  void SetLocalMapper(LocalMapping* pLocalMapper);
66  void SetLoopClosing(LoopClosing* pLoopClosing);
67  void SetViewer(Viewer* pViewer);
68 
69  // Load new settings
70  // The focal lenght should be similar or scale prediction will fail when projecting points
71  // TODO: Modify MapPoint::PredictScale to take into account focal lenght
72  void ChangeCalibration(const string &strSettingPath);
73 
74  // Use this function if you have deactivated local mapping and you only want to localize the camera.
75  void InformOnlyTracking(const bool &flag);
76 
77 
78 public:
79 
80  // Tracking states
81  enum eTrackingState{
82  SYSTEM_NOT_READY=-1,
83  NO_IMAGES_YET=0,
84  NOT_INITIALIZED=1,
85  OK=2,
86  LOST=3
87  };
88 
89  eTrackingState mState;
90  eTrackingState mLastProcessedState;
91 
92  // Input sensor
93  int mSensor;
94 
95  // Current Frame
96  Frame mCurrentFrame;
97  cv::Mat mImGray;
98 
99  // Initialization Variables (Monocular)
100  std::vector<int> mvIniLastMatches;
101  std::vector<int> mvIniMatches;
102  std::vector<cv::Point2f> mvbPrevMatched;
103  std::vector<cv::Point3f> mvIniP3D;
104  Frame mInitialFrame;
105 
106  // Lists used to recover the full camera trajectory at the end of the execution.
107  // Basically we store the reference keyframe for each frame and its relative transformation
108  list<cv::Mat> mlRelativeFramePoses;
109  list<KeyFrame*> mlpReferences;
110  list<double> mlFrameTimes;
111  list<bool> mlbLost;
112 
113  // True if local mapping is deactivated and we are performing only localization
114  bool mbOnlyTracking;
115 
116  void Reset();
117 
118 protected:
119 
120  // Main tracking function. It is independent of the input sensor.
121  void Track();
122 
123  // Map initialization for stereo and RGB-D
124  void StereoInitialization();
125 
126  // Map initialization for monocular
127  void MonocularInitialization();
128  void CreateInitialMapMonocular();
129 
130  void CheckReplacedInLastFrame();
131  bool TrackReferenceKeyFrame();
132  void UpdateLastFrame();
133  bool TrackWithMotionModel();
134 
135  bool Relocalization();
136 
137  void UpdateLocalMap();
138  void UpdateLocalPoints();
139  void UpdateLocalKeyFrames();
140 
141  bool TrackLocalMap();
142  void SearchLocalPoints();
143 
144  bool NeedNewKeyFrame();
145  void CreateNewKeyFrame();
146 
147  // In case of performing only localization, this flag is true when there are no matches to
148  // points in the map. Still tracking will continue if there are enough matches with temporal points.
149  // In that case we are doing visual odometry. The system will try to do relocalization to recover
150  // "zero-drift" localization to the map.
151  bool mbVO;
152 
153  //Other Thread Pointers
154  LocalMapping* mpLocalMapper;
155  LoopClosing* mpLoopClosing;
156 
157  //ORB
158  ORBextractor* mpORBextractorLeft, *mpORBextractorRight;
159  ORBextractor* mpIniORBextractor;
160 
161  //BoW
162  ORBVocabulary* mpORBVocabulary;
163  KeyFrameDatabase* mpKeyFrameDB;
164 
165  // Initalization (only for monocular)
166  Initializer* mpInitializer;
167 
168  //Local Map
169  KeyFrame* mpReferenceKF;
170  std::vector<KeyFrame*> mvpLocalKeyFrames;
171  std::vector<MapPoint*> mvpLocalMapPoints;
172 
173  // System
174  System* mpSystem;
175 
176  //Drawers
177  Viewer* mpViewer;
178  FrameDrawer* mpFrameDrawer;
179  MapDrawer* mpMapDrawer;
180 
181  //Map
182  Map* mpMap;
183 
184  //Calibration matrix
185  cv::Mat mK;
186  cv::Mat mDistCoef;
187  float mbf;
188 
189  //New KeyFrame rules (according to fps)
190  int mMinFrames;
191  int mMaxFrames;
192 
193  // Threshold close/far points
194  // Points seen as close by the stereo/RGBD sensor are considered reliable
195  // and inserted from just one frame. Far points requiere a match in two keyframes.
196  float mThDepth;
197 
198  // For RGB-D inputs only. For some datasets (e.g. TUM) the depthmap values are scaled.
199  float mDepthMapFactor;
200 
201  //Current matches in frame
202  int mnMatchesInliers;
203 
204  //Last Frame, KeyFrame and Relocalisation Info
205  KeyFrame* mpLastKeyFrame;
206  Frame mLastFrame;
207  unsigned int mnLastKeyFrameId;
208  unsigned int mnLastRelocFrameId;
209 
210  //Motion Model
211  cv::Mat mVelocity;
212 
213  //Color order (true RGB, false BGR, ignored if grayscale)
214  bool mbRGB;
215 
216  list<MapPoint*> mlpTemporalPoints;
217 };
218 
219 } //namespace ORB_SLAM
220 
221 #endif // TRACKING_H
Definition: ORBextractor.h:45
Definition: Tracking.h:53
Definition: Viewer.h:40
Definition: KeyFrame.h:43
Definition: LoopClosing.h:44
Definition: KeyFrameDatabase.h:42
Definition: Frame.h:43
Definition: Converter.cpp:24
Definition: MapDrawer.h:34
Definition: Initializer.h:31
Definition: FrameDrawer.h:40
Definition: System.h:49
Definition: Map.h:38
Definition: LocalMapping.h:40