Rtabmap.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #ifndef RTABMAP_H_
00029 #define RTABMAP_H_
00030 
00031 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
00032 
00033 #include "rtabmap/core/Parameters.h"
00034 #include "rtabmap/core/SensorData.h"
00035 #include "rtabmap/core/Statistics.h"
00036 #include "rtabmap/core/Link.h"
00037 #include "rtabmap/core/ProgressState.h"
00038 
00039 #include <opencv2/core/core.hpp>
00040 #include <list>
00041 #include <stack>
00042 #include <set>
00043 
00044 namespace rtabmap
00045 {
00046 
00047 class EpipolarGeometry;
00048 class Memory;
00049 class BayesFilter;
00050 class Signature;
00051 class Optimizer;
00052 
00053 class RTABMAP_EXP Rtabmap
00054 {
00055 public:
00056         enum VhStrategy {kVhNone, kVhEpipolar, kVhUndef};
00057 
00058 public:
00059         Rtabmap();
00060         virtual ~Rtabmap();
00061 
00070         bool process(
00071                         const SensorData & data,
00072                         Transform odomPose,
00073                         const cv::Mat & odomCovariance = cv::Mat::eye(6,6,CV_64FC1),
00074                         const std::vector<float> & odomVelocity = std::vector<float>(),
00075                         const std::map<std::string, float> & externalStats = std::map<std::string, float>());
00076         // for convenience
00077         bool process(
00078                         const SensorData & data,
00079                         Transform odomPose,
00080                         float odomLinearVariance,
00081                         float odomAngularVariance,
00082                         const std::vector<float> & odomVelocity = std::vector<float>(),
00083                         const std::map<std::string, float> & externalStats = std::map<std::string, float>());
00084         // for convenience, loop closure detection only
00085         bool process(
00086                         const cv::Mat & image,
00087                         int id=0, const std::map<std::string, float> & externalStats = std::map<std::string, float>());
00088 
00089         void init(const ParametersMap & parameters, const std::string & databasePath = "");
00090         void init(const std::string & configFile = "", const std::string & databasePath = "");
00091 
00099         void close(bool databaseSaved = true, const std::string & ouputDatabasePath = "");
00100 
00101         const std::string & getWorkingDir() const {return _wDir;}
00102         bool isRGBDMode() const { return _rgbdSlamMode; }
00103         int getLoopClosureId() const {return _loopClosureHypothesis.first;}
00104         float getLoopClosureValue() const {return _loopClosureHypothesis.second;}
00105         int getHighestHypothesisId() const {return _highestHypothesis.first;}
00106         float getHighestHypothesisValue() const {return _highestHypothesis.second;}
00107         int getLastLocationId() const;
00108         std::list<int> getWM() const; // working memory
00109         std::set<int> getSTM() const; // short-term memory
00110         int getWMSize() const; // working memory size
00111         int getSTMSize() const; // short-term memory size
00112         std::map<int, int> getWeights() const;
00113         int getTotalMemSize() const;
00114         double getLastProcessTime() const {return _lastProcessTime;};
00115         std::multimap<int, cv::KeyPoint> getWords(int locationId) const;
00116         bool isInSTM(int locationId) const;
00117         bool isIDsGenerated() const;
00118         const Statistics & getStatistics() const;
00119         //bool getMetricData(int locationId, cv::Mat & rgb, cv::Mat & depth, float & depthConstant, Transform & pose, Transform & localTransform) const;
00120         const std::map<int, Transform> & getLocalOptimizedPoses() const {return _optimizedPoses;}
00121         const std::multimap<int, Link> & getLocalConstraints() const {return _constraints;}
00122         Transform getPose(int locationId) const;
00123         Transform getMapCorrection() const {return _mapCorrection;}
00124         const Memory * getMemory() const {return _memory;}
00125         float getGoalReachedRadius() const {return _goalReachedRadius;}
00126         float getLocalRadius() const {return _localRadius;}
00127         const Transform & getLastLocalizationPose() const {return _lastLocalizationPose;}
00128 
00129         float getTimeThreshold() const {return _maxTimeAllowed;} // in ms
00130         void setTimeThreshold(float maxTimeAllowed); // in ms
00131 
00132         void setInitialPose(const Transform & initialPose);
00133         int triggerNewMap();
00134         bool labelLocation(int id, const std::string & label);
00142         bool setUserData(int id, const cv::Mat & data);
00143         void generateDOTGraph(const std::string & path, int id=0, int margin=5);
00144         void exportPoses(
00145                         const std::string & path,
00146                         bool optimized,
00147                         bool global,
00148                         int format // 0=raw, 1=rgbd-slam format, 2=KITTI format, 3=TORO, 4=g2o
00149         );
00150         void resetMemory();
00151         void dumpPrediction() const;
00152         void dumpData() const;
00153         void parseParameters(const ParametersMap & parameters);
00154         const ParametersMap & getParameters() const {return _parameters;}
00155         void setWorkingDirectory(std::string path);
00156         void rejectLastLoopClosure();
00157         void deleteLastLocation();
00158         void setOptimizedPoses(const std::map<int, Transform> & poses);
00159         void get3DMap(std::map<int, Signature> & signatures,
00160                         std::map<int, Transform> & poses,
00161                         std::multimap<int, Link> & constraints,
00162                         bool optimized,
00163                         bool global) const;
00164         void getGraph(std::map<int, Transform> & poses,
00165                         std::multimap<int, Link> & constraints,
00166                         bool optimized,
00167                         bool global,
00168                         std::map<int, Signature> * signatures = 0);
00169         int detectMoreLoopClosures(float clusterRadius = 0.5f, float clusterAngle = M_PI/6.0f, int iterations = 1, const ProgressState * state = 0);
00170         int refineLinks();
00171 
00172         int getPathStatus() const {return _pathStatus;} // -1=failed 0=idle/executing 1=success
00173         void clearPath(int status); // -1=failed 0=idle/executing 1=success
00174         bool computePath(int targetNode, bool global);
00175         bool computePath(const Transform & targetPose, float tolerance = -1.0f); // only in current optimized map, tolerance (m) < 0 means RGBD/LocalRadius, 0 means infinite
00176         const std::vector<std::pair<int, Transform> > & getPath() const {return _path;}
00177         std::vector<std::pair<int, Transform> > getPathNextPoses() const;
00178         std::vector<int> getPathNextNodes() const;
00179         int getPathCurrentGoalId() const;
00180         unsigned int getPathCurrentIndex() const {return _pathCurrentIndex;}
00181         unsigned int getPathCurrentGoalIndex() const {return _pathGoalIndex;}
00182         const Transform & getPathTransformToGoal() const {return _pathTransformToGoal;}
00183 
00184         std::map<int, Transform> getForwardWMPoses(int fromId, int maxNearestNeighbors, float radius, int maxDiffID) const;
00185         std::map<int, std::map<int, Transform> > getPaths(std::map<int, Transform> poses, const Transform & target, int maxGraphDepth = 0) const;
00186         void adjustLikelihood(std::map<int, float> & likelihood) const;
00187         std::pair<int, float> selectHypothesis(const std::map<int, float> & posterior,
00188                                                                                         const std::map<int, float> & likelihood) const;
00189 
00190 private:
00191         void optimizeCurrentMap(int id,
00192                         bool lookInDatabase,
00193                         std::map<int, Transform> & optimizedPoses,
00194                         cv::Mat & covariance,
00195                         std::multimap<int, Link> * constraints = 0,
00196                         double * error = 0,
00197                         int * iterationsDone = 0) const;
00198         std::map<int, Transform> optimizeGraph(
00199                         int fromId,
00200                         const std::set<int> & ids,
00201                         const std::map<int, Transform> & guessPoses,
00202                         bool lookInDatabase,
00203                         cv::Mat & covariance,
00204                         std::multimap<int, Link> * constraints = 0,
00205                         double * error = 0,
00206                         int * iterationsDone = 0) const;
00207         void updateGoalIndex();
00208         bool computePath(int targetNode, std::map<int, Transform> nodes, const std::multimap<int, rtabmap::Link> & constraints);
00209 
00210         void setupLogFiles(bool overwrite = false);
00211         void flushStatisticLogs();
00212 
00213 private:
00214         // Modifiable parameters
00215         bool _publishStats;
00216         bool _publishLastSignatureData;
00217         bool _publishPdf;
00218         bool _publishLikelihood;
00219         bool _publishRAMUsage;
00220         bool _computeRMSE;
00221         bool _saveWMState;
00222         float _maxTimeAllowed; // in ms
00223         unsigned int _maxMemoryAllowed; // signatures count in WM
00224         float _loopThr;
00225         float _loopRatio;
00226         bool _verifyLoopClosureHypothesis;
00227         unsigned int _maxRetrieved;
00228         unsigned int _maxLocalRetrieved;
00229         bool _rawDataKept;
00230         bool _statisticLogsBufferedInRAM;
00231         bool _statisticLogged;
00232         bool _statisticLoggedHeaders;
00233         bool _rgbdSlamMode;
00234         float _rgbdLinearUpdate;
00235         float _rgbdAngularUpdate;
00236         float _rgbdLinearSpeedUpdate;
00237         float _rgbdAngularSpeedUpdate;
00238         float _newMapOdomChangeDistance;
00239         bool _neighborLinkRefining;
00240         bool _proximityByTime;
00241         bool _proximityBySpace;
00242         bool _scanMatchingIdsSavedInLinks;
00243         float _localRadius;
00244         float _localImmunizationRatio;
00245         int _proximityMaxGraphDepth;
00246         int _proximityMaxPaths;
00247         int _proximityMaxNeighbors;
00248         float _proximityFilteringRadius;
00249         bool _proximityRawPosesUsed;
00250         float _proximityAngle;
00251         std::string _databasePath;
00252         bool _optimizeFromGraphEnd;
00253         float _optimizationMaxError;
00254         bool _startNewMapOnLoopClosure;
00255         bool _startNewMapOnGoodSignature;
00256         float _goalReachedRadius; // meters
00257         bool _goalsSavedInUserData;
00258         int _pathStuckIterations;
00259         float _pathLinearVelocity;
00260         float _pathAngularVelocity;
00261         bool _savedLocalizationIgnored;
00262 
00263         std::pair<int, float> _loopClosureHypothesis;
00264         std::pair<int, float> _highestHypothesis;
00265         double _lastProcessTime;
00266         bool _someNodesHaveBeenTransferred;
00267         float _distanceTravelled;
00268 
00269         // Abstract classes containing all loop closure
00270         // strategies for a type of signature or configuration.
00271         EpipolarGeometry * _epipolarGeometry;
00272         BayesFilter * _bayesFilter;
00273         Optimizer * _graphOptimizer;
00274         ParametersMap _parameters;
00275 
00276         Memory * _memory;
00277 
00278         FILE* _foutFloat;
00279         FILE* _foutInt;
00280         std::list<std::string> _bufferedLogsF;
00281         std::list<std::string> _bufferedLogsI;
00282 
00283         Statistics statistics_;
00284 
00285         std::string _wDir;
00286 
00287         std::map<int, Transform> _optimizedPoses;
00288         std::multimap<int, Link> _constraints;
00289         Transform _mapCorrection;
00290         Transform _mapCorrectionBackup; // used in localization mode when odom is lost
00291         Transform _lastLocalizationPose; // Corrected odometry pose. In mapping mode, this corresponds to last pose return by getLocalOptimizedPoses().
00292         int _lastLocalizationNodeId; // for localization mode
00293 
00294         // Planning stuff
00295         int _pathStatus;
00296         std::vector<std::pair<int,Transform> > _path;
00297         std::set<unsigned int> _pathUnreachableNodes;
00298         unsigned int _pathCurrentIndex;
00299         unsigned int _pathGoalIndex;
00300         Transform _pathTransformToGoal;
00301         int _pathStuckCount;
00302         float _pathStuckDistance;
00303 
00304 };
00305 
00306 } // namespace rtabmap
00307 #endif /* RTABMAP_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:22