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 #include <pcl/pcl_config.h>
00046 
00047 namespace rtabmap {
00048 
00049 class Signature;
00050 class DBDriver;
00051 class VWDictionary;
00052 class VisualWord;
00053 class Feature2D;
00054 class Statistics;
00055 class Registration;
00056 class RegistrationInfo;
00057 class RegistrationIcp;
00058 class Stereo;
00059 class OccupancyGrid;
00060 
00061 class RTABMAP_EXP Memory
00062 {
00063 public:
00064         static const int kIdStart;
00065         static const int kIdVirtual;
00066         static const int kIdInvalid;
00067 
00068 public:
00069         Memory(const ParametersMap & parameters = ParametersMap());
00070         virtual ~Memory();
00071 
00072         virtual void parseParameters(const ParametersMap & parameters);
00073         virtual const ParametersMap & getParameters() const {return parameters_;}
00074         bool update(const SensorData & data,
00075                         Statistics * stats = 0);
00076         bool update(const SensorData & data,
00077                         const Transform & pose,
00078                         const cv::Mat & covariance,
00079                         const std::vector<float> & velocity = std::vector<float>(), // vx,vy,vz,vroll,vpitch,vyaw
00080                         Statistics * stats = 0);
00081         bool init(const std::string & dbUrl,
00082                         bool dbOverwritten = false,
00083                         const ParametersMap & parameters = ParametersMap(),
00084                         bool postInitClosingEvents = false);
00085         void close(bool databaseSaved = true, bool postInitClosingEvents = false, const std::string & ouputDatabasePath = "");
00086         std::map<int, float> computeLikelihood(const Signature * signature,
00087                         const std::list<int> & ids);
00088         int incrementMapId(std::map<int, int> * reducedIds = 0);
00089         void updateAge(int signatureId);
00090 
00091         std::list<int> forget(const std::set<int> & ignoredIds = std::set<int>());
00092         std::set<int> reactivateSignatures(const std::list<int> & ids, unsigned int maxLoaded, double & timeDbAccess);
00093 
00094         int cleanup();
00095         void saveStatistics(const Statistics & statistics);
00096         void savePreviewImage(const cv::Mat & image) const;
00097         cv::Mat loadPreviewImage() const;
00098         void saveOptimizedPoses(const std::map<int, Transform> & optimizedPoses, const Transform & lastlocalizationPose) const;
00099         std::map<int, Transform> loadOptimizedPoses(Transform * lastlocalizationPose) const;
00100         void save2DMap(const cv::Mat & map, float xMin, float yMin, float cellSize) const;
00101         cv::Mat load2DMap(float & xMin, float & yMin, float & cellSize) const;
00102         void saveOptimizedMesh(
00103                         const cv::Mat & cloud,
00104                         const std::vector<std::vector<std::vector<unsigned int> > > & polygons = std::vector<std::vector<std::vector<unsigned int> > >(),      // Textures -> polygons -> vertices
00105 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
00106                         const std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > & texCoords = std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > >(), // Textures -> uv coords for each vertex of the polygons
00107 #else
00108                         const std::vector<std::vector<Eigen::Vector2f> > & texCoords = std::vector<std::vector<Eigen::Vector2f> >(), // Textures -> uv coords for each vertex of the polygons
00109 #endif
00110                         const cv::Mat & textures = cv::Mat()) const; // concatenated textures (assuming square textures with all same size)
00111         cv::Mat loadOptimizedMesh(
00112                         std::vector<std::vector<std::vector<unsigned int> > > * polygons = 0,
00113 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
00114                         std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > * texCoords = 0,
00115 #else
00116                         std::vector<std::vector<Eigen::Vector2f> > * texCoords = 0,
00117 #endif
00118                         cv::Mat * textures = 0) const;
00119         void emptyTrash();
00120         void joinTrashThread();
00121         bool addLink(const Link & link, bool addInDatabase = false);
00122         void updateLink(const Link & link, bool updateInDatabase = false);
00123         void removeAllVirtualLinks();
00124         void removeVirtualLinks(int signatureId);
00125         std::map<int, int> getNeighborsId(
00126                         int signatureId,
00127                         int maxGraphDepth,
00128                         int maxCheckedInDatabase = -1,
00129                         bool incrementMarginOnLoop = false,
00130                         bool ignoreLoopIds = false,
00131                         bool ignoreIntermediateNodes = false,
00132                         bool ignoreLocalSpaceLoopIds = false,
00133                         const std::set<int> & nodesSet = std::set<int>(),
00134                         double * dbAccessTime = 0) const;
00135         std::map<int, float> getNeighborsIdRadius(
00136                         int signatureId,
00137                         float radius,
00138                         const std::map<int, Transform> & optimizedPoses,
00139                         int maxGraphDepth) const;
00140         void deleteLocation(int locationId, std::list<int> * deletedWords = 0);
00141         void saveLocationData(int locationId);
00142         void removeLink(int idA, int idB);
00143         void removeRawData(int id, bool image = true, bool scan = true, bool userData = true);
00144 
00145         //getters
00146         const std::map<int, double> & getWorkingMem() const {return _workingMem;}
00147         const std::set<int> & getStMem() const {return _stMem;}
00148         int getMaxStMemSize() const {return _maxStMemSize;}
00149         std::map<int, Link> getNeighborLinks(int signatureId,
00150                         bool lookInDatabase = false) const;
00151         std::map<int, Link> getLoopClosureLinks(int signatureId,
00152                         bool lookInDatabase = false) const;
00153         std::map<int, Link> getLinks(int signatureId,
00154                         bool lookInDatabase = false) const;
00155         std::multimap<int, Link> getAllLinks(bool lookInDatabase, bool ignoreNullLinks = true) const;
00156         bool isBinDataKept() const {return _binDataKept;}
00157         float getSimilarityThreshold() const {return _similarityThreshold;}
00158         std::map<int, int> getWeights() const;
00159         int getLastSignatureId() const;
00160         const Signature * getLastWorkingSignature() const;
00161         int getSignatureIdByLabel(const std::string & label, bool lookInDatabase = true) const;
00162         bool labelSignature(int id, const std::string & label);
00163         std::map<int, std::string> getAllLabels() const;
00171         bool setUserData(int id, const cv::Mat & data);
00172         int getDatabaseMemoryUsed() const; // in bytes
00173         std::string getDatabaseVersion() const;
00174         std::string getDatabaseUrl() const;
00175         double getDbSavingTime() const;
00176         Transform getOdomPose(int signatureId, bool lookInDatabase = false) const;
00177         Transform getGroundTruthPose(int signatureId, bool lookInDatabase = false) const;
00178         bool getNodeInfo(int signatureId,
00179                         Transform & odomPose,
00180                         int & mapId,
00181                         int & weight,
00182                         std::string & label,
00183                         double & stamp,
00184                         Transform & groundTruth,
00185                         std::vector<float> & velocity,
00186                         GPS & gps,
00187                         bool lookInDatabase = false) const;
00188         cv::Mat getImageCompressed(int signatureId) const;
00189         SensorData getNodeData(int nodeId, bool uncompressedData = false) const;
00190         void getNodeWords(int nodeId,
00191                         std::multimap<int, cv::KeyPoint> & words,
00192                         std::multimap<int, cv::Point3f> & words3,
00193                         std::multimap<int, cv::Mat> & wordsDescriptors);
00194         void getNodeCalibration(int nodeId,
00195                         std::vector<CameraModel> & models,
00196                         StereoCameraModel & stereoModel);
00197         SensorData getSignatureDataConst(int locationId, bool images = true, bool scan = true, bool userData = true, bool occupancyGrid = true) const;
00198         std::set<int> getAllSignatureIds() const;
00199         bool memoryChanged() const {return _memoryChanged;}
00200         bool isIncremental() const {return _incrementalMemory;}
00201         const Signature * getSignature(int id) const;
00202         bool isInSTM(int signatureId) const {return _stMem.find(signatureId) != _stMem.end();}
00203         bool isInWM(int signatureId) const {return _workingMem.find(signatureId) != _workingMem.end();}
00204         bool isInLTM(int signatureId) const {return !this->isInSTM(signatureId) && !this->isInWM(signatureId);}
00205         bool isIDsGenerated() const {return _generateIds;}
00206         int getLastGlobalLoopClosureId() const {return _lastGlobalLoopClosureId;}
00207         const Feature2D * getFeature2D() const {return _feature2D;}
00208         bool isGraphReduced() const {return _reduceGraph;}
00209 
00210         void dumpMemoryTree(const char * fileNameTree) const;
00211         virtual void dumpMemory(std::string directory) const;
00212         virtual void dumpSignatures(const char * fileNameSign, bool words3D) const;
00213         void dumpDictionary(const char * fileNameRef, const char * fileNameDesc) const;
00214 
00215         void generateGraph(const std::string & fileName, const std::set<int> & ids = std::set<int>());
00216 
00217         //keypoint stuff
00218         const VWDictionary * getVWDictionary() const;
00219 
00220         // RGB-D stuff
00221         void getMetricConstraints(
00222                         const std::set<int> & ids,
00223                         std::map<int, Transform> & poses,
00224                         std::multimap<int, Link> & links,
00225                         bool lookInDatabase = false);
00226 
00227         Transform computeTransform(Signature & fromS, Signature & toS, Transform guess, RegistrationInfo * info = 0, bool useKnownCorrespondencesIfPossible = false) const;
00228         Transform computeTransform(int fromId, int toId, Transform guess, RegistrationInfo * info = 0, bool useKnownCorrespondencesIfPossible = false);
00229         Transform computeIcpTransformMulti(
00230                         int newId,
00231                         int oldId,
00232                         const std::map<int, Transform> & poses,
00233                         RegistrationInfo * info = 0);
00234 
00235 private:
00236         void preUpdate();
00237         void addSignatureToStm(Signature * signature, const cv::Mat & covariance);
00238         void clear();
00239         void loadDataFromDb(bool postInitClosingEvents);
00240         void moveToTrash(Signature * s, bool keepLinkedToGraph = true, std::list<int> * deletedWords = 0);
00241 
00242         void moveSignatureToWMFromSTM(int id, int * reducedTo = 0);
00243         void addSignatureToWmFromLTM(Signature * signature);
00244         Signature * _getSignature(int id) const;
00245         std::list<Signature *> getRemovableSignatures(int count,
00246                         const std::set<int> & ignoredIds = std::set<int>());
00247         int getNextId();
00248         void initCountId();
00249         void rehearsal(Signature * signature, Statistics * stats = 0);
00250         bool rehearsalMerge(int oldId, int newId);
00251 
00252         const std::map<int, Signature*> & getSignatures() const {return _signatures;}
00253 
00254         void copyData(const Signature * from, Signature * to);
00255         Signature * createSignature(
00256                         const SensorData & data,
00257                         const Transform & pose,
00258                         Statistics * stats = 0);
00259 
00260         //keypoint stuff
00261         void disableWordsRef(int signatureId);
00262         void enableWordsRef(const std::list<int> & signatureIds);
00263         void cleanUnusedWords();
00264         int getNi(int signatureId) const;
00265 
00266 protected:
00267         DBDriver * _dbDriver;
00268 
00269 private:
00270         // parameters
00271         ParametersMap parameters_;
00272         float _similarityThreshold;
00273         bool _binDataKept;
00274         bool _rawDescriptorsKept;
00275         bool _saveDepth16Format;
00276         bool _notLinkedNodesKeptInDb;
00277         bool _saveIntermediateNodeData;
00278         bool _incrementalMemory;
00279         bool _reduceGraph;
00280         int _maxStMemSize;
00281         float _recentWmRatio;
00282         bool _transferSortingByWeightId;
00283         bool _idUpdatedToNewOneRehearsal;
00284         bool _generateIds;
00285         bool _badSignaturesIgnored;
00286         bool _mapLabelsAdded;
00287         bool _depthAsMask;
00288         int _imagePreDecimation;
00289         int _imagePostDecimation;
00290         bool _compressionParallelized;
00291         float _laserScanDownsampleStepSize;
00292         float _laserScanVoxelSize;
00293         int _laserScanNormalK;
00294         float _laserScanNormalRadius;
00295         bool _reextractLoopClosureFeatures;
00296         bool _localBundleOnLoopClosure;
00297         float _rehearsalMaxDistance;
00298         float _rehearsalMaxAngle;
00299         bool _rehearsalWeightIgnoredWhileMoving;
00300         bool _useOdometryFeatures;
00301         bool _createOccupancyGrid;
00302         int _visMaxFeatures;
00303         int _visCorType;
00304         bool _imagesAlreadyRectified;
00305         bool _rectifyOnlyFeatures;
00306         bool _covOffDiagonalIgnored;
00307 
00308         int _idCount;
00309         int _idMapCount;
00310         Signature * _lastSignature;
00311         int _lastGlobalLoopClosureId;
00312         bool _memoryChanged; // False by default, become true only when Memory::update() is called.
00313         bool _linksChanged; // False by default, become true when links are modified.
00314         int _signaturesAdded;
00315         GPS _gpsOrigin;
00316         std::vector<CameraModel> _rectCameraModels;
00317         StereoCameraModel _rectStereoCameraModel;
00318 
00319         std::map<int, Signature *> _signatures; // TODO : check if a signature is already added? although it is not supposed to occur...
00320         std::set<int> _stMem; // id
00321         std::map<int, double> _workingMem; // id,age
00322 
00323         //Keypoint stuff
00324         VWDictionary * _vwd;
00325         Feature2D * _feature2D;
00326         float _badSignRatio;;
00327         bool _tfIdfLikelihoodUsed;
00328         bool _parallelized;
00329 
00330         Registration * _registrationPipeline;
00331         RegistrationIcp * _registrationIcpMulti;
00332 
00333         OccupancyGrid * _occupancy;
00334 };
00335 
00336 } // namespace rtabmap
00337 
00338 #endif /* MEMORY_H_ */


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