Rtabmap.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #ifndef RTABMAP_H_
29 #define RTABMAP_H_
30 
31 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
32 
36 #include "rtabmap/core/Link.h"
38 
39 #include <opencv2/core/core.hpp>
40 #include <list>
41 #include <stack>
42 #include <set>
43 
44 namespace rtabmap
45 {
46 
47 class EpipolarGeometry;
48 class Memory;
49 class BayesFilter;
50 class Signature;
51 class Optimizer;
52 
54 {
55 public:
56  enum VhStrategy {kVhNone, kVhEpipolar, kVhUndef};
57 
58 public:
59  Rtabmap();
60  virtual ~Rtabmap();
61 
70  bool process(
71  const SensorData & data,
72  Transform odomPose,
73  const cv::Mat & odomCovariance = cv::Mat::eye(6,6,CV_64FC1),
74  const std::vector<float> & odomVelocity = std::vector<float>(),
75  const std::map<std::string, float> & externalStats = std::map<std::string, float>());
76  // for convenience
77  bool process(
78  const SensorData & data,
79  Transform odomPose,
80  float odomLinearVariance,
81  float odomAngularVariance,
82  const std::vector<float> & odomVelocity = std::vector<float>(),
83  const std::map<std::string, float> & externalStats = std::map<std::string, float>());
84  // for convenience, loop closure detection only
85  bool process(
86  const cv::Mat & image,
87  int id=0, const std::map<std::string, float> & externalStats = std::map<std::string, float>());
88 
89  void init(const ParametersMap & parameters, const std::string & databasePath = "");
90  void init(const std::string & configFile = "", const std::string & databasePath = "");
91 
99  void close(bool databaseSaved = true, const std::string & ouputDatabasePath = "");
100 
101  const std::string & getWorkingDir() const {return _wDir;}
102  bool isRGBDMode() const { return _rgbdSlamMode; }
103  int getLoopClosureId() const {return _loopClosureHypothesis.first;}
104  float getLoopClosureValue() const {return _loopClosureHypothesis.second;}
105  int getHighestHypothesisId() const {return _highestHypothesis.first;}
106  float getHighestHypothesisValue() const {return _highestHypothesis.second;}
107  int getLastLocationId() const;
108  std::list<int> getWM() const; // working memory
109  std::set<int> getSTM() const; // short-term memory
110  int getWMSize() const; // working memory size
111  int getSTMSize() const; // short-term memory size
112  std::map<int, int> getWeights() const;
113  int getTotalMemSize() const;
114  double getLastProcessTime() const {return _lastProcessTime;};
115  std::multimap<int, cv::KeyPoint> getWords(int locationId) const;
116  bool isInSTM(int locationId) const;
117  bool isIDsGenerated() const;
118  const Statistics & getStatistics() const;
119  //bool getMetricData(int locationId, cv::Mat & rgb, cv::Mat & depth, float & depthConstant, Transform & pose, Transform & localTransform) const;
120  const std::map<int, Transform> & getLocalOptimizedPoses() const {return _optimizedPoses;}
121  const std::multimap<int, Link> & getLocalConstraints() const {return _constraints;}
122  Transform getPose(int locationId) const;
123  Transform getMapCorrection() const {return _mapCorrection;}
124  const Memory * getMemory() const {return _memory;}
125  float getGoalReachedRadius() const {return _goalReachedRadius;}
126  float getLocalRadius() const {return _localRadius;}
127  const Transform & getLastLocalizationPose() const {return _lastLocalizationPose;}
128 
129  float getTimeThreshold() const {return _maxTimeAllowed;} // in ms
130  void setTimeThreshold(float maxTimeAllowed); // in ms
131 
132  void setInitialPose(const Transform & initialPose);
133  int triggerNewMap();
134  bool labelLocation(int id, const std::string & label);
142  bool setUserData(int id, const cv::Mat & data);
143  void generateDOTGraph(const std::string & path, int id=0, int margin=5);
144  void exportPoses(
145  const std::string & path,
146  bool optimized,
147  bool global,
148  int format // 0=raw, 1=rgbd-slam format, 2=KITTI format, 3=TORO, 4=g2o
149  );
150  void resetMemory();
151  void dumpPrediction() const;
152  void dumpData() const;
153  void parseParameters(const ParametersMap & parameters);
154  const ParametersMap & getParameters() const {return _parameters;}
155  void setWorkingDirectory(std::string path);
156  void rejectLastLoopClosure();
157  void deleteLastLocation();
158  void setOptimizedPoses(const std::map<int, Transform> & poses);
159  void get3DMap(std::map<int, Signature> & signatures,
160  std::map<int, Transform> & poses,
161  std::multimap<int, Link> & constraints,
162  bool optimized,
163  bool global) const;
164  void getGraph(std::map<int, Transform> & poses,
165  std::multimap<int, Link> & constraints,
166  bool optimized,
167  bool global,
168  std::map<int, Signature> * signatures = 0);
169  int detectMoreLoopClosures(float clusterRadius = 0.5f, float clusterAngle = M_PI/6.0f, int iterations = 1, const ProgressState * state = 0);
170  int refineLinks();
171 
172  int getPathStatus() const {return _pathStatus;} // -1=failed 0=idle/executing 1=success
173  void clearPath(int status); // -1=failed 0=idle/executing 1=success
174  bool computePath(int targetNode, bool global);
175  bool computePath(const Transform & targetPose, float tolerance = -1.0f); // only in current optimized map, tolerance (m) < 0 means RGBD/LocalRadius, 0 means infinite
176  const std::vector<std::pair<int, Transform> > & getPath() const {return _path;}
177  std::vector<std::pair<int, Transform> > getPathNextPoses() const;
178  std::vector<int> getPathNextNodes() const;
179  int getPathCurrentGoalId() const;
180  unsigned int getPathCurrentIndex() const {return _pathCurrentIndex;}
181  unsigned int getPathCurrentGoalIndex() const {return _pathGoalIndex;}
182  const Transform & getPathTransformToGoal() const {return _pathTransformToGoal;}
183 
184  std::map<int, Transform> getForwardWMPoses(int fromId, int maxNearestNeighbors, float radius, int maxDiffID) const;
185  std::map<int, std::map<int, Transform> > getPaths(std::map<int, Transform> poses, const Transform & target, int maxGraphDepth = 0) const;
186  void adjustLikelihood(std::map<int, float> & likelihood) const;
187  std::pair<int, float> selectHypothesis(const std::map<int, float> & posterior,
188  const std::map<int, float> & likelihood) const;
189 
190 private:
191  void optimizeCurrentMap(int id,
192  bool lookInDatabase,
193  std::map<int, Transform> & optimizedPoses,
194  cv::Mat & covariance,
195  std::multimap<int, Link> * constraints = 0,
196  double * error = 0,
197  int * iterationsDone = 0) const;
198  std::map<int, Transform> optimizeGraph(
199  int fromId,
200  const std::set<int> & ids,
201  const std::map<int, Transform> & guessPoses,
202  bool lookInDatabase,
203  cv::Mat & covariance,
204  std::multimap<int, Link> * constraints = 0,
205  double * error = 0,
206  int * iterationsDone = 0) const;
207  void updateGoalIndex();
208  bool computePath(int targetNode, std::map<int, Transform> nodes, const std::multimap<int, rtabmap::Link> & constraints);
209 
210  void setupLogFiles(bool overwrite = false);
211  void flushStatisticLogs();
212 
213 private:
214  // Modifiable parameters
222  float _maxTimeAllowed; // in ms
223  unsigned int _maxMemoryAllowed; // signatures count in WM
224  float _loopThr;
225  float _loopRatio;
227  unsigned int _maxRetrieved;
228  unsigned int _maxLocalRetrieved;
251  std::string _databasePath;
256  float _goalReachedRadius; // meters
262 
263  std::pair<int, float> _loopClosureHypothesis;
264  std::pair<int, float> _highestHypothesis;
268 
269  // Abstract classes containing all loop closure
270  // strategies for a type of signature or configuration.
275 
277 
278  FILE* _foutFloat;
279  FILE* _foutInt;
280  std::list<std::string> _bufferedLogsF;
281  std::list<std::string> _bufferedLogsI;
282 
284 
285  std::string _wDir;
286 
287  std::map<int, Transform> _optimizedPoses;
288  std::multimap<int, Link> _constraints;
290  Transform _mapCorrectionBackup; // used in localization mode when odom is lost
291  Transform _lastLocalizationPose; // Corrected odometry pose. In mapping mode, this corresponds to last pose return by getLocalOptimizedPoses().
292  int _lastLocalizationNodeId; // for localization mode
293 
294  // Planning stuff
296  std::vector<std::pair<int,Transform> > _path;
297  std::set<unsigned int> _pathUnreachableNodes;
298  unsigned int _pathCurrentIndex;
299  unsigned int _pathGoalIndex;
303 
304 };
305 
306 } // namespace rtabmap
307 #endif /* RTABMAP_H_ */
Transform getMapCorrection() const
Definition: Rtabmap.h:123
Transform _mapCorrectionBackup
Definition: Rtabmap.h:290
EpipolarGeometry * _epipolarGeometry
Definition: Rtabmap.h:271
const Transform & getPathTransformToGoal() const
Definition: Rtabmap.h:182
float _loopThr
Definition: Rtabmap.h:224
bool _rgbdSlamMode
Definition: Rtabmap.h:233
float _proximityAngle
Definition: Rtabmap.h:250
bool isRGBDMode() const
Definition: Rtabmap.h:102
unsigned int _maxLocalRetrieved
Definition: Rtabmap.h:228
double getLastProcessTime() const
Definition: Rtabmap.h:114
std::vector< std::pair< int, Transform > > _path
Definition: Rtabmap.h:296
bool _proximityByTime
Definition: Rtabmap.h:240
bool RTABMAP_EXP exportPoses(const std::string &filePath, int format, const std::map< int, Transform > &poses, const std::multimap< int, Link > &constraints=std::multimap< int, Link >(), const std::map< int, double > &stamps=std::map< int, double >(), bool g2oRobust=false)
Definition: Graph.cpp:53
float _pathStuckDistance
Definition: Rtabmap.h:302
float _localRadius
Definition: Rtabmap.h:243
f
float _rgbdAngularUpdate
Definition: Rtabmap.h:235
int _proximityMaxPaths
Definition: Rtabmap.h:246
bool _scanMatchingIdsSavedInLinks
Definition: Rtabmap.h:242
bool _publishRAMUsage
Definition: Rtabmap.h:219
const std::string & getWorkingDir() const
Definition: Rtabmap.h:101
bool _publishPdf
Definition: Rtabmap.h:217
float _rgbdAngularSpeedUpdate
Definition: Rtabmap.h:237
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:41
float _rgbdLinearSpeedUpdate
Definition: Rtabmap.h:236
float _distanceTravelled
Definition: Rtabmap.h:267
unsigned int _maxMemoryAllowed
Definition: Rtabmap.h:223
int _proximityMaxGraphDepth
Definition: Rtabmap.h:245
std::list< std::string > _bufferedLogsF
Definition: Rtabmap.h:280
float getGoalReachedRadius() const
Definition: Rtabmap.h:125
float getLoopClosureValue() const
Definition: Rtabmap.h:104
const std::map< int, Transform > & getLocalOptimizedPoses() const
Definition: Rtabmap.h:120
float _newMapOdomChangeDistance
Definition: Rtabmap.h:238
int getHighestHypothesisId() const
Definition: Rtabmap.h:105
float _pathLinearVelocity
Definition: Rtabmap.h:259
Optimizer * _graphOptimizer
Definition: Rtabmap.h:273
bool _proximityBySpace
Definition: Rtabmap.h:241
bool _proximityRawPosesUsed
Definition: Rtabmap.h:249
float _optimizationMaxError
Definition: Rtabmap.h:253
#define RTABMAP_EXP
Definition: RtabmapExp.h:38
BayesFilter * _bayesFilter
Definition: Rtabmap.h:272
bool _statisticLoggedHeaders
Definition: Rtabmap.h:232
float _rgbdLinearUpdate
Definition: Rtabmap.h:234
float _goalReachedRadius
Definition: Rtabmap.h:256
bool _savedLocalizationIgnored
Definition: Rtabmap.h:261
Statistics statistics_
Definition: Rtabmap.h:283
FILE * _foutInt
Definition: Rtabmap.h:279
bool _saveWMState
Definition: Rtabmap.h:221
unsigned int getPathCurrentGoalIndex() const
Definition: Rtabmap.h:181
Memory * _memory
Definition: Rtabmap.h:276
int _pathStuckCount
Definition: Rtabmap.h:301
int getLoopClosureId() const
Definition: Rtabmap.h:103
bool _statisticLogsBufferedInRAM
Definition: Rtabmap.h:230
FILE * _foutFloat
Definition: Rtabmap.h:278
std::list< std::pair< int, Transform > > RTABMAP_EXP computePath(const std::map< int, rtabmap::Transform > &poses, const std::multimap< int, int > &links, int from, int to, bool updateNewCosts=false)
Definition: Graph.cpp:1450
Transform _lastLocalizationPose
Definition: Rtabmap.h:291
float getTimeThreshold() const
Definition: Rtabmap.h:129
unsigned int _pathCurrentIndex
Definition: Rtabmap.h:298
float _maxTimeAllowed
Definition: Rtabmap.h:222
float _pathAngularVelocity
Definition: Rtabmap.h:260
std::string _wDir
Definition: Rtabmap.h:285
bool _statisticLogged
Definition: Rtabmap.h:231
std::pair< int, float > _highestHypothesis
Definition: Rtabmap.h:264
RecoveryProgressState state
bool _startNewMapOnLoopClosure
Definition: Rtabmap.h:254
bool _someNodesHaveBeenTransferred
Definition: Rtabmap.h:266
bool _publishLikelihood
Definition: Rtabmap.h:218
float getHighestHypothesisValue() const
Definition: Rtabmap.h:106
Transform _mapCorrection
Definition: Rtabmap.h:289
bool _computeRMSE
Definition: Rtabmap.h:220
int getPathStatus() const
Definition: Rtabmap.h:172
float _proximityFilteringRadius
Definition: Rtabmap.h:248
const std::vector< std::pair< int, Transform > > & getPath() const
Definition: Rtabmap.h:176
const ParametersMap & getParameters() const
Definition: Rtabmap.h:154
unsigned int _pathGoalIndex
Definition: Rtabmap.h:299
std::list< std::map< int, Transform > > RTABMAP_EXP getPaths(std::map< int, Transform > poses, const std::multimap< int, Link > &links)
Definition: Graph.cpp:2088
const Memory * getMemory() const
Definition: Rtabmap.h:124
std::multimap< int, Link > _constraints
Definition: Rtabmap.h:288
bool _optimizeFromGraphEnd
Definition: Rtabmap.h:252
bool _publishLastSignatureData
Definition: Rtabmap.h:216
std::list< std::string > _bufferedLogsI
Definition: Rtabmap.h:281
double _lastProcessTime
Definition: Rtabmap.h:265
bool _startNewMapOnGoodSignature
Definition: Rtabmap.h:255
int _pathStuckIterations
Definition: Rtabmap.h:258
const Transform & getLastLocalizationPose() const
Definition: Rtabmap.h:127
ParametersMap _parameters
Definition: Rtabmap.h:274
int _lastLocalizationNodeId
Definition: Rtabmap.h:292
float _loopRatio
Definition: Rtabmap.h:225
bool _goalsSavedInUserData
Definition: Rtabmap.h:257
std::pair< int, float > _loopClosureHypothesis
Definition: Rtabmap.h:263
const std::multimap< int, Link > & getLocalConstraints() const
Definition: Rtabmap.h:121
float _localImmunizationRatio
Definition: Rtabmap.h:244
std::set< unsigned int > _pathUnreachableNodes
Definition: Rtabmap.h:297
bool _rawDataKept
Definition: Rtabmap.h:229
bool _neighborLinkRefining
Definition: Rtabmap.h:239
bool _verifyLoopClosureHypothesis
Definition: Rtabmap.h:226
std::map< int, Transform > _optimizedPoses
Definition: Rtabmap.h:287
unsigned int getPathCurrentIndex() const
Definition: Rtabmap.h:180
bool _publishStats
Definition: Rtabmap.h:215
float getLocalRadius() const
Definition: Rtabmap.h:126
int _proximityMaxNeighbors
Definition: Rtabmap.h:247
std::string _databasePath
Definition: Rtabmap.h:251
Transform _pathTransformToGoal
Definition: Rtabmap.h:300
unsigned int _maxRetrieved
Definition: Rtabmap.h:227


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:32