System.h
Go to the documentation of this file.
1 
22 #ifndef SYSTEM_H
23 #define SYSTEM_H
24 
25 #include <string>
26 #include <thread>
27 #include <unistd.h>
28 #include <opencv2/core/core.hpp>
29 #include <sys/resource.h>
30 
31 
32 #include "Tracking.h"
33 #include "FrameDrawer.h"
34 #include "Map.h"
35 #include "LocalMapping.h"
36 #include "LoopClosing.h"
37 #include "KeyFrameDatabase.h"
38 #include "ORBVocabulary.h"
39 
40 namespace ORB_SLAM2
41 {
42 class FrameDrawer;
43 class Map;
44 class Tracking;
45 class LocalMapping;
46 class LoopClosing;
47 
48 struct ORBParameters;
49 
50 class System
51 {
52 public:
53  // Input sensor
54  enum eSensor{
56  STEREO=1,
57  RGBD=2
58  };
59 
60 public:
61 
62  // Initialize the SLAM system. It launches the Local Mapping, Loop Closing and Viewer threads.
63  System(const string strVocFile, const eSensor sensor, ORBParameters& parameters,
64  const std::string & map_file = "", bool load_map = false); // map serialization addition
65 
66  // Process the given stereo frame. Images must be synchronized and rectified.
67  // Input images: RGB (CV_8UC3) or grayscale (CV_8U). RGB is converted to grayscale.
68  // Returns the camera pose (empty if tracking fails).
69  void TrackStereo(const cv::Mat &imLeft, const cv::Mat &imRight, const double &timestamp);
70 
71  // Process the given rgbd frame. Depthmap must be registered to the RGB frame.
72  // Input image: RGB (CV_8UC3) or grayscale (CV_8U). RGB is converted to grayscale.
73  // Input depthmap: Float (CV_32F).
74  // Returns the camera pose (empty if tracking fails).
75  void TrackRGBD(const cv::Mat &im, const cv::Mat &depthmap, const double &timestamp);
76 
77  // Process the given monocular frame
78  // Input images: RGB (CV_8UC3) or grayscale (CV_8U). RGB is converted to grayscale.
79  // Returns the camera pose (empty if tracking fails).
80  void TrackMonocular(const cv::Mat &im, const double &timestamp);
81 
82  // Returns true if there have been a big map change (loop closure, global BA)
83  // since last call to this function
84  bool MapChanged();
85 
86  // Returns true if Global Bundle Adjustment is running
87  bool isRunningGBA();
88 
89  // Reset the system (clear map)
90  void Reset();
91 
92  // All threads will be requested to finish.
93  // It waits until all threads have finished.
94  // This function must be called before saving the trajectory.
95  void Shutdown();
96 
97  // Save camera trajectory in the TUM RGB-D dataset format.
98  // Only for stereo and RGB-D. This method does not work for monocular.
99  // Call first Shutdown()
100  // See format details at: http://vision.in.tum.de/data/datasets/rgbd-dataset
101  void SaveTrajectoryTUM(const string &filename);
102 
103  // Save keyframe poses in the TUM RGB-D dataset format.
104  // This method works for all sensor input.
105  // Call first Shutdown()
106  // See format details at: http://vision.in.tum.de/data/datasets/rgbd-dataset
107  void SaveKeyFrameTrajectoryTUM(const string &filename);
108 
109  // Save camera trajectory in the KITTI dataset format.
110  // Only for stereo and RGB-D. This method does not work for monocular.
111  // Call first Shutdown()
112  // See format details at: http://www.cvlibs.net/datasets/kitti/eval_odometry.php
113  void SaveTrajectoryKITTI(const string &filename);
114 
115  //Checks the current mode (mapping or localization) and changes the mode if requested
116  void EnableLocalizationOnly (bool localize_only);
117 
118  // TODO: Save/Load functions
119  // SaveMap(const string &filename);
120  // LoadMap(const string &filename);
121 
122  void SetMinimumKeyFrames (int min_num_kf);
123 
124  bool SaveMap(const string &filename);
125 
126  cv::Mat GetCurrentPosition ();
127 
128  // Information from most recent processed frame
129  // You can call this right after TrackMonocular (or stereo or RGBD)
130  int GetTrackingState();
131  std::vector<MapPoint*> GetTrackedMapPoints();
132  std::vector<cv::KeyPoint> GetTrackedKeyPointsUn();
133 
134  cv::Mat DrawCurrentFrame ();
135 
136  std::vector<MapPoint*> GetAllMapPoints();
137 
138 private:
139  bool SetCallStackSize (const rlim_t kNewStackSize);
140 
141  rlim_t GetCurrentCallStackSize ();
142 
143  // This stops local mapping thread (map building) and performs only camera tracking.
145 
146  // This resumes local mapping thread and performs SLAM again.
148 
149  bool LoadMap(const string &filename);
150 
152 
153  bool load_map;
154 
155  std::string map_file;
156 
157  // Input sensor
159 
160  // ORB vocabulary used for place recognition and feature matching.
162 
163  // KeyFrame database for place recognition (relocalization and loop detection).
165 
166  // Map structure that stores the pointers to all KeyFrames and MapPoints.
168 
169  // Tracker. It receives a frame and computes the associated camera pose.
170  // It also decides when to insert a new keyframe, create some new MapPoints and
171  // performs relocalization if tracking fails.
173 
174  // Local Mapper. It manages the local map and performs local bundle adjustment.
176 
177  // Loop Closer. It searches loops with every new keyframe. If there is a loop it performs
178  // a pose graph optimization and full bundle adjustment (in a new thread) afterwards.
180 
182 
183  // System threads: Local Mapping, Loop Closing, Viewer.
184  // The Tracking thread "lives" in the main execution thread that creates the System object.
185  std::thread* mptLocalMapping;
186  std::thread* mptLoopClosing;
187 
188  // Reset flag
189  std::mutex mMutexReset;
190  bool mbReset;
191 
192  // Change mode flags
193  std::mutex mMutexMode;
196 
197  // Tracking state
199  std::vector<MapPoint*> mTrackedMapPoints;
200  std::vector<cv::KeyPoint> mTrackedKeyPointsUn;
201  std::mutex mMutexState;
202 
203  // Current position
205 
206 };
207 
208 }// namespace ORB_SLAM
209 
210 #endif // SYSTEM_H
bool MapChanged()
Definition: System.cc:279
KeyFrameDatabase * mpKeyFrameDatabase
Definition: System.h:164
ORBVocabulary * mpVocabulary
Definition: System.h:161
std::vector< MapPoint * > GetTrackedMapPoints()
Definition: System.cc:481
cv::Mat current_position_
Definition: System.h:204
std::vector< MapPoint * > mTrackedMapPoints
Definition: System.h:199
bool SaveMap(const string &filename)
Definition: System.cc:573
rlim_t GetCurrentCallStackSize()
Definition: System.cc:530
void TrackMonocular(const cv::Mat &im, const double &timestamp)
Definition: System.cc:227
bool currently_localizing_only_
Definition: System.h:151
std::thread * mptLocalMapping
Definition: System.h:185
LoopClosing * mpLoopCloser
Definition: System.h:179
bool SetCallStackSize(const rlim_t kNewStackSize)
Definition: System.cc:502
bool isRunningGBA()
Definition: System.cc:292
System(const string strVocFile, const eSensor sensor, ORBParameters &parameters, const std::string &map_file="", bool load_map=false)
Definition: System.cc:31
LocalMapping * mpLocalMapper
Definition: System.h:175
void TrackStereo(const cv::Mat &imLeft, const cv::Mat &imRight, const double &timestamp)
Definition: System.cc:125
void EnableLocalizationOnly(bool localize_only)
Definition: System.cc:558
void Shutdown()
Definition: System.cc:303
std::vector< cv::KeyPoint > GetTrackedKeyPointsUn()
Definition: System.cc:487
int mTrackingState
Definition: System.h:198
Tracking * mpTracker
Definition: System.h:172
std::thread * mptLoopClosing
Definition: System.h:186
std::vector< cv::KeyPoint > mTrackedKeyPointsUn
Definition: System.h:200
bool mbActivateLocalizationMode
Definition: System.h:194
void TrackRGBD(const cv::Mat &im, const cv::Mat &depthmap, const double &timestamp)
Definition: System.cc:176
eSensor mSensor
Definition: System.h:158
void SaveTrajectoryKITTI(const string &filename)
Definition: System.cc:412
void SaveTrajectoryTUM(const string &filename)
Definition: System.cc:315
int GetTrackingState()
Definition: System.cc:475
std::mutex mMutexState
Definition: System.h:201
std::string map_file
Definition: System.h:155
cv::Mat GetCurrentPosition()
Definition: System.cc:471
bool mbDeactivateLocalizationMode
Definition: System.h:195
void DeactivateLocalizationMode()
Definition: System.cc:551
std::mutex mMutexMode
Definition: System.h:193
FrameDrawer * mpFrameDrawer
Definition: System.h:181
std::vector< MapPoint * > GetAllMapPoints()
Definition: System.cc:497
void SaveKeyFrameTrajectoryTUM(const string &filename)
Definition: System.cc:376
bool LoadMap(const string &filename)
Definition: System.cc:609
std::mutex mMutexReset
Definition: System.h:189
void ActivateLocalizationMode()
Definition: System.cc:544
cv::Mat DrawCurrentFrame()
Definition: System.cc:493
void SetMinimumKeyFrames(int min_num_kf)
Definition: System.cc:467


orb_slam2_ros
Author(s):
autogenerated on Wed Apr 21 2021 02:53:05