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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:37:30