System.h 7.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244
  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 SYSTEM_H
  19. #define SYSTEM_H
  20. //#define SAVE_TIMES
  21. #include <unistd.h>
  22. #include<stdio.h>
  23. #include<stdlib.h>
  24. #include<string>
  25. #include<thread>
  26. #include<opencv2/core/core.hpp>
  27. #include "Tracking.h"
  28. #include "FrameDrawer.h"
  29. #include "MapDrawer.h"
  30. #include "Atlas.h"
  31. #include "LocalMapping.h"
  32. #include "LoopClosing.h"
  33. #include "KeyFrameDatabase.h"
  34. #include "ORBVocabulary.h"
  35. #include "Viewer.h"
  36. #include "ImuTypes.h"
  37. namespace ORB_SLAM3
  38. {
  39. class Verbose
  40. {
  41. public:
  42. enum eLevel
  43. {
  44. VERBOSITY_QUIET=0,
  45. VERBOSITY_NORMAL=1,
  46. VERBOSITY_VERBOSE=2,
  47. VERBOSITY_VERY_VERBOSE=3,
  48. VERBOSITY_DEBUG=4
  49. };
  50. static eLevel th;
  51. public:
  52. static void PrintMess(std::string str, eLevel lev)
  53. {
  54. if(lev <= th)
  55. cout << str << endl;
  56. }
  57. static void SetTh(eLevel _th)
  58. {
  59. th = _th;
  60. }
  61. };
  62. class Viewer;
  63. class FrameDrawer;
  64. class Atlas;
  65. class Tracking;
  66. class LocalMapping;
  67. class LoopClosing;
  68. class System
  69. {
  70. public:
  71. // Input sensor
  72. enum eSensor{
  73. MONOCULAR=0,
  74. STEREO=1,
  75. RGBD=2,
  76. IMU_MONOCULAR=3,
  77. IMU_STEREO=4
  78. };
  79. // File type
  80. enum eFileType{
  81. TEXT_FILE=0,
  82. BINARY_FILE=1,
  83. };
  84. public:
  85. // Initialize the SLAM system. It launches the Local Mapping, Loop Closing and Viewer threads.
  86. System(const string &strVocFile, const string &strSettingsFile, const eSensor sensor, const bool bUseViewer = true, const int initFr = 0, const string &strSequence = std::string(), const string &strLoadingFile = std::string());
  87. // Proccess the given stereo frame. Images must be synchronized and rectified.
  88. // Input images: RGB (CV_8UC3) or grayscale (CV_8U). RGB is converted to grayscale.
  89. // Returns the camera pose (empty if tracking fails).
  90. cv::Mat TrackStereo(const cv::Mat &imLeft, const cv::Mat &imRight, const double &timestamp, const vector<IMU::Point>& vImuMeas = vector<IMU::Point>(), string filename="");
  91. // Process the given rgbd frame. Depthmap must be registered to the RGB frame.
  92. // Input image: RGB (CV_8UC3) or grayscale (CV_8U). RGB is converted to grayscale.
  93. // Input depthmap: Float (CV_32F).
  94. // Returns the camera pose (empty if tracking fails).
  95. cv::Mat TrackRGBD(const cv::Mat &im, const cv::Mat &depthmap, const double &timestamp, string filename="");
  96. // Proccess the given monocular frame and optionally imu data
  97. // Input images: RGB (CV_8UC3) or grayscale (CV_8U). RGB is converted to grayscale.
  98. // Returns the camera pose (empty if tracking fails).
  99. cv::Mat TrackMonocular(const cv::Mat &im, const double &timestamp, const vector<IMU::Point>& vImuMeas = vector<IMU::Point>(), string filename="");
  100. // This stops local mapping thread (map building) and performs only camera tracking.
  101. void ActivateLocalizationMode();
  102. // This resumes local mapping thread and performs SLAM again.
  103. void DeactivateLocalizationMode();
  104. // Returns true if there have been a big map change (loop closure, global BA)
  105. // since last call to this function
  106. bool MapChanged();
  107. // Reset the system (clear Atlas or the active map)
  108. void Reset();
  109. void ResetActiveMap();
  110. // All threads will be requested to finish.
  111. // It waits until all threads have finished.
  112. // This function must be called before saving the trajectory.
  113. void Shutdown();
  114. // Save camera trajectory in the TUM RGB-D dataset format.
  115. // Only for stereo and RGB-D. This method does not work for monocular.
  116. // Call first Shutdown()
  117. // See format details at: http://vision.in.tum.de/data/datasets/rgbd-dataset
  118. void SaveTrajectoryTUM(const string &filename);
  119. // Save keyframe poses in the TUM RGB-D dataset format.
  120. // This method works for all sensor input.
  121. // Call first Shutdown()
  122. // See format details at: http://vision.in.tum.de/data/datasets/rgbd-dataset
  123. void SaveKeyFrameTrajectoryTUM(const string &filename);
  124. void SaveTrajectoryEuRoC(const string &filename);
  125. void SaveKeyFrameTrajectoryEuRoC(const string &filename);
  126. // Save data used for initialization debug
  127. void SaveDebugData(const int &iniIdx);
  128. // Save camera trajectory in the KITTI dataset format.
  129. // Only for stereo and RGB-D. This method does not work for monocular.
  130. // Call first Shutdown()
  131. // See format details at: http://www.cvlibs.net/datasets/kitti/eval_odometry.php
  132. void SaveTrajectoryKITTI(const string &filename);
  133. // TODO: Save/Load functions
  134. // SaveMap(const string &filename);
  135. // LoadMap(const string &filename);
  136. // Information from most recent processed frame
  137. // You can call this right after TrackMonocular (or stereo or RGBD)
  138. int GetTrackingState();
  139. std::vector<MapPoint*> GetTrackedMapPoints();
  140. std::vector<cv::KeyPoint> GetTrackedKeyPointsUn();
  141. // For debugging
  142. double GetTimeFromIMUInit();
  143. bool isLost();
  144. bool isFinished();
  145. void ChangeDataset();
  146. //void SaveAtlas(int type);
  147. private:
  148. //bool LoadAtlas(string filename, int type);
  149. //string CalculateCheckSum(string filename, int type);
  150. // Input sensor
  151. eSensor mSensor;
  152. // ORB vocabulary used for place recognition and feature matching.
  153. ORBVocabulary* mpVocabulary;
  154. // KeyFrame database for place recognition (relocalization and loop detection).
  155. KeyFrameDatabase* mpKeyFrameDatabase;
  156. // Map structure that stores the pointers to all KeyFrames and MapPoints.
  157. //Map* mpMap;
  158. Atlas* mpAtlas;
  159. // Tracker. It receives a frame and computes the associated camera pose.
  160. // It also decides when to insert a new keyframe, create some new MapPoints and
  161. // performs relocalization if tracking fails.
  162. Tracking* mpTracker;
  163. // Local Mapper. It manages the local map and performs local bundle adjustment.
  164. LocalMapping* mpLocalMapper;
  165. // Loop Closer. It searches loops with every new keyframe. If there is a loop it performs
  166. // a pose graph optimization and full bundle adjustment (in a new thread) afterwards.
  167. LoopClosing* mpLoopCloser;
  168. // The viewer draws the map and the current camera pose. It uses Pangolin.
  169. Viewer* mpViewer;
  170. FrameDrawer* mpFrameDrawer;
  171. MapDrawer* mpMapDrawer;
  172. // System threads: Local Mapping, Loop Closing, Viewer.
  173. // The Tracking thread "lives" in the main execution thread that creates the System object.
  174. std::thread* mptLocalMapping;
  175. std::thread* mptLoopClosing;
  176. std::thread* mptViewer;
  177. // Reset flag
  178. std::mutex mMutexReset;
  179. bool mbReset;
  180. bool mbResetActiveMap;
  181. // Change mode flags
  182. std::mutex mMutexMode;
  183. bool mbActivateLocalizationMode;
  184. bool mbDeactivateLocalizationMode;
  185. // Tracking state
  186. int mTrackingState;
  187. std::vector<MapPoint*> mTrackedMapPoints;
  188. std::vector<cv::KeyPoint> mTrackedKeyPointsUn;
  189. std::mutex mMutexState;
  190. };
  191. }// namespace ORB_SLAM
  192. #endif // SYSTEM_H