00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #ifndef RTABMAP_H_
00029 #define RTABMAP_H_
00030
00031 #include "rtabmap/core/RtabmapExp.h"
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 namespace graph {
00051 class Optimizer;
00052 }
00053
00054 class RTABMAP_EXP Rtabmap
00055 {
00056 public:
00057 enum VhStrategy {kVhNone, kVhEpipolar, kVhUndef};
00058
00059 public:
00060 static std::string getVersion();
00061 static void readParameters(const std::string & configFile, ParametersMap & parameters);
00062 static void writeParameters(const std::string & configFile, const ParametersMap & parameters);
00063
00064 public:
00065 Rtabmap();
00066 virtual ~Rtabmap();
00067
00068 bool process(const cv::Mat & image, int id=0);
00069 bool process(const SensorData & data);
00070
00071 void init(const ParametersMap & parameters, const std::string & databasePath = "");
00072 void init(const std::string & configFile = "", const std::string & databasePath = "");
00073
00074 void close();
00075
00076 const std::string & getWorkingDir() const {return _wDir;}
00077 int getLoopClosureId() const {return _loopClosureHypothesis.first;}
00078 float getLoopClosureValue() const {return _loopClosureHypothesis.second;}
00079 int getHighestHypothesisId() const {return _highestHypothesis.first;}
00080 float getHighestHypothesisValue() const {return _highestHypothesis.second;}
00081 int getLastLocationId() const;
00082 std::list<int> getWM() const;
00083 std::set<int> getSTM() const;
00084 int getWMSize() const;
00085 int getSTMSize() const;
00086 std::map<int, int> getWeights() const;
00087 int getTotalMemSize() const;
00088 double getLastProcessTime() const {return _lastProcessTime;};
00089 std::multimap<int, cv::KeyPoint> getWords(int locationId) const;
00090 bool isInSTM(int locationId) const;
00091 bool isIDsGenerated() const;
00092 const Statistics & getStatistics() const;
00093
00094 const std::map<int, Transform> & getLocalOptimizedPoses() const {return _optimizedPoses;}
00095 Transform getPose(int locationId) const;
00096 Transform getMapCorrection() const {return _mapCorrection;}
00097 const Memory * getMemory() const {return _memory;}
00098 float getGoalReachedRadius() const {return _goalReachedRadius;}
00099 float getLocalRadius() const {return _localRadius;}
00100
00101 float getTimeThreshold() const {return _maxTimeAllowed;}
00102 void setTimeThreshold(float maxTimeAllowed);
00103
00104 int triggerNewMap();
00105 bool labelLocation(int id, const std::string & label);
00106 bool setUserData(int id, const std::vector<unsigned char> & data);
00107 void generateDOTGraph(const std::string & path, int id=0, int margin=5);
00108 void generateTOROGraph(const std::string & path, bool optimized, bool global);
00109 void resetMemory();
00110 void dumpPrediction() const;
00111 void dumpData() const;
00112 void parseParameters(const ParametersMap & parameters);
00113 void setWorkingDirectory(std::string path);
00114 void rejectLoopClosure(int oldId, int newId);
00115 void get3DMap(std::map<int, Signature> & signatures,
00116 std::map<int, Transform> & poses,
00117 std::multimap<int, Link> & constraints,
00118 std::map<int, int> & mapIds,
00119 std::map<int, double> & stamps,
00120 std::map<int, std::string> & labels,
00121 std::map<int, std::vector<unsigned char> > & userDatas,
00122 bool optimized,
00123 bool global) const;
00124 void getGraph(std::map<int, Transform> & poses,
00125 std::multimap<int, Link> & constraints,
00126 std::map<int, int> & mapIds,
00127 std::map<int, double> & stamps,
00128 std::map<int, std::string> & labels,
00129 std::map<int, std::vector<unsigned char> > & userDatas,
00130 bool optimized,
00131 bool global);
00132 void clearPath();
00133 bool computePath(int targetNode, bool global);
00134 bool computePath(const Transform & targetPose, bool global);
00135 const std::vector<std::pair<int, Transform> > & getPath() const {return _path;}
00136 std::vector<std::pair<int, Transform> > getPathNextPoses() const;
00137 std::vector<int> getPathNextNodes() const;
00138 int getPathCurrentGoalId() const;
00139 const Transform & getPathTransformToGoal() const {return _pathTransformToGoal;}
00140
00141 std::map<int, Transform> getForwardWMPoses(int fromId, int maxNearestNeighbors, float radius, int maxDiffID) const;
00142 std::list<std::map<int, Transform> > getPaths(std::map<int, Transform> poses) const;
00143 void adjustLikelihood(std::map<int, float> & likelihood) const;
00144 std::pair<int, float> selectHypothesis(const std::map<int, float> & posterior,
00145 const std::map<int, float> & likelihood) const;
00146
00147 private:
00148 void optimizeCurrentMap(int id,
00149 bool lookInDatabase,
00150 std::map<int, Transform> & optimizedPoses,
00151 std::multimap<int, Link> * constraints = 0) const;
00152 std::map<int, Transform> optimizeGraph(
00153 int fromId,
00154 const std::set<int> & ids,
00155 bool lookInDatabase,
00156 std::multimap<int, Link> * constraints = 0) const;
00157 void updateGoalIndex();
00158 bool computePath(int targetNode, std::map<int, Transform> nodes, const std::multimap<int, rtabmap::Link> & constraints);
00159
00160 void setupLogFiles(bool overwrite = false);
00161 void flushStatisticLogs();
00162
00163 private:
00164
00165 bool _publishStats;
00166 bool _publishLastSignature;
00167 bool _publishPdf;
00168 bool _publishLikelihood;
00169 float _maxTimeAllowed;
00170 unsigned int _maxMemoryAllowed;
00171 float _loopThr;
00172 float _loopRatio;
00173 unsigned int _maxRetrieved;
00174 unsigned int _maxLocalRetrieved;
00175 bool _statisticLogsBufferedInRAM;
00176 bool _statisticLogged;
00177 bool _statisticLoggedHeaders;
00178 bool _rgbdSlamMode;
00179 float _rgbdLinearUpdate;
00180 float _rgbdAngularUpdate;
00181 float _newMapOdomChangeDistance;
00182 int _globalLoopClosureIcpType;
00183 bool _poseScanMatching;
00184 bool _localLoopClosureDetectionTime;
00185 bool _localLoopClosureDetectionSpace;
00186 float _localRadius;
00187 float _localImmunizationRatio;
00188 int _localDetectMaxGraphDepth;
00189 float _localPathFilteringRadius;
00190 bool _localPathOdomPosesUsed;
00191 std::string _databasePath;
00192 bool _optimizeFromGraphEnd;
00193 bool _reextractLoopClosureFeatures;
00194 int _reextractNNType;
00195 float _reextractNNDR;
00196 int _reextractFeatureType;
00197 int _reextractMaxWords;
00198 bool _startNewMapOnLoopClosure;
00199 float _goalReachedRadius;
00200 bool _planVirtualLinks;
00201 bool _goalsSavedInUserData;
00202
00203 std::pair<int, float> _loopClosureHypothesis;
00204 std::pair<int, float> _highestHypothesis;
00205 double _lastProcessTime;
00206
00207
00208
00209 EpipolarGeometry * _epipolarGeometry;
00210 BayesFilter * _bayesFilter;
00211 graph::Optimizer * _graphOptimizer;
00212 ParametersMap _modifiedParameters;
00213
00214 Memory * _memory;
00215
00216 FILE* _foutFloat;
00217 FILE* _foutInt;
00218 std::list<std::string> _bufferedLogsF;
00219 std::list<std::string> _bufferedLogsI;
00220
00221 Statistics statistics_;
00222
00223 std::string _wDir;
00224
00225 std::map<int, Transform> _optimizedPoses;
00226 std::multimap<int, Link> _constraints;
00227 Transform _mapCorrection;
00228 Transform _mapTransform;
00229 Transform _lastLocalizationPose;
00230
00231
00232 std::vector<std::pair<int,Transform> > _path;
00233 unsigned int _pathCurrentIndex;
00234 unsigned int _pathGoalIndex;
00235 Transform _pathTransformToGoal;
00236
00237 };
00238
00239 #endif
00240
00241 }