Memory.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2014, 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 MEMORY_H_
00029 #define MEMORY_H_
00030 
00031 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
00032 
00033 #include "rtabmap/utilite/UEventsHandler.h"
00034 #include "rtabmap/core/Parameters.h"
00035 #include "rtabmap/core/SensorData.h"
00036 #include "rtabmap/core/Link.h"
00037 #include "rtabmap/core/Features2d.h"
00038 #include <typeinfo>
00039 #include <list>
00040 #include <map>
00041 #include <set>
00042 #include "rtabmap/utilite/UStl.h"
00043 #include <opencv2/core/core.hpp>
00044 #include <opencv2/features2d/features2d.hpp>
00045 
00046 namespace rtabmap {
00047 
00048 class Signature;
00049 class DBDriver;
00050 class GraphNode;
00051 class VWDictionary;
00052 class VisualWord;
00053 class Feature2D;
00054 class Statistics;
00055 
00056 class RTABMAP_EXP Memory
00057 {
00058 public:
00059         static const int kIdStart;
00060         static const int kIdVirtual;
00061         static const int kIdInvalid;
00062 
00063 public:
00064         Memory(const ParametersMap & parameters = ParametersMap());
00065         virtual ~Memory();
00066 
00067         virtual void parseParameters(const ParametersMap & parameters);
00068         bool update(const SensorData & data, Statistics * stats = 0);
00069         bool init(const std::string & dbUrl,
00070                         bool dbOverwritten = false,
00071                         const ParametersMap & parameters = ParametersMap(),
00072                         bool postInitClosingEvents = false);
00073         std::map<int, float> computeLikelihood(const Signature * signature,
00074                         const std::list<int> & ids);
00075         int incrementMapId();
00076         void updateAge(int signatureId);
00077 
00078         std::list<int> forget(const std::set<int> & ignoredIds = std::set<int>());
00079         std::set<int> reactivateSignatures(const std::list<int> & ids, unsigned int maxLoaded, double & timeDbAccess);
00080 
00081         std::list<int> cleanup(const std::list<int> & ignoredIds = std::list<int>());
00082         void emptyTrash();
00083         void joinTrashThread();
00084         bool addLink(int to, int from, const Transform & transform, Link::Type type, float rotVariance, float transVariance);
00085         void updateLink(int fromId, int toId, const Transform & transform, float rotVariance, float transVariance);
00086         void removeAllVirtualLinks();
00087         std::map<int, int> getNeighborsId(
00088                         int signatureId,
00089                         int maxGraphDepth,
00090                         int maxCheckedInDatabase = -1,
00091                         bool incrementMarginOnLoop = false,
00092                         bool ignoreLoopIds = false,
00093                         double * dbAccessTime = 0) const;
00094         std::map<int, float> getNeighborsIdRadius(
00095                         int signatureId,
00096                         float radius,
00097                         const std::map<int, Transform> & optimizedPoses,
00098                         int maxGraphDepth) const;
00099         void deleteLocation(int locationId, std::list<int> * deletedWords = 0);
00100         void removeLink(int idA, int idB);
00101 
00102         //getters
00103         const std::map<int, double> & getWorkingMem() const {return _workingMem;}
00104         const std::set<int> & getStMem() const {return _stMem;}
00105         int getMaxStMemSize() const {return _maxStMemSize;}
00106         std::map<int, Link> getNeighborLinks(int signatureId,
00107                         bool lookInDatabase = false) const;
00108         std::map<int, Link> getLoopClosureLinks(int signatureId,
00109                         bool lookInDatabase = false) const;
00110         bool isRawDataKept() const {return _rawDataKept;}
00111         bool isBinDataKept() const {return _binDataKept;}
00112         float getSimilarityThreshold() const {return _similarityThreshold;}
00113         std::map<int, int> getWeights() const;
00114         int getLastSignatureId() const;
00115         const Signature * getLastWorkingSignature() const;
00116         int getSignatureIdByLabel(const std::string & label, bool lookInDatabase = true) const;
00117         bool labelSignature(int id, const std::string & label);
00118         std::map<int, std::string> getAllLabels() const;
00119         bool setUserData(int id, const std::vector<unsigned char> & data);
00120         int getDatabaseMemoryUsed() const; // in bytes
00121         double getDbSavingTime() const;
00122         Transform getOdomPose(int signatureId, bool lookInDatabase = false) const;
00123         bool getNodeInfo(int signatureId,
00124                         Transform & odomPose,
00125                         int & mapId,
00126                         int & weight,
00127                         std::string & label,
00128                         double & stamp,
00129                         std::vector<unsigned char> & userData,
00130                         bool lookInDatabase = false) const;
00131         cv::Mat getImageCompressed(int signatureId) const;
00132         Signature getSignatureData(int locationId, bool uncompressedData = false);
00133         Signature getSignatureDataConst(int locationId) const;
00134         std::set<int> getAllSignatureIds() const;
00135         bool memoryChanged() const {return _memoryChanged;}
00136         bool isIncremental() const {return _incrementalMemory;}
00137         const Signature * getSignature(int id) const;
00138         bool isInSTM(int signatureId) const {return _stMem.find(signatureId) != _stMem.end();}
00139         bool isInWM(int signatureId) const {return _workingMem.find(signatureId) != _workingMem.end();}
00140         bool isInLTM(int signatureId) const {return !this->isInSTM(signatureId) && !this->isInWM(signatureId);}
00141         bool isIDsGenerated() const {return _generateIds;}
00142         int getLastGlobalLoopClosureId() const {return _lastGlobalLoopClosureId;}
00143         const Feature2D * getFeature2D() const {return _feature2D;}
00144 
00145         void setRoi(const std::string & roi);
00146 
00147         void dumpMemoryTree(const char * fileNameTree) const;
00148         virtual void dumpMemory(std::string directory) const;
00149         virtual void dumpSignatures(const char * fileNameSign, bool words3D) const;
00150         void dumpDictionary(const char * fileNameRef, const char * fileNameDesc) const;
00151 
00152         void generateGraph(const std::string & fileName, std::set<int> ids = std::set<int>());
00153         void createGraph(GraphNode * parent,
00154                         unsigned int maxDepth,
00155                         const std::set<int> & endIds = std::set<int>());
00156 
00157         //keypoint stuff
00158         const VWDictionary * getVWDictionary() const;
00159         Feature2D::Type getFeatureType() const {return _featureType;}
00160 
00161         // RGB-D stuff
00162         void getMetricConstraints(
00163                         const std::set<int> & ids,
00164                         std::map<int, Transform> & poses,
00165                         std::multimap<int, Link> & links,
00166                         bool lookInDatabase = false);
00167         float getBowInlierDistance() const {return _bowInlierDistance;}
00168         int getBowIterations() const {return _bowIterations;}
00169         int getBowMinInliers() const {return _bowMinInliers;}
00170         float getBowMaxDepth() const {return _bowMaxDepth;}
00171         bool getBowForce2D() const {return _bowForce2D;}
00172         Transform computeVisualTransform(int oldId, int newId, std::string * rejectedMsg = 0, int * inliers = 0, double * variance = 0) const;
00173         Transform computeVisualTransform(const Signature & oldS, const Signature & newS, std::string * rejectedMsg = 0, int * inliers = 0, double * variance = 0) const;
00174         Transform computeIcpTransform(int oldId, int newId, Transform guess, bool icp3D, std::string * rejectedMsg = 0, int * correspondences = 0, double * variance = 0, float * correspondencesRatio = 0);
00175         Transform computeIcpTransform(const Signature & oldS, const Signature & newS, Transform guess, bool icp3D, std::string * rejectedMsg = 0, int * correspondences = 0, double * variance = 0, float * correspondencesRatio = 0) const;
00176         Transform computeScanMatchingTransform(
00177                         int newId,
00178                         int oldId,
00179                         const std::map<int, Transform> & poses,
00180                         std::string * rejectedMsg = 0,
00181                         int * inliers = 0,
00182                         double * variance = 0);
00183 
00184 private:
00185         void preUpdate();
00186         void addSignatureToStm(Signature * signature, float poseRotVariance, float poseTransVariance);
00187         void clear();
00188         void moveToTrash(Signature * s, bool keepLinkedToGraph = true, std::list<int> * deletedWords = 0);
00189 
00190         void addSignatureToWm(Signature * signature);
00191         Signature * _getSignature(int id) const;
00192         std::list<Signature *> getRemovableSignatures(int count,
00193                         const std::set<int> & ignoredIds = std::set<int>());
00194         int getNextId();
00195         void initCountId();
00196         void rehearsal(Signature * signature, Statistics * stats = 0);
00197         bool rehearsalMerge(int oldId, int newId);
00198 
00199         const std::map<int, Signature*> & getSignatures() const {return _signatures;}
00200 
00201         void copyData(const Signature * from, Signature * to);
00202         Signature * createSignature(
00203                         const SensorData & data,
00204                         Statistics * stats = 0);
00205 
00206         //keypoint stuff
00207         void disableWordsRef(int signatureId);
00208         void enableWordsRef(const std::list<int> & signatureIds);
00209         void cleanUnusedWords();
00210         int getNi(int signatureId) const;
00211 
00212 protected:
00213         DBDriver * _dbDriver;
00214 
00215 private:
00216         // parameters
00217         float _similarityThreshold;
00218         bool _rawDataKept;
00219         bool _binDataKept;
00220         bool _notLinkedNodesKeptInDb;
00221         bool _incrementalMemory;
00222         int _maxStMemSize;
00223         float _recentWmRatio;
00224         bool _transferSortingByWeightId;
00225         bool _idUpdatedToNewOneRehearsal;
00226         bool _generateIds;
00227         bool _badSignaturesIgnored;
00228         int _imageDecimation;
00229         float _laserScanVoxelSize;
00230         bool _localSpaceLinksKeptInWM;
00231         float _rehearsalMaxDistance;
00232         float _rehearsalMaxAngle;
00233         bool _rehearsalWeightIgnoredWhileMoving;
00234 
00235         int _idCount;
00236         int _idMapCount;
00237         Signature * _lastSignature;
00238         int _lastGlobalLoopClosureId;
00239         bool _memoryChanged; // False by default, become true only when Memory::update() is called.
00240         bool _linksChanged; // False by default, become true when links are modified.
00241         int _signaturesAdded;
00242         bool _postInitClosingEvents;
00243 
00244         std::map<int, Signature *> _signatures; // TODO : check if a signature is already added? although it is not supposed to occur...
00245         std::set<int> _stMem; // id
00246         std::map<int, double> _workingMem; // id,age
00247 
00248         //Keypoint stuff
00249         VWDictionary * _vwd;
00250         Feature2D * _feature2D;
00251         Feature2D::Type _featureType;
00252         float _badSignRatio;;
00253         bool _tfIdfLikelihoodUsed;
00254         bool _parallelized;
00255         float _wordsMaxDepth; // 0=inf
00256         std::vector<float> _roiRatios; // size 4
00257 
00258         // RGBD-SLAM stuff
00259         int _bowMinInliers;
00260         float _bowInlierDistance;
00261         int _bowIterations;
00262         float _bowMaxDepth;
00263         bool _bowForce2D;
00264         bool _bowEpipolarGeometry;
00265         float _bowEpipolarGeometryVar;
00266         float _icpMaxTranslation;
00267         float _icpMaxRotation;
00268         int _icpDecimation;
00269         float _icpMaxDepth;
00270         float _icpVoxelSize;
00271         int _icpSamples;
00272         float _icpMaxCorrespondenceDistance;
00273         int _icpMaxIterations;
00274         float _icpCorrespondenceRatio;
00275         bool _icpPointToPlane;
00276         int _icpPointToPlaneNormalNeighbors;
00277         float _icp2MaxCorrespondenceDistance;
00278         int _icp2MaxIterations;
00279         float _icp2CorrespondenceRatio;
00280         float _icp2VoxelSize;
00281 
00282         // Stereo stuff
00283         int _stereoFlowWinSize;
00284         int _stereoFlowIterations;
00285         double _stereoFlowEpsilon;
00286         int _stereoFlowMaxLevel;
00287         float _stereoMaxSlope;
00288 
00289         int _subPixWinSize;
00290         int _subPixIterations;
00291         double _subPixEps;
00292 };
00293 
00294 } // namespace rtabmap
00295 
00296 #endif /* MEMORY_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Fri Aug 28 2015 12:51:32