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 
101  void init(const ParametersMap & parameters, const std::string & databasePath = "", bool loadDatabaseParameters = false);
114  void init(const std::string & configFile = "", const std::string & databasePath = "", bool loadDatabaseParameters = false);
115 
123  void close(bool databaseSaved = true, const std::string & ouputDatabasePath = "");
124 
125  const std::string & getWorkingDir() const {return _wDir;}
126  bool isRGBDMode() const { return _rgbdSlamMode; }
127  int getLoopClosureId() const {return _loopClosureHypothesis.first;}
128  float getLoopClosureValue() const {return _loopClosureHypothesis.second;}
129  int getHighestHypothesisId() const {return _highestHypothesis.first;}
130  float getHighestHypothesisValue() const {return _highestHypothesis.second;}
131  int getLastLocationId() const;
132  std::list<int> getWM() const; // working memory
133  std::set<int> getSTM() const; // short-term memory
134  int getWMSize() const; // working memory size
135  int getSTMSize() const; // short-term memory size
136  std::map<int, int> getWeights() const;
137  int getTotalMemSize() const;
138  double getLastProcessTime() const {return _lastProcessTime;};
139  bool isInSTM(int locationId) const;
140  bool isIDsGenerated() const;
141  const Statistics & getStatistics() const;
142  const std::map<int, Transform> & getLocalOptimizedPoses() const {return _optimizedPoses;}
143  const std::multimap<int, Link> & getLocalConstraints() const {return _constraints;}
144  Transform getPose(int locationId) const;
145  Transform getMapCorrection() const {return _mapCorrection;}
146  const Memory * getMemory() const {return _memory;}
147  float getGoalReachedRadius() const {return _goalReachedRadius;}
148  float getLocalRadius() const {return _localRadius;}
149  const Transform & getLastLocalizationPose() const {return _lastLocalizationPose;}
150 
151  float getTimeThreshold() const {return _maxTimeAllowed;} // in ms
152  void setTimeThreshold(float maxTimeAllowed); // in ms
153 
154  void setInitialPose(const Transform & initialPose);
155  int triggerNewMap();
156  bool labelLocation(int id, const std::string & label);
164  bool setUserData(int id, const cv::Mat & data);
165  void generateDOTGraph(const std::string & path, int id=0, int margin=5);
166  void exportPoses(
167  const std::string & path,
168  bool optimized,
169  bool global,
170  int format // 0=raw, 1=rgbd-slam format, 2=KITTI format, 3=TORO, 4=g2o
171  );
172  void resetMemory();
173  void dumpPrediction() const;
174  void dumpData() const;
175  void parseParameters(const ParametersMap & parameters);
176  const ParametersMap & getParameters() const {return _parameters;}
177  void setWorkingDirectory(std::string path);
178  void rejectLastLoopClosure();
179  void deleteLastLocation();
180  void setOptimizedPoses(const std::map<int, Transform> & poses);
181  Signature getSignatureCopy(int id, bool images, bool scan, bool userData, bool occupancyGrid, bool withWords, bool withGlobalDescriptors) const;
183  void get3DMap(std::map<int, Signature> & signatures,
184  std::map<int, Transform> & poses,
185  std::multimap<int, Link> & constraints,
186  bool optimized,
187  bool global) const, "Use getGraph() instead with withImages=true, withScan=true, withUserData=true and withGrid=true.");
188  void getGraph(std::map<int, Transform> & poses,
189  std::multimap<int, Link> & constraints,
190  bool optimized,
191  bool global,
192  std::map<int, Signature> * signatures = 0,
193  bool withImages = false,
194  bool withScan = false,
195  bool withUserData = false,
196  bool withGrid = false,
197  bool withWords = true,
198  bool withGlobalDescriptors = true) const;
199  std::map<int, Transform> getNodesInRadius(const Transform & pose, float radius); // If radius=0, RGBD/LocalRadius is used. Can return landmarks.
200  std::map<int, Transform> getNodesInRadius(int nodeId, float radius); // If nodeId==0, return poses around latest node. If radius=0, RGBD/LocalRadius is used. Can return landmarks and use landmark id (negative) as request.
201  int detectMoreLoopClosures(
202  float clusterRadius = 0.5f,
203  float clusterAngle = M_PI/6.0f,
204  int iterations = 1,
205  bool intraSession = true,
206  bool interSession = true,
207  const ProgressState * state = 0);
208  int refineLinks();
209  bool addLink(const Link & link);
210  cv::Mat getInformation(const cv::Mat & covariance) const;
211 
212  int getPathStatus() const {return _pathStatus;} // -1=failed 0=idle/executing 1=success
213  void clearPath(int status); // -1=failed 0=idle/executing 1=success
214  bool computePath(int targetNode, bool global);
215  bool computePath(const Transform & targetPose, float tolerance = -1.0f); // only in current optimized map, tolerance (m) < 0 means RGBD/LocalRadius, 0 means infinite
216  const std::vector<std::pair<int, Transform> > & getPath() const {return _path;}
217  std::vector<std::pair<int, Transform> > getPathNextPoses() const;
218  std::vector<int> getPathNextNodes() const;
219  int getPathCurrentGoalId() const;
220  unsigned int getPathCurrentIndex() const {return _pathCurrentIndex;}
221  unsigned int getPathCurrentGoalIndex() const {return _pathGoalIndex;}
222  const Transform & getPathTransformToGoal() const {return _pathTransformToGoal;}
223 
224  std::map<int, Transform> getForwardWMPoses(int fromId, int maxNearestNeighbors, float radius, int maxDiffID) const;
225  std::map<int, std::map<int, Transform> > getPaths(const std::map<int, Transform> & poses, const Transform & target, int maxGraphDepth = 0) const;
226  void adjustLikelihood(std::map<int, float> & likelihood) const;
227  std::pair<int, float> selectHypothesis(const std::map<int, float> & posterior,
228  const std::map<int, float> & likelihood) const;
229 
230 private:
231  void optimizeCurrentMap(int id,
232  bool lookInDatabase,
233  std::map<int, Transform> & optimizedPoses,
234  cv::Mat & covariance,
235  std::multimap<int, Link> * constraints = 0,
236  double * error = 0,
237  int * iterationsDone = 0) const;
238  std::map<int, Transform> optimizeGraph(
239  int fromId,
240  const std::set<int> & ids,
241  const std::map<int, Transform> & guessPoses,
242  bool lookInDatabase,
243  cv::Mat & covariance,
244  std::multimap<int, Link> * constraints = 0,
245  double * error = 0,
246  int * iterationsDone = 0) const;
247  void updateGoalIndex();
248  bool computePath(int targetNode, std::map<int, Transform> nodes, const std::multimap<int, rtabmap::Link> & constraints);
249 
250  void setupLogFiles(bool overwrite = false);
251  void flushStatisticLogs();
252 
253 private:
254  // Modifiable parameters
262  float _maxTimeAllowed; // in ms
263  unsigned int _maxMemoryAllowed; // signatures count in WM
264  float _loopThr;
265  float _loopRatio;
268  unsigned int _maxRetrieved;
269  unsigned int _maxLocalRetrieved;
293  std::string _databasePath;
298  float _goalReachedRadius; // meters
305  bool _loopGPS;
307 
308  std::pair<int, float> _loopClosureHypothesis;
309  std::pair<int, float> _highestHypothesis;
315 
316  // Abstract classes containing all loop closure
317  // strategies for a type of signature or configuration.
322 
324 
325  FILE* _foutFloat;
326  FILE* _foutInt;
327  std::list<std::string> _bufferedLogsF;
328  std::list<std::string> _bufferedLogsI;
329 
331 
332  std::string _wDir;
333 
334  std::map<int, Transform> _optimizedPoses;
335  std::multimap<int, Link> _constraints;
337  Transform _mapCorrectionBackup; // used in localization mode when odom is lost
338  Transform _lastLocalizationPose; // Corrected odometry pose. In mapping mode, this corresponds to last pose return by getLocalOptimizedPoses().
339  int _lastLocalizationNodeId; // for localization mode
340  std::map<int, std::pair<cv::Point3d, Transform> > _gpsGeocentricCache;
342  std::map<int, Transform> _odomCachePoses; // used in localization mode to reject loop closures
343  std::multimap<int, Link> _odomCacheConstraints; // used in localization mode to reject loop closures
344  std::map<int, Transform> _odomCacheAddLink; // used in localization mode when adding external link
345  std::vector<float> _odomCorrectionAcc;
346 
347  // Planning stuff
349  std::vector<std::pair<int,Transform> > _path;
350  std::set<unsigned int> _pathUnreachableNodes;
351  unsigned int _pathCurrentIndex;
352  unsigned int _pathGoalIndex;
356 
357 };
358 
359 } // namespace rtabmap
360 #endif /* RTABMAP_H_ */
Transform getMapCorrection() const
Definition: Rtabmap.h:145
Transform _mapCorrectionBackup
Definition: Rtabmap.h:337
EpipolarGeometry * _epipolarGeometry
Definition: Rtabmap.h:318
const Transform & getPathTransformToGoal() const
Definition: Rtabmap.h:222
float _loopThr
Definition: Rtabmap.h:264
bool _rgbdSlamMode
Definition: Rtabmap.h:274
bool _currentSessionHasGPS
Definition: Rtabmap.h:341
float _proximityAngle
Definition: Rtabmap.h:291
bool isRGBDMode() const
Definition: Rtabmap.h:126
unsigned int _maxLocalRetrieved
Definition: Rtabmap.h:269
double getLastProcessTime() const
Definition: Rtabmap.h:138
std::vector< std::pair< int, Transform > > _path
Definition: Rtabmap.h:349
bool _proximityByTime
Definition: Rtabmap.h:281
bool _optimizeFromGraphEndChanged
Definition: Rtabmap.h:314
bool exportPoses
float _pathStuckDistance
Definition: Rtabmap.h:355
float _localRadius
Definition: Rtabmap.h:284
f
float _distanceTravelledSinceLastLocalization
Definition: Rtabmap.h:313
float _rgbdAngularUpdate
Definition: Rtabmap.h:276
int _proximityMaxPaths
Definition: Rtabmap.h:287
def init(descriptorDim, matchThreshold, iterations, cuda, model_path)
bool _scanMatchingIdsSavedInLinks
Definition: Rtabmap.h:283
bool _publishRAMUsage
Definition: Rtabmap.h:259
const std::string & getWorkingDir() const
Definition: Rtabmap.h:125
bool _publishPdf
Definition: Rtabmap.h:257
float _rgbdAngularSpeedUpdate
Definition: Rtabmap.h:278
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
float _rgbdLinearSpeedUpdate
Definition: Rtabmap.h:277
float _distanceTravelled
Definition: Rtabmap.h:312
int _maxOdomCacheSize
Definition: Rtabmap.h:306
unsigned int _maxMemoryAllowed
Definition: Rtabmap.h:263
int _proximityMaxGraphDepth
Definition: Rtabmap.h:286
std::list< std::string > _bufferedLogsF
Definition: Rtabmap.h:327
float getGoalReachedRadius() const
Definition: Rtabmap.h:147
float _maxLoopClosureDistance
Definition: Rtabmap.h:266
float getLoopClosureValue() const
Definition: Rtabmap.h:128
const std::map< int, Transform > & getLocalOptimizedPoses() const
Definition: Rtabmap.h:142
std::map< int, Transform > _odomCachePoses
Definition: Rtabmap.h:342
float _newMapOdomChangeDistance
Definition: Rtabmap.h:279
int getHighestHypothesisId() const
Definition: Rtabmap.h:129
float _pathLinearVelocity
Definition: Rtabmap.h:301
Optimizer * _graphOptimizer
Definition: Rtabmap.h:320
bool _proximityBySpace
Definition: Rtabmap.h:282
bool _proximityRawPosesUsed
Definition: Rtabmap.h:290
float _optimizationMaxError
Definition: Rtabmap.h:295
#define RTABMAP_EXP
Definition: RtabmapExp.h:38
BayesFilter * _bayesFilter
Definition: Rtabmap.h:319
bool _statisticLoggedHeaders
Definition: Rtabmap.h:273
float _rgbdLinearUpdate
Definition: Rtabmap.h:275
float _goalReachedRadius
Definition: Rtabmap.h:298
bool _savedLocalizationIgnored
Definition: Rtabmap.h:303
Statistics statistics_
Definition: Rtabmap.h:330
FILE * _foutInt
Definition: Rtabmap.h:326
bool _saveWMState
Definition: Rtabmap.h:261
unsigned int getPathCurrentGoalIndex() const
Definition: Rtabmap.h:221
std::map< int, Transform > _odomCacheAddLink
Definition: Rtabmap.h:344
Memory * _memory
Definition: Rtabmap.h:323
int _pathStuckCount
Definition: Rtabmap.h:354
int getLoopClosureId() const
Definition: Rtabmap.h:127
bool _loopCovLimited
Definition: Rtabmap.h:304
bool _statisticLogsBufferedInRAM
Definition: Rtabmap.h:271
FILE * _foutFloat
Definition: Rtabmap.h:325
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:1634
bool _proximityOdomGuess
Definition: Rtabmap.h:292
Transform _lastLocalizationPose
Definition: Rtabmap.h:338
float getTimeThreshold() const
Definition: Rtabmap.h:151
std::multimap< int, Link > _odomCacheConstraints
Definition: Rtabmap.h:343
unsigned int _pathCurrentIndex
Definition: Rtabmap.h:351
float _maxTimeAllowed
Definition: Rtabmap.h:262
float _pathAngularVelocity
Definition: Rtabmap.h:302
std::string _wDir
Definition: Rtabmap.h:332
bool _statisticLogged
Definition: Rtabmap.h:272
std::pair< int, float > _highestHypothesis
Definition: Rtabmap.h:309
RecoveryProgressState state
bool _startNewMapOnLoopClosure
Definition: Rtabmap.h:296
bool _someNodesHaveBeenTransferred
Definition: Rtabmap.h:311
bool _publishLikelihood
Definition: Rtabmap.h:258
float getHighestHypothesisValue() const
Definition: Rtabmap.h:130
Transform _mapCorrection
Definition: Rtabmap.h:336
bool _computeRMSE
Definition: Rtabmap.h:260
std::map< int, std::pair< cv::Point3d, Transform > > _gpsGeocentricCache
Definition: Rtabmap.h:340
std::map< int, float > RTABMAP_EXP getNodesInRadius(int nodeId, const std::map< int, Transform > &nodes, float radius)
Definition: Graph.cpp:2113
int getPathStatus() const
Definition: Rtabmap.h:212
float _proximityFilteringRadius
Definition: Rtabmap.h:289
const std::vector< std::pair< int, Transform > > & getPath() const
Definition: Rtabmap.h:216
const ParametersMap & getParameters() const
Definition: Rtabmap.h:176
unsigned int _pathGoalIndex
Definition: Rtabmap.h:352
std::list< std::map< int, Transform > > RTABMAP_EXP getPaths(std::map< int, Transform > poses, const std::multimap< int, Link > &links)
Definition: Graph.cpp:2299
const Memory * getMemory() const
Definition: Rtabmap.h:146
std::vector< float > _odomCorrectionAcc
Definition: Rtabmap.h:345
std::multimap< int, Link > _constraints
Definition: Rtabmap.h:335
bool _optimizeFromGraphEnd
Definition: Rtabmap.h:294
bool _publishLastSignatureData
Definition: Rtabmap.h:256
std::list< std::string > _bufferedLogsI
Definition: Rtabmap.h:328
double _lastProcessTime
Definition: Rtabmap.h:310
bool _startNewMapOnGoodSignature
Definition: Rtabmap.h:297
int _pathStuckIterations
Definition: Rtabmap.h:300
const Transform & getLastLocalizationPose() const
Definition: Rtabmap.h:149
ParametersMap _parameters
Definition: Rtabmap.h:321
int _lastLocalizationNodeId
Definition: Rtabmap.h:339
float _loopRatio
Definition: Rtabmap.h:265
bool _goalsSavedInUserData
Definition: Rtabmap.h:299
std::pair< int, float > _loopClosureHypothesis
Definition: Rtabmap.h:308
const std::multimap< int, Link > & getLocalConstraints() const
Definition: Rtabmap.h:143
float _localImmunizationRatio
Definition: Rtabmap.h:285
RTABMAP_DEPRECATED(typedef SensorData Image,"rtabmap::Image class is renamed to rtabmap::SensorData, use the last one instead.")
std::set< unsigned int > _pathUnreachableNodes
Definition: Rtabmap.h:350
bool _rawDataKept
Definition: Rtabmap.h:270
bool _neighborLinkRefining
Definition: Rtabmap.h:280
bool _verifyLoopClosureHypothesis
Definition: Rtabmap.h:267
std::map< int, Transform > _optimizedPoses
Definition: Rtabmap.h:334
unsigned int getPathCurrentIndex() const
Definition: Rtabmap.h:220
bool _publishStats
Definition: Rtabmap.h:255
float getLocalRadius() const
Definition: Rtabmap.h:148
int _proximityMaxNeighbors
Definition: Rtabmap.h:288
std::string _databasePath
Definition: Rtabmap.h:293
Transform _pathTransformToGoal
Definition: Rtabmap.h:353
unsigned int _maxRetrieved
Definition: Rtabmap.h:268


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:35:00