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 
00038 #include <opencv2/core/core.hpp>
00039 #include <list>
00040 #include <stack>
00041 #include <set>
00042 
00043 namespace rtabmap
00044 {
00045 
00046 class EpipolarGeometry;
00047 class Memory;
00048 class BayesFilter;
00049 class Signature;
00050 class Optimizer;
00051 
00052 class RTABMAP_EXP Rtabmap
00053 {
00054 public:
00055         enum VhStrategy {kVhNone, kVhEpipolar, kVhUndef};
00056 
00057 public:
00058         Rtabmap();
00059         virtual ~Rtabmap();
00060 
00061         bool process(const cv::Mat & image, int id=0); // for convenience, an id is automatically generated if id=0
00062         bool process(
00063                         const SensorData & data,
00064                         const Transform & odomPose,
00065                         const cv::Mat & covariance = cv::Mat::eye(6,6,CV_64FC1)); // for convenience
00066 
00067         void init(const ParametersMap & parameters, const std::string & databasePath = "");
00068         void init(const std::string & configFile = "", const std::string & databasePath = "");
00069 
00070         void close(bool databaseSaved = true);
00071 
00072         const std::string & getWorkingDir() const {return _wDir;}
00073         bool isRGBDMode() const { return _rgbdSlamMode; }
00074         int getLoopClosureId() const {return _loopClosureHypothesis.first;}
00075         float getLoopClosureValue() const {return _loopClosureHypothesis.second;}
00076         int getHighestHypothesisId() const {return _highestHypothesis.first;}
00077         float getHighestHypothesisValue() const {return _highestHypothesis.second;}
00078         int getLastLocationId() const;
00079         std::list<int> getWM() const; // working memory
00080         std::set<int> getSTM() const; // short-term memory
00081         int getWMSize() const; // working memory size
00082         int getSTMSize() const; // short-term memory size
00083         std::map<int, int> getWeights() const;
00084         int getTotalMemSize() const;
00085         double getLastProcessTime() const {return _lastProcessTime;};
00086         std::multimap<int, cv::KeyPoint> getWords(int locationId) const;
00087         bool isInSTM(int locationId) const;
00088         bool isIDsGenerated() const;
00089         const Statistics & getStatistics() const;
00090         //bool getMetricData(int locationId, cv::Mat & rgb, cv::Mat & depth, float & depthConstant, Transform & pose, Transform & localTransform) const;
00091         const std::map<int, Transform> & getLocalOptimizedPoses() const {return _optimizedPoses;}
00092         Transform getPose(int locationId) const;
00093         Transform getMapCorrection() const {return _mapCorrection;}
00094         const Memory * getMemory() const {return _memory;}
00095         float getGoalReachedRadius() const {return _goalReachedRadius;}
00096         float getLocalRadius() const {return _localRadius;}
00097         const Transform & getLastLocalizationPose() const {return _lastLocalizationPose;}
00098 
00099         float getTimeThreshold() const {return _maxTimeAllowed;} // in ms
00100         void setTimeThreshold(float maxTimeAllowed); // in ms
00101 
00102         int triggerNewMap();
00103         bool labelLocation(int id, const std::string & label);
00104         bool setUserData(int id, const cv::Mat & data);
00105         void generateDOTGraph(const std::string & path, int id=0, int margin=5);
00106         void exportPoses(
00107                         const std::string & path,
00108                         bool optimized,
00109                         bool global,
00110                         int format // 0=raw, 1=rgbd-slam format, 2=KITTI format, 3=TORO, 4=g2o
00111         );
00112         void resetMemory();
00113         void dumpPrediction() const;
00114         void dumpData() const;
00115         void parseParameters(const ParametersMap & parameters);
00116         const ParametersMap & getParameters() const {return _parameters;}
00117         void setWorkingDirectory(std::string path);
00118         void rejectLoopClosure(int oldId, int newId);
00119         void setOptimizedPoses(const std::map<int, Transform> & poses);
00120         void get3DMap(std::map<int, Signature> & signatures,
00121                         std::map<int, Transform> & poses,
00122                         std::multimap<int, Link> & constraints,
00123                         bool optimized,
00124                         bool global) const;
00125         void getGraph(std::map<int, Transform> & poses,
00126                         std::multimap<int, Link> & constraints,
00127                         bool optimized,
00128                         bool global,
00129                         std::map<int, Signature> * signatures = 0);
00130         int detectMoreLoopClosures(float clusterRadius = 0.5f, float clusterAngle = M_PI/6.0f, int iterations = 1);
00131 
00132         int getPathStatus() const {return _pathStatus;} // -1=failed 0=idle/executing 1=success
00133         void clearPath(int status); // -1=failed 0=idle/executing 1=success
00134         bool computePath(int targetNode, bool global);
00135         bool computePath(const Transform & targetPose); // only in current optimized map
00136         const std::vector<std::pair<int, Transform> > & getPath() const {return _path;}
00137         std::vector<std::pair<int, Transform> > getPathNextPoses() const;
00138         std::vector<int> getPathNextNodes() const;
00139         int getPathCurrentGoalId() const;
00140         unsigned int getPathCurrentIndex() const {return _pathCurrentIndex;}
00141         unsigned int getPathCurrentGoalIndex() const {return _pathGoalIndex;}
00142         const Transform & getPathTransformToGoal() const {return _pathTransformToGoal;}
00143 
00144         std::map<int, Transform> getForwardWMPoses(int fromId, int maxNearestNeighbors, float radius, int maxDiffID) const;
00145         std::list<std::map<int, Transform> > getPaths(std::map<int, Transform> poses) const;
00146         void adjustLikelihood(std::map<int, float> & likelihood) const;
00147         std::pair<int, float> selectHypothesis(const std::map<int, float> & posterior,
00148                                                                                         const std::map<int, float> & likelihood) const;
00149 
00150 private:
00151         void optimizeCurrentMap(int id,
00152                         bool lookInDatabase,
00153                         std::map<int, Transform> & optimizedPoses,
00154                         std::multimap<int, Link> * constraints = 0,
00155                         double * error = 0,
00156                         int * iterationsDone = 0) const;
00157         std::map<int, Transform> optimizeGraph(
00158                         int fromId,
00159                         const std::set<int> & ids,
00160                         const std::map<int, Transform> & guessPoses,
00161                         bool lookInDatabase,
00162                         std::multimap<int, Link> * constraints = 0,
00163                         double * error = 0,
00164                         int * iterationsDone = 0) const;
00165         void updateGoalIndex();
00166         bool computePath(int targetNode, std::map<int, Transform> nodes, const std::multimap<int, rtabmap::Link> & constraints);
00167 
00168         void setupLogFiles(bool overwrite = false);
00169         void flushStatisticLogs();
00170 
00171 private:
00172         // Modifiable parameters
00173         bool _publishStats;
00174         bool _publishLastSignatureData;
00175         bool _publishPdf;
00176         bool _publishLikelihood;
00177         float _maxTimeAllowed; // in ms
00178         unsigned int _maxMemoryAllowed; // signatures count in WM
00179         float _loopThr;
00180         float _loopRatio;
00181         unsigned int _maxRetrieved;
00182         unsigned int _maxLocalRetrieved;
00183         bool _rawDataKept;
00184         bool _statisticLogsBufferedInRAM;
00185         bool _statisticLogged;
00186         bool _statisticLoggedHeaders;
00187         bool _rgbdSlamMode;
00188         float _rgbdLinearUpdate;
00189         float _rgbdAngularUpdate;
00190         float _newMapOdomChangeDistance;
00191         bool _neighborLinkRefining;
00192         bool _proximityByTime;
00193         bool _proximityBySpace;
00194         bool _scanMatchingIdsSavedInLinks;
00195         float _localRadius;
00196         float _localImmunizationRatio;
00197         int _proximityMaxGraphDepth;
00198         float _proximityFilteringRadius;
00199         bool _proximityRawPosesUsed;
00200         float _proximityAngle;
00201         std::string _databasePath;
00202         bool _optimizeFromGraphEnd;
00203         float _optimizationMaxLinearError;
00204         bool _startNewMapOnLoopClosure;
00205         float _goalReachedRadius; // meters
00206         bool _goalsSavedInUserData;
00207         int _pathStuckIterations;
00208         float _pathLinearVelocity;
00209         float _pathAngularVelocity;
00210 
00211         std::pair<int, float> _loopClosureHypothesis;
00212         std::pair<int, float> _highestHypothesis;
00213         double _lastProcessTime;
00214         bool _someNodesHaveBeenTransferred;
00215         float _distanceTravelled;
00216 
00217         // Abstract classes containing all loop closure
00218         // strategies for a type of signature or configuration.
00219         EpipolarGeometry * _epipolarGeometry;
00220         BayesFilter * _bayesFilter;
00221         Optimizer * _graphOptimizer;
00222         ParametersMap _parameters;
00223 
00224         Memory * _memory;
00225 
00226         FILE* _foutFloat;
00227         FILE* _foutInt;
00228         std::list<std::string> _bufferedLogsF;
00229         std::list<std::string> _bufferedLogsI;
00230 
00231         Statistics statistics_;
00232 
00233         std::string _wDir;
00234 
00235         std::map<int, Transform> _optimizedPoses;
00236         std::multimap<int, Link> _constraints;
00237         Transform _mapCorrection;
00238         Transform _lastLocalizationPose; // Corrected odometry pose. In mapping mode, this corresponds to last pose return by getLocalOptimizedPoses().
00239         int _lastLocalizationNodeId; // for localization mode
00240 
00241         // Planning stuff
00242         int _pathStatus;
00243         std::vector<std::pair<int,Transform> > _path;
00244         std::set<unsigned int> _pathUnreachableNodes;
00245         unsigned int _pathCurrentIndex;
00246         unsigned int _pathGoalIndex;
00247         Transform _pathTransformToGoal;
00248         int _pathStuckCount;
00249         float _pathStuckDistance;
00250 
00251 };
00252 
00253 #endif /* RTABMAP_H_ */
00254 
00255 } // namespace rtabmap


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:17