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


orb_slam2_with_maps_odom
Author(s): teng zhang
autogenerated on Fri Sep 25 2020 03:24:47