Memory.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 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 VWDictionary;
00051 class VisualWord;
00052 class Feature2D;
00053 class Statistics;
00054 class Registration;
00055 class RegistrationInfo;
00056 class RegistrationIcp;
00057 class Stereo;
00058 
00059 class RTABMAP_EXP Memory
00060 {
00061 public:
00062         static const int kIdStart;
00063         static const int kIdVirtual;
00064         static const int kIdInvalid;
00065 
00066 public:
00067         Memory(const ParametersMap & parameters = ParametersMap());
00068         virtual ~Memory();
00069 
00070         virtual void parseParameters(const ParametersMap & parameters);
00071         virtual const ParametersMap & getParameters() const {return parameters_;}
00072         bool update(const SensorData & data,
00073                         Statistics * stats = 0);
00074         bool update(const SensorData & data,
00075                         const Transform & pose,
00076                         const cv::Mat & covariance,
00077                         Statistics * stats = 0);
00078         bool init(const std::string & dbUrl,
00079                         bool dbOverwritten = false,
00080                         const ParametersMap & parameters = ParametersMap(),
00081                         bool postInitClosingEvents = false);
00082         void close(bool databaseSaved = true, bool postInitClosingEvents = false);
00083         std::map<int, float> computeLikelihood(const Signature * signature,
00084                         const std::list<int> & ids);
00085         int incrementMapId(std::map<int, int> * reducedIds = 0);
00086         void updateAge(int signatureId);
00087 
00088         std::list<int> forget(const std::set<int> & ignoredIds = std::set<int>());
00089         std::set<int> reactivateSignatures(const std::list<int> & ids, unsigned int maxLoaded, double & timeDbAccess);
00090 
00091         int cleanup();
00092         void emptyTrash();
00093         void joinTrashThread();
00094         bool addLink(const Link & link, bool addInDatabase = false);
00095         void updateLink(int fromId, int toId, const Transform & transform, float rotVariance, float transVariance);
00096         void updateLink(int fromId, int toId, const Transform & transform, const cv::Mat & covariance);
00097         void removeAllVirtualLinks();
00098         void removeVirtualLinks(int signatureId);
00099         std::map<int, int> getNeighborsId(
00100                         int signatureId,
00101                         int maxGraphDepth,
00102                         int maxCheckedInDatabase = -1,
00103                         bool incrementMarginOnLoop = false,
00104                         bool ignoreLoopIds = false,
00105                         bool ignoreIntermediateNodes = false,
00106                         double * dbAccessTime = 0) const;
00107         std::map<int, float> getNeighborsIdRadius(
00108                         int signatureId,
00109                         float radius,
00110                         const std::map<int, Transform> & optimizedPoses,
00111                         int maxGraphDepth) const;
00112         void deleteLocation(int locationId, std::list<int> * deletedWords = 0);
00113         void removeLink(int idA, int idB);
00114         void removeRawData(int id, bool image = true, bool scan = true, bool userData = true);
00115 
00116         //getters
00117         const std::map<int, double> & getWorkingMem() const {return _workingMem;}
00118         const std::set<int> & getStMem() const {return _stMem;}
00119         int getMaxStMemSize() const {return _maxStMemSize;}
00120         std::map<int, Link> getNeighborLinks(int signatureId,
00121                         bool lookInDatabase = false) const;
00122         std::map<int, Link> getLoopClosureLinks(int signatureId,
00123                         bool lookInDatabase = false) const;
00124         std::map<int, Link> getLinks(int signatureId,
00125                         bool lookInDatabase = false) const;
00126         std::multimap<int, Link> getAllLinks(bool lookInDatabase, bool ignoreNullLinks = true) const;
00127         bool isBinDataKept() const {return _binDataKept;}
00128         float getSimilarityThreshold() const {return _similarityThreshold;}
00129         std::map<int, int> getWeights() const;
00130         int getLastSignatureId() const;
00131         const Signature * getLastWorkingSignature() const;
00132         int getSignatureIdByLabel(const std::string & label, bool lookInDatabase = true) const;
00133         bool labelSignature(int id, const std::string & label);
00134         std::map<int, std::string> getAllLabels() const;
00135         bool setUserData(int id, const cv::Mat & data);
00136         int getDatabaseMemoryUsed() const; // in bytes
00137         std::string getDatabaseVersion() const;
00138         double getDbSavingTime() const;
00139         Transform getOdomPose(int signatureId, bool lookInDatabase = false) const;
00140         Transform getGroundTruthPose(int signatureId, bool lookInDatabase = false) const;
00141         bool getNodeInfo(int signatureId,
00142                         Transform & odomPose,
00143                         int & mapId,
00144                         int & weight,
00145                         std::string & label,
00146                         double & stamp,
00147                         Transform & groundTruth,
00148                         bool lookInDatabase = false) const;
00149         cv::Mat getImageCompressed(int signatureId) const;
00150         SensorData getNodeData(int nodeId, bool uncompressedData = false) const;
00151         void getNodeWords(int nodeId,
00152                         std::multimap<int, cv::KeyPoint> & words,
00153                         std::multimap<int, cv::Point3f> & words3,
00154                         std::multimap<int, cv::Mat> & wordsDescriptors);
00155         void getNodeCalibration(int nodeId,
00156                         std::vector<CameraModel> & models,
00157                         StereoCameraModel & stereoModel);
00158         SensorData getSignatureDataConst(int locationId) const;
00159         std::set<int> getAllSignatureIds() const;
00160         bool memoryChanged() const {return _memoryChanged;}
00161         bool isIncremental() const {return _incrementalMemory;}
00162         const Signature * getSignature(int id) const;
00163         bool isInSTM(int signatureId) const {return _stMem.find(signatureId) != _stMem.end();}
00164         bool isInWM(int signatureId) const {return _workingMem.find(signatureId) != _workingMem.end();}
00165         bool isInLTM(int signatureId) const {return !this->isInSTM(signatureId) && !this->isInWM(signatureId);}
00166         bool isIDsGenerated() const {return _generateIds;}
00167         int getLastGlobalLoopClosureId() const {return _lastGlobalLoopClosureId;}
00168         const Feature2D * getFeature2D() const {return _feature2D;}
00169         bool isGraphReduced() const {return _reduceGraph;}
00170 
00171         void dumpMemoryTree(const char * fileNameTree) const;
00172         virtual void dumpMemory(std::string directory) const;
00173         virtual void dumpSignatures(const char * fileNameSign, bool words3D) const;
00174         void dumpDictionary(const char * fileNameRef, const char * fileNameDesc) const;
00175 
00176         void generateGraph(const std::string & fileName, const std::set<int> & ids = std::set<int>());
00177 
00178         //keypoint stuff
00179         const VWDictionary * getVWDictionary() const;
00180 
00181         // RGB-D stuff
00182         void getMetricConstraints(
00183                         const std::set<int> & ids,
00184                         std::map<int, Transform> & poses,
00185                         std::multimap<int, Link> & links,
00186                         bool lookInDatabase = false);
00187 
00188         Transform computeTransform(Signature & fromS, Signature & toS, Transform guess, RegistrationInfo * info = 0) const;
00189         Transform computeTransform(int fromId, int toId, Transform guess, RegistrationInfo * info = 0);
00190         Transform computeIcpTransform(int fromId, int toId, Transform guess, RegistrationInfo * info = 0);
00191         Transform computeIcpTransformMulti(
00192                         int newId,
00193                         int oldId,
00194                         const std::map<int, Transform> & poses,
00195                         RegistrationInfo * info = 0);
00196 
00197 private:
00198         void preUpdate();
00199         void addSignatureToStm(Signature * signature, const cv::Mat & covariance);
00200         void clear();
00201         void moveToTrash(Signature * s, bool keepLinkedToGraph = true, std::list<int> * deletedWords = 0);
00202 
00203         void moveSignatureToWMFromSTM(int id, int * reducedTo = 0);
00204         void addSignatureToWmFromLTM(Signature * signature);
00205         Signature * _getSignature(int id) const;
00206         std::list<Signature *> getRemovableSignatures(int count,
00207                         const std::set<int> & ignoredIds = std::set<int>());
00208         int getNextId();
00209         void initCountId();
00210         void rehearsal(Signature * signature, Statistics * stats = 0);
00211         bool rehearsalMerge(int oldId, int newId);
00212 
00213         const std::map<int, Signature*> & getSignatures() const {return _signatures;}
00214 
00215         void copyData(const Signature * from, Signature * to);
00216         Signature * createSignature(
00217                         const SensorData & data,
00218                         const Transform & pose,
00219                         Statistics * stats = 0);
00220 
00221         //keypoint stuff
00222         void disableWordsRef(int signatureId);
00223         void enableWordsRef(const std::list<int> & signatureIds);
00224         void cleanUnusedWords();
00225         int getNi(int signatureId) const;
00226 
00227 protected:
00228         DBDriver * _dbDriver;
00229 
00230 private:
00231         // parameters
00232         ParametersMap parameters_;
00233         float _similarityThreshold;
00234         bool _binDataKept;
00235         bool _rawDescriptorsKept;
00236         bool _saveDepth16Format;
00237         bool _notLinkedNodesKeptInDb;
00238         bool _incrementalMemory;
00239         bool _reduceGraph;
00240         int _maxStMemSize;
00241         float _recentWmRatio;
00242         bool _transferSortingByWeightId;
00243         bool _idUpdatedToNewOneRehearsal;
00244         bool _generateIds;
00245         bool _badSignaturesIgnored;
00246         bool _mapLabelsAdded;
00247         int _imagePreDecimation;
00248         int _imagePostDecimation;
00249         float _laserScanDownsampleStepSize;
00250         bool _reextractLoopClosureFeatures;
00251         float _rehearsalMaxDistance;
00252         float _rehearsalMaxAngle;
00253         bool _rehearsalWeightIgnoredWhileMoving;
00254         bool _useOdometryFeatures;
00255 
00256         int _idCount;
00257         int _idMapCount;
00258         Signature * _lastSignature;
00259         int _lastGlobalLoopClosureId;
00260         bool _memoryChanged; // False by default, become true only when Memory::update() is called.
00261         bool _linksChanged; // False by default, become true when links are modified.
00262         int _signaturesAdded;
00263 
00264         std::map<int, Signature *> _signatures; // TODO : check if a signature is already added? although it is not supposed to occur...
00265         std::set<int> _stMem; // id
00266         std::map<int, double> _workingMem; // id,age
00267 
00268         //Keypoint stuff
00269         VWDictionary * _vwd;
00270         Feature2D * _feature2D;
00271         float _badSignRatio;;
00272         bool _tfIdfLikelihoodUsed;
00273         bool _parallelized;
00274 
00275         Registration * _registrationPipeline;
00276         RegistrationIcp * _registrationIcp;
00277 };
00278 
00279 } // namespace rtabmap
00280 
00281 #endif /* MEMORY_H_ */


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