DBDriver.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 DBDRIVER_H_
00029 #define DBDRIVER_H_
00030 
00031 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
00032 
00033 #include <string>
00034 #include <list>
00035 #include <map>
00036 #include <set>
00037 #include <opencv2/core/core.hpp>
00038 #include "rtabmap/utilite/UMutex.h"
00039 #include "rtabmap/utilite/UThreadNode.h"
00040 #include "rtabmap/core/Parameters.h"
00041 #include "rtabmap/core/SensorData.h"
00042 #include <rtabmap/core/Statistics.h>
00043 
00044 #include <rtabmap/core/Transform.h>
00045 #include <rtabmap/core/Link.h>
00046 
00047 namespace rtabmap {
00048 
00049 class Signature;
00050 class VWDictionary;
00051 class VisualWord;
00052 
00053 // Todo This class needs a refactoring, the _dbSafeAccessMutex problem when the trash is emptying (transaction)
00054 // "Of course, it has always been the case and probably always will be
00055 //that you cannot use the same sqlite3 connection in two or more
00056 //threads at the same time.  You can use different sqlite3 connections
00057 //at the same time in different threads, or you can move the same
00058 //sqlite3 connection across threads (subject to the constraints above)
00059 //but never, never try to use the same connection simultaneously in
00060 //two or more threads."
00061 //
00062 class RTABMAP_EXP DBDriver : public UThreadNode
00063 {
00064 public:
00065         static DBDriver * create(const ParametersMap & parameters = ParametersMap());
00066 
00067 public:
00068         virtual ~DBDriver();
00069 
00070         virtual void parseParameters(const ParametersMap & parameters);
00071         virtual bool isInMemory() const {return _url.empty();}
00072         const std::string & getUrl() const {return _url;}
00073 
00074         void beginTransaction() const;
00075         void commit() const;
00076 
00077         void asyncSave(Signature * s); //ownership transferred
00078         void asyncSave(VisualWord * vw); //ownership transferred
00079         void emptyTrashes(bool async = false);
00080         double getEmptyTrashesTime() const {return _emptyTrashesTime;}
00081         void setTimestampUpdateEnabled(bool enabled) {_timestampUpdate = enabled;} // used on Update Signature and Word queries
00082 
00083         // Warning: the following functions don't look in the trash, direct database modifications
00084         void generateGraph(
00085                         const std::string & fileName,
00086                         const std::set<int> & ids = std::set<int>(),
00087                         const std::map<int, Signature *> & otherSignatures = std::map<int, Signature *>());
00088         void addLink(const Link & link);
00089         void removeLink(int from, int to);
00090         void updateLink(const Link & link);
00091         void updateOccupancyGrid(
00092                                 int nodeId,
00093                                 const cv::Mat & ground,
00094                                 const cv::Mat & obstacles,
00095                                 const cv::Mat & empty,
00096                                 float cellSize,
00097                                 const cv::Point3f & viewpoint);
00098         void updateDepthImage(int nodeId, const cv::Mat & image);
00099 
00100 public:
00101         void addInfoAfterRun(int stMemSize, int lastSignAdded, int processMemUsed, int databaseMemUsed, int dictionarySize, const ParametersMap & parameters) const;
00102         void addStatistics(const Statistics & statistics) const;
00103         void savePreviewImage(const cv::Mat & image) const;
00104         cv::Mat loadPreviewImage() const;
00105         void saveOptimizedPoses(const std::map<int, Transform> & optimizedPoses, const Transform & lastlocalizationPose) const;
00106         std::map<int, Transform> loadOptimizedPoses(Transform * lastlocalizationPose) const;
00107         void save2DMap(const cv::Mat & map, float xMin, float yMin, float cellSize) const;
00108         cv::Mat load2DMap(float & xMin, float & yMin, float & cellSize) const;
00109         void saveOptimizedMesh(
00110                         const cv::Mat & cloud,
00111                         const std::vector<std::vector<std::vector<unsigned int> > > & polygons = std::vector<std::vector<std::vector<unsigned int> > >(),      // Textures -> polygons -> vertices
00112 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
00113                         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
00114 #else
00115                         const std::vector<std::vector<Eigen::Vector2f> > & texCoords = std::vector<std::vector<Eigen::Vector2f> >(), // Textures -> uv coords for each vertex of the polygons
00116 #endif
00117                         const cv::Mat & textures = cv::Mat()) const; // concatenated textures (assuming square textures with all same size);
00118         cv::Mat loadOptimizedMesh(
00119                         std::vector<std::vector<std::vector<unsigned int> > > * polygons = 0,
00120 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
00121                         std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > * texCoords = 0,
00122 #else
00123                         std::vector<std::vector<Eigen::Vector2f> > * texCoords = 0,
00124 #endif
00125                         cv::Mat * textures = 0) const;
00126 
00127 public:
00128         // Mutex-protected methods of abstract versions below
00129 
00130         bool openConnection(const std::string & url, bool overwritten = false);
00131         void closeConnection(bool save = true, const std::string & outputUrl = "");
00132         bool isConnected() const;
00133         long getMemoryUsed() const; // In bytes
00134         std::string getDatabaseVersion() const;
00135         long getNodesMemoryUsed() const;
00136         long getLinksMemoryUsed() const;
00137         long getImagesMemoryUsed() const;
00138         long getDepthImagesMemoryUsed() const;
00139         long getCalibrationsMemoryUsed() const;
00140         long getGridsMemoryUsed() const;
00141         long getLaserScansMemoryUsed() const;
00142         long getUserDataMemoryUsed() const;
00143         long getWordsMemoryUsed() const;
00144         long getFeaturesMemoryUsed() const;
00145         long getStatisticsMemoryUsed() const;
00146         int getLastNodesSize() const; // working memory
00147         int getLastDictionarySize() const; // working memory
00148         int getTotalNodesSize() const;
00149         int getTotalDictionarySize() const;
00150         ParametersMap getLastParameters() const;
00151         std::map<std::string, float> getStatistics(int nodeId, double & stamp, std::vector<int> * wmState=0) const;
00152         std::map<int, std::pair<std::map<std::string, float>, double> > getAllStatistics() const;
00153         std::map<int, std::vector<int> > getAllStatisticsWmStates() const;
00154 
00155         void executeNoResult(const std::string & sql) const;
00156 
00157         // Load objects
00158         void load(VWDictionary * dictionary, bool lastStateOnly = true) const;
00159         void loadLastNodes(std::list<Signature *> & signatures) const;
00160         void loadSignatures(const std::list<int> & ids, std::list<Signature *> & signatures, std::set<int> * loadedFromTrash = 0);
00161         void loadWords(const std::set<int> & wordIds, std::list<VisualWord *> & vws);
00162 
00163         // Specific queries...
00164         void loadNodeData(std::list<Signature *> & signatures, bool images = true, bool scan = true, bool userData = true, bool occupancyGrid = true) const;
00165         void getNodeData(int signatureId, SensorData & data, bool images = true, bool scan = true, bool userData = true, bool occupancyGrid = true) const;
00166         bool getCalibration(int signatureId, std::vector<CameraModel> & models, StereoCameraModel & stereoModel) const;
00167         bool getLaserScanInfo(int signatureId, LaserScan & info) const;
00168         bool getNodeInfo(int signatureId, Transform & pose, int & mapId, int & weight, std::string & label, double & stamp, Transform & groundTruthPose, std::vector<float> & velocity, GPS & gps) const;
00169         void loadLinks(int signatureId, std::map<int, Link> & links, Link::Type type = Link::kUndef) const;
00170         void getWeight(int signatureId, int & weight) const;
00171         void getAllNodeIds(std::set<int> & ids, bool ignoreChildren = false, bool ignoreBadSignatures = false) const;
00172         void getAllLinks(std::multimap<int, Link> & links, bool ignoreNullLinks = true) const;
00173         void getLastNodeId(int & id) const;
00174         void getLastWordId(int & id) const;
00175         void getInvertedIndexNi(int signatureId, int & ni) const;
00176         void getNodeIdByLabel(const std::string & label, int & id) const;
00177         void getAllLabels(std::map<int, std::string> & labels) const;
00178 
00179 protected:
00180         DBDriver(const ParametersMap & parameters = ParametersMap());
00181 
00182         virtual bool connectDatabaseQuery(const std::string & url, bool overwritten = false) = 0;
00183         virtual void disconnectDatabaseQuery(bool save = true, const std::string & outputUrl = "") = 0;
00184         virtual bool isConnectedQuery() const = 0;
00185         virtual long getMemoryUsedQuery() const = 0; // In bytes
00186         virtual bool getDatabaseVersionQuery(std::string & version) const = 0;
00187         virtual long getNodesMemoryUsedQuery() const = 0;
00188         virtual long getLinksMemoryUsedQuery() const = 0;
00189         virtual long getImagesMemoryUsedQuery() const = 0;
00190         virtual long getDepthImagesMemoryUsedQuery() const = 0;
00191         virtual long getCalibrationsMemoryUsedQuery() const = 0;
00192         virtual long getGridsMemoryUsedQuery() const = 0;
00193         virtual long getLaserScansMemoryUsedQuery() const = 0;
00194         virtual long getUserDataMemoryUsedQuery() const = 0;
00195         virtual long getWordsMemoryUsedQuery() const = 0;
00196         virtual long getFeaturesMemoryUsedQuery() const = 0;
00197         virtual long getStatisticsMemoryUsedQuery() const = 0;
00198         virtual int getLastNodesSizeQuery() const = 0;
00199         virtual int getLastDictionarySizeQuery() const = 0;
00200         virtual int getTotalNodesSizeQuery() const = 0;
00201         virtual int getTotalDictionarySizeQuery() const = 0;
00202         virtual ParametersMap getLastParametersQuery() const = 0;
00203         virtual std::map<std::string, float> getStatisticsQuery(int nodeId, double & stamp, std::vector<int> * wmState) const = 0;
00204         virtual std::map<int, std::pair<std::map<std::string, float>, double> > getAllStatisticsQuery() const = 0;
00205         virtual std::map<int, std::vector<int> > getAllStatisticsWmStatesQuery() const = 0;
00206 
00207         virtual void executeNoResultQuery(const std::string & sql) const = 0;
00208 
00209         virtual void getWeightQuery(int signatureId, int & weight) const = 0;
00210 
00211         virtual void saveQuery(const std::list<Signature *> & signatures) = 0;
00212         virtual void saveQuery(const std::list<VisualWord *> & words) const = 0;
00213         virtual void updateQuery(const std::list<Signature *> & signatures, bool updateTimestamp) const = 0;
00214         virtual void updateQuery(const std::list<VisualWord *> & words, bool updateTimestamp) const = 0;
00215 
00216         virtual void addLinkQuery(const Link & link) const = 0;
00217         virtual void updateLinkQuery(const Link & link) const = 0;
00218 
00219         virtual void updateOccupancyGridQuery(
00220                                 int nodeId,
00221                                 const cv::Mat & ground,
00222                                 const cv::Mat & obstacles,
00223                                 const cv::Mat & empty,
00224                                 float cellSize,
00225                                 const cv::Point3f & viewpoint) const = 0;
00226 
00227         virtual void updateDepthImageQuery(
00228                                         int nodeId,
00229                                         const cv::Mat & image) const = 0;
00230 
00231         virtual void addStatisticsQuery(const Statistics & statistics) const = 0;
00232         virtual void savePreviewImageQuery(const cv::Mat & image) const = 0;
00233         virtual cv::Mat loadPreviewImageQuery() const = 0;
00234         virtual void saveOptimizedPosesQuery(const std::map<int, Transform> & optimizedPoses, const Transform & lastlocalizationPose) const = 0;
00235         virtual std::map<int, Transform> loadOptimizedPosesQuery(Transform * lastlocalizationPose) const = 0;
00236         virtual void save2DMapQuery(const cv::Mat & map, float xMin, float yMin, float cellSize) const = 0;
00237         virtual cv::Mat load2DMapQuery(float & xMin, float & yMin, float & cellSize) const = 0;
00238         virtual void saveOptimizedMeshQuery(
00239                                 const cv::Mat & cloud,
00240                                 const std::vector<std::vector<std::vector<unsigned int> > > & polygons,
00241 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
00242                                 const std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > & texCoords,
00243 #else
00244                                 const std::vector<std::vector<Eigen::Vector2f> > & texCoords,
00245 #endif
00246                                 const cv::Mat & textures) const = 0;
00247         virtual cv::Mat loadOptimizedMeshQuery(
00248                                 std::vector<std::vector<std::vector<unsigned int> > > * polygons,
00249 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
00250                                 std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > * texCoords,
00251 #else
00252                                 std::vector<std::vector<Eigen::Vector2f> > * texCoords,
00253 #endif
00254                                 cv::Mat * textures) const = 0;
00255 
00256         // Load objects
00257         virtual void loadQuery(VWDictionary * dictionary, bool lastStateOnly = true) const = 0;
00258         virtual void loadLastNodesQuery(std::list<Signature *> & signatures) const = 0;
00259         virtual void loadSignaturesQuery(const std::list<int> & ids, std::list<Signature *> & signatures) const = 0;
00260         virtual void loadWordsQuery(const std::set<int> & wordIds, std::list<VisualWord *> & vws) const = 0;
00261         virtual void loadLinksQuery(int signatureId, std::map<int, Link> & links, Link::Type type = Link::kUndef) const = 0;
00262 
00263         virtual void loadNodeDataQuery(std::list<Signature *> & signatures, bool images=true, bool scan=true, bool userData=true, bool occupancyGrid=true) const = 0;
00264         virtual bool getCalibrationQuery(int signatureId, std::vector<CameraModel> & models, StereoCameraModel & stereoModel) const = 0;
00265         virtual bool getLaserScanInfoQuery(int signatureId, LaserScan & info) const = 0;
00266         virtual bool getNodeInfoQuery(int signatureId, Transform & pose, int & mapId, int & weight, std::string & label, double & stamp, Transform & groundTruthPose, std::vector<float> & velocity, GPS & gps) const = 0;
00267         virtual void getAllNodeIdsQuery(std::set<int> & ids, bool ignoreChildren, bool ignoreBadSignatures) const = 0;
00268         virtual void getAllLinksQuery(std::multimap<int, Link> & links, bool ignoreNullLinks) const = 0;
00269         virtual void getLastIdQuery(const std::string & tableName, int & id) const = 0;
00270         virtual void getInvertedIndexNiQuery(int signatureId, int & ni) const = 0;
00271         virtual void getNodeIdByLabelQuery(const std::string & label, int & id) const = 0;
00272         virtual void getAllLabelsQuery(std::map<int, std::string> & labels) const = 0;
00273 
00274 private:
00275         //non-abstract methods
00276         void saveOrUpdate(const std::vector<Signature *> & signatures);
00277         void saveOrUpdate(const std::vector<VisualWord *> & words) const;
00278 
00279         //thread stuff
00280         virtual void mainLoop();
00281 
00282 private:
00283         UMutex _transactionMutex;
00284         std::map<int, Signature *> _trashSignatures;//<id, Signature*>
00285         std::map<int, VisualWord *> _trashVisualWords; //<id, VisualWord*>
00286         UMutex _trashesMutex;
00287         UMutex _dbSafeAccessMutex;
00288         USemaphore _addSem;
00289         double _emptyTrashesTime;
00290         std::string _url;
00291         bool _timestampUpdate;
00292 };
00293 
00294 }
00295 
00296 #endif /* DBDRIVER_H_ */


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