Tracking.h 8.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331
  1. /**
  2. * This file is part of ORB-SLAM3
  3. *
  4. * Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  5. * Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  6. *
  7. * ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public
  8. * License as published by the Free Software Foundation, either version 3 of the License, or
  9. * (at your option) any later version.
  10. *
  11. * ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even
  12. * the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  13. * GNU General Public License for more details.
  14. *
  15. * You should have received a copy of the GNU General Public License along with ORB-SLAM3.
  16. * If not, see <http://www.gnu.org/licenses/>.
  17. */
  18. #ifndef TRACKING_H
  19. #define TRACKING_H
  20. #include<opencv2/core/core.hpp>
  21. #include<opencv2/features2d/features2d.hpp>
  22. #include <opencv2/video/tracking.hpp>
  23. #include"Viewer.h"
  24. #include"FrameDrawer.h"
  25. #include"Atlas.h"
  26. #include"LocalMapping.h"
  27. #include"LoopClosing.h"
  28. #include"Frame.h"
  29. #include "ORBVocabulary.h"
  30. #include"KeyFrameDatabase.h"
  31. #include"ORBextractor.h"
  32. #include "Initializer.h"
  33. #include "MapDrawer.h"
  34. #include "System.h"
  35. #include "ImuTypes.h"
  36. #include "GeometricCamera.h"
  37. #include <mutex>
  38. #include <unordered_set>
  39. namespace ORB_SLAM3
  40. {
  41. class Viewer;
  42. class FrameDrawer;
  43. class Atlas;
  44. class LocalMapping;
  45. class LoopClosing;
  46. class System;
  47. class Tracking
  48. {
  49. public:
  50. Tracking(System* pSys, ORBVocabulary* pVoc, FrameDrawer* pFrameDrawer, MapDrawer* pMapDrawer, Atlas* pAtlas,
  51. KeyFrameDatabase* pKFDB, const string &strSettingPath, const int sensor, const string &_nameSeq=std::string());
  52. ~Tracking();
  53. // Preprocess the input and call Track(). Extract features and performs stereo matching.
  54. cv::Mat GrabImageStereo(const cv::Mat &imRectLeft,const cv::Mat &imRectRight, const double &timestamp, string filename);
  55. cv::Mat GrabImageRGBD(const cv::Mat &imRGB,const cv::Mat &imD, const double &timestamp, string filename);
  56. cv::Mat GrabImageMonocular(const cv::Mat &im, const double &timestamp, string filename);
  57. // cv::Mat GrabImageImuMonocular(const cv::Mat &im, const double &timestamp);
  58. void GrabImuData(const IMU::Point &imuMeasurement);
  59. void SetLocalMapper(LocalMapping* pLocalMapper);
  60. void SetLoopClosing(LoopClosing* pLoopClosing);
  61. void SetViewer(Viewer* pViewer);
  62. void SetStepByStep(bool bSet);
  63. // Load new settings
  64. // The focal lenght should be similar or scale prediction will fail when projecting points
  65. void ChangeCalibration(const string &strSettingPath);
  66. // Use this function if you have deactivated local mapping and you only want to localize the camera.
  67. void InformOnlyTracking(const bool &flag);
  68. void UpdateFrameIMU(const float s, const IMU::Bias &b, KeyFrame* pCurrentKeyFrame);
  69. KeyFrame* GetLastKeyFrame()
  70. {
  71. return mpLastKeyFrame;
  72. }
  73. void CreateMapInAtlas();
  74. std::mutex mMutexTracks;
  75. //--
  76. void NewDataset();
  77. int GetNumberDataset();
  78. int GetMatchesInliers();
  79. public:
  80. // Tracking states
  81. enum eTrackingState{
  82. SYSTEM_NOT_READY=-1,
  83. NO_IMAGES_YET=0,
  84. NOT_INITIALIZED=1,
  85. OK=2,
  86. RECENTLY_LOST=3,
  87. LOST=4,
  88. OK_KLT=5
  89. };
  90. eTrackingState mState;
  91. eTrackingState mLastProcessedState;
  92. // Input sensor
  93. int mSensor;
  94. // Current Frame
  95. Frame mCurrentFrame;
  96. Frame mLastFrame;
  97. cv::Mat mImGray;
  98. // Initialization Variables (Monocular)
  99. std::vector<int> mvIniLastMatches;
  100. std::vector<int> mvIniMatches;
  101. std::vector<cv::Point2f> mvbPrevMatched;
  102. std::vector<cv::Point3f> mvIniP3D;
  103. Frame mInitialFrame;
  104. // Lists used to recover the full camera trajectory at the end of the execution.
  105. // Basically we store the reference keyframe for each frame and its relative transformation
  106. list<cv::Mat> mlRelativeFramePoses;
  107. list<KeyFrame*> mlpReferences;
  108. list<double> mlFrameTimes;
  109. list<bool> mlbLost;
  110. // frames with estimated pose
  111. int mTrackedFr;
  112. bool mbStep;
  113. // True if local mapping is deactivated and we are performing only localization
  114. bool mbOnlyTracking;
  115. void Reset(bool bLocMap = false);
  116. void ResetActiveMap(bool bLocMap = false);
  117. float mMeanTrack;
  118. bool mbInitWith3KFs;
  119. double t0; // time-stamp of first read frame
  120. double t0vis; // time-stamp of first inserted keyframe
  121. double t0IMU; // time-stamp of IMU initialization
  122. vector<MapPoint*> GetLocalMapMPS();
  123. //TEST--
  124. cv::Mat M1l, M2l;
  125. cv::Mat M1r, M2r;
  126. bool mbWriteStats;
  127. protected:
  128. // Main tracking function. It is independent of the input sensor.
  129. void Track();
  130. // Map initialization for stereo and RGB-D
  131. void StereoInitialization();
  132. // Map initialization for monocular
  133. void MonocularInitialization();
  134. void CreateNewMapPoints();
  135. cv::Mat ComputeF12(KeyFrame *&pKF1, KeyFrame *&pKF2);
  136. void CreateInitialMapMonocular();
  137. void CheckReplacedInLastFrame();
  138. bool TrackReferenceKeyFrame();
  139. void UpdateLastFrame();
  140. bool TrackWithMotionModel();
  141. bool PredictStateIMU();
  142. bool Relocalization();
  143. void UpdateLocalMap();
  144. void UpdateLocalPoints();
  145. void UpdateLocalKeyFrames();
  146. bool TrackLocalMap();
  147. bool TrackLocalMap_old();
  148. void SearchLocalPoints();
  149. bool NeedNewKeyFrame();
  150. void CreateNewKeyFrame();
  151. // Perform preintegration from last frame
  152. void PreintegrateIMU();
  153. // Reset IMU biases and compute frame velocity
  154. void ResetFrameIMU();
  155. void ComputeGyroBias(const vector<Frame*> &vpFs, float &bwx, float &bwy, float &bwz);
  156. void ComputeVelocitiesAccBias(const vector<Frame*> &vpFs, float &bax, float &bay, float &baz);
  157. bool mbMapUpdated;
  158. // Imu preintegration from last frame
  159. IMU::Preintegrated *mpImuPreintegratedFromLastKF;
  160. // Queue of IMU measurements between frames
  161. std::list<IMU::Point> mlQueueImuData;
  162. // Vector of IMU measurements from previous to current frame (to be filled by PreintegrateIMU)
  163. std::vector<IMU::Point> mvImuFromLastFrame;
  164. std::mutex mMutexImuQueue;
  165. // Imu calibration parameters
  166. IMU::Calib *mpImuCalib;
  167. // Last Bias Estimation (at keyframe creation)
  168. IMU::Bias mLastBias;
  169. // In case of performing only localization, this flag is true when there are no matches to
  170. // points in the map. Still tracking will continue if there are enough matches with temporal points.
  171. // In that case we are doing visual odometry. The system will try to do relocalization to recover
  172. // "zero-drift" localization to the map.
  173. bool mbVO;
  174. //Other Thread Pointers
  175. LocalMapping* mpLocalMapper;
  176. LoopClosing* mpLoopClosing;
  177. //ORB
  178. ORBextractor* mpORBextractorLeft, *mpORBextractorRight;
  179. ORBextractor* mpIniORBextractor;
  180. //BoW
  181. ORBVocabulary* mpORBVocabulary;
  182. KeyFrameDatabase* mpKeyFrameDB;
  183. // Initalization (only for monocular)
  184. Initializer* mpInitializer;
  185. bool mbSetInit;
  186. //Local Map
  187. KeyFrame* mpReferenceKF;
  188. std::vector<KeyFrame*> mvpLocalKeyFrames;
  189. std::vector<MapPoint*> mvpLocalMapPoints;
  190. // System
  191. System* mpSystem;
  192. //Drawers
  193. Viewer* mpViewer;
  194. FrameDrawer* mpFrameDrawer;
  195. MapDrawer* mpMapDrawer;
  196. bool bStepByStep;
  197. //Atlas
  198. Atlas* mpAtlas;
  199. //Calibration matrix
  200. cv::Mat mK;
  201. cv::Mat mDistCoef;
  202. float mbf;
  203. //New KeyFrame rules (according to fps)
  204. int mMinFrames;
  205. int mMaxFrames;
  206. int mnFirstImuFrameId;
  207. int mnFramesToResetIMU;
  208. // Threshold close/far points
  209. // Points seen as close by the stereo/RGBD sensor are considered reliable
  210. // and inserted from just one frame. Far points requiere a match in two keyframes.
  211. float mThDepth;
  212. // For RGB-D inputs only. For some datasets (e.g. TUM) the depthmap values are scaled.
  213. float mDepthMapFactor;
  214. //Current matches in frame
  215. int mnMatchesInliers;
  216. //Last Frame, KeyFrame and Relocalisation Info
  217. KeyFrame* mpLastKeyFrame;
  218. unsigned int mnLastKeyFrameId;
  219. unsigned int mnLastRelocFrameId;
  220. double mTimeStampLost;
  221. double time_recently_lost;
  222. unsigned int mnFirstFrameId;
  223. unsigned int mnInitialFrameId;
  224. unsigned int mnLastInitFrameId;
  225. bool mbCreatedMap;
  226. //Motion Model
  227. cv::Mat mVelocity;
  228. //Color order (true RGB, false BGR, ignored if grayscale)
  229. bool mbRGB;
  230. list<MapPoint*> mlpTemporalPoints;
  231. //int nMapChangeIndex;
  232. int mnNumDataset;
  233. ofstream f_track_stats;
  234. ofstream f_track_times;
  235. double mTime_PreIntIMU;
  236. double mTime_PosePred;
  237. double mTime_LocalMapTrack;
  238. double mTime_NewKF_Dec;
  239. GeometricCamera* mpCamera, *mpCamera2;
  240. int initID, lastID;
  241. cv::Mat mTlr;
  242. public:
  243. cv::Mat mImRight;
  244. };
  245. } //namespace ORB_SLAM
  246. #endif // TRACKING_H