Tracking.h 9.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337
  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. // Parse the config file
  54. bool ParseCamParamFile(cv::FileStorage &fSettings);
  55. bool ParseORBParamFile(cv::FileStorage &fSettings);
  56. bool ParseIMUParamFile(cv::FileStorage &fSettings);
  57. // Preprocess the input and call Track(). Extract features and performs stereo matching.
  58. cv::Mat GrabImageStereo(const cv::Mat &imRectLeft,const cv::Mat &imRectRight, const double &timestamp, string filename);
  59. cv::Mat GrabImageRGBD(const cv::Mat &imRGB,const cv::Mat &imD, const double &timestamp, string filename);
  60. cv::Mat GrabImageMonocular(const cv::Mat &im, const double &timestamp, string filename);
  61. // cv::Mat GrabImageImuMonocular(const cv::Mat &im, const double &timestamp);
  62. void GrabImuData(const IMU::Point &imuMeasurement);
  63. void SetLocalMapper(LocalMapping* pLocalMapper);
  64. void SetLoopClosing(LoopClosing* pLoopClosing);
  65. void SetViewer(Viewer* pViewer);
  66. void SetStepByStep(bool bSet);
  67. // Load new settings
  68. // The focal lenght should be similar or scale prediction will fail when projecting points
  69. void ChangeCalibration(const string &strSettingPath);
  70. // Use this function if you have deactivated local mapping and you only want to localize the camera.
  71. void InformOnlyTracking(const bool &flag);
  72. void UpdateFrameIMU(const float s, const IMU::Bias &b, KeyFrame* pCurrentKeyFrame);
  73. KeyFrame* GetLastKeyFrame()
  74. {
  75. return mpLastKeyFrame;
  76. }
  77. void CreateMapInAtlas();
  78. std::mutex mMutexTracks;
  79. //--
  80. void NewDataset();
  81. int GetNumberDataset();
  82. int GetMatchesInliers();
  83. public:
  84. // Tracking states
  85. enum eTrackingState{
  86. SYSTEM_NOT_READY=-1,
  87. NO_IMAGES_YET=0,
  88. NOT_INITIALIZED=1,
  89. OK=2,
  90. RECENTLY_LOST=3,
  91. LOST=4,
  92. OK_KLT=5
  93. };
  94. eTrackingState mState;
  95. eTrackingState mLastProcessedState;
  96. // Input sensor
  97. int mSensor;
  98. // Current Frame
  99. Frame mCurrentFrame;
  100. Frame mLastFrame;
  101. cv::Mat mImGray;
  102. // Initialization Variables (Monocular)
  103. std::vector<int> mvIniLastMatches;
  104. std::vector<int> mvIniMatches;
  105. std::vector<cv::Point2f> mvbPrevMatched;
  106. std::vector<cv::Point3f> mvIniP3D;
  107. Frame mInitialFrame;
  108. // Lists used to recover the full camera trajectory at the end of the execution.
  109. // Basically we store the reference keyframe for each frame and its relative transformation
  110. list<cv::Mat> mlRelativeFramePoses;
  111. list<KeyFrame*> mlpReferences;
  112. list<double> mlFrameTimes;
  113. list<bool> mlbLost;
  114. // frames with estimated pose
  115. int mTrackedFr;
  116. bool mbStep;
  117. // True if local mapping is deactivated and we are performing only localization
  118. bool mbOnlyTracking;
  119. void Reset(bool bLocMap = false);
  120. void ResetActiveMap(bool bLocMap = false);
  121. float mMeanTrack;
  122. bool mbInitWith3KFs;
  123. double t0; // time-stamp of first read frame
  124. double t0vis; // time-stamp of first inserted keyframe
  125. double t0IMU; // time-stamp of IMU initialization
  126. vector<MapPoint*> GetLocalMapMPS();
  127. //TEST--
  128. bool mbNeedRectify;
  129. //cv::Mat M1l, M2l;
  130. //cv::Mat M1r, M2r;
  131. bool mbWriteStats;
  132. protected:
  133. // Main tracking function. It is independent of the input sensor.
  134. void Track();
  135. // Map initialization for stereo and RGB-D
  136. void StereoInitialization();
  137. // Map initialization for monocular
  138. void MonocularInitialization();
  139. void CreateNewMapPoints();
  140. cv::Mat ComputeF12(KeyFrame *&pKF1, KeyFrame *&pKF2);
  141. void CreateInitialMapMonocular();
  142. void CheckReplacedInLastFrame();
  143. bool TrackReferenceKeyFrame();
  144. void UpdateLastFrame();
  145. bool TrackWithMotionModel();
  146. bool PredictStateIMU();
  147. bool Relocalization();
  148. void UpdateLocalMap();
  149. void UpdateLocalPoints();
  150. void UpdateLocalKeyFrames();
  151. bool TrackLocalMap();
  152. bool TrackLocalMap_old();
  153. void SearchLocalPoints();
  154. bool NeedNewKeyFrame();
  155. void CreateNewKeyFrame();
  156. // Perform preintegration from last frame
  157. void PreintegrateIMU();
  158. // Reset IMU biases and compute frame velocity
  159. void ResetFrameIMU();
  160. void ComputeGyroBias(const vector<Frame*> &vpFs, float &bwx, float &bwy, float &bwz);
  161. void ComputeVelocitiesAccBias(const vector<Frame*> &vpFs, float &bax, float &bay, float &baz);
  162. bool mbMapUpdated;
  163. // Imu preintegration from last frame
  164. IMU::Preintegrated *mpImuPreintegratedFromLastKF;
  165. // Queue of IMU measurements between frames
  166. std::list<IMU::Point> mlQueueImuData;
  167. // Vector of IMU measurements from previous to current frame (to be filled by PreintegrateIMU)
  168. std::vector<IMU::Point> mvImuFromLastFrame;
  169. std::mutex mMutexImuQueue;
  170. // Imu calibration parameters
  171. IMU::Calib *mpImuCalib;
  172. // Last Bias Estimation (at keyframe creation)
  173. IMU::Bias mLastBias;
  174. // In case of performing only localization, this flag is true when there are no matches to
  175. // points in the map. Still tracking will continue if there are enough matches with temporal points.
  176. // In that case we are doing visual odometry. The system will try to do relocalization to recover
  177. // "zero-drift" localization to the map.
  178. bool mbVO;
  179. //Other Thread Pointers
  180. LocalMapping* mpLocalMapper;
  181. LoopClosing* mpLoopClosing;
  182. //ORB
  183. ORBextractor* mpORBextractorLeft, *mpORBextractorRight;
  184. ORBextractor* mpIniORBextractor;
  185. //BoW
  186. ORBVocabulary* mpORBVocabulary;
  187. KeyFrameDatabase* mpKeyFrameDB;
  188. // Initalization (only for monocular)
  189. Initializer* mpInitializer;
  190. bool mbSetInit;
  191. //Local Map
  192. KeyFrame* mpReferenceKF;
  193. std::vector<KeyFrame*> mvpLocalKeyFrames;
  194. std::vector<MapPoint*> mvpLocalMapPoints;
  195. // System
  196. System* mpSystem;
  197. //Drawers
  198. Viewer* mpViewer;
  199. FrameDrawer* mpFrameDrawer;
  200. MapDrawer* mpMapDrawer;
  201. bool bStepByStep;
  202. //Atlas
  203. Atlas* mpAtlas;
  204. //Calibration matrix
  205. cv::Mat mK;
  206. cv::Mat mDistCoef;
  207. float mbf;
  208. //New KeyFrame rules (according to fps)
  209. int mMinFrames;
  210. int mMaxFrames;
  211. int mnFirstImuFrameId;
  212. int mnFramesToResetIMU;
  213. // Threshold close/far points
  214. // Points seen as close by the stereo/RGBD sensor are considered reliable
  215. // and inserted from just one frame. Far points requiere a match in two keyframes.
  216. float mThDepth;
  217. // For RGB-D inputs only. For some datasets (e.g. TUM) the depthmap values are scaled.
  218. float mDepthMapFactor;
  219. //Current matches in frame
  220. int mnMatchesInliers;
  221. //Last Frame, KeyFrame and Relocalisation Info
  222. KeyFrame* mpLastKeyFrame;
  223. unsigned int mnLastKeyFrameId;
  224. unsigned int mnLastRelocFrameId;
  225. double mTimeStampLost;
  226. double time_recently_lost;
  227. unsigned int mnFirstFrameId;
  228. unsigned int mnInitialFrameId;
  229. unsigned int mnLastInitFrameId;
  230. bool mbCreatedMap;
  231. //Motion Model
  232. cv::Mat mVelocity;
  233. //Color order (true RGB, false BGR, ignored if grayscale)
  234. bool mbRGB;
  235. list<MapPoint*> mlpTemporalPoints;
  236. //int nMapChangeIndex;
  237. int mnNumDataset;
  238. ofstream f_track_stats;
  239. ofstream f_track_times;
  240. double mTime_PreIntIMU;
  241. double mTime_PosePred;
  242. double mTime_LocalMapTrack;
  243. double mTime_NewKF_Dec;
  244. GeometricCamera* mpCamera, *mpCamera2;
  245. int initID, lastID;
  246. cv::Mat mTlr;
  247. public:
  248. cv::Mat mImRight;
  249. };
  250. } //namespace ORB_SLAM
  251. #endif // TRACKING_H