DBDriver.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 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 
00042 #include <rtabmap/core/Transform.h>
00043 #include <rtabmap/core/Link.h>
00044 
00045 namespace rtabmap {
00046 
00047 class Signature;
00048 class VWDictionary;
00049 class VisualWord;
00050 
00051 // Todo This class needs a refactoring, the _dbSafeAccessMutex problem when the trash is emptying (transaction)
00052 // "Of course, it has always been the case and probably always will be
00053 //that you cannot use the same sqlite3 connection in two or more
00054 //threads at the same time.  You can use different sqlite3 connections
00055 //at the same time in different threads, or you can move the same
00056 //sqlite3 connection across threads (subject to the constraints above)
00057 //but never, never try to use the same connection simultaneously in
00058 //two or more threads."
00059 //
00060 class RTABMAP_EXP DBDriver : public UThreadNode
00061 {
00062 public:
00063         virtual ~DBDriver();
00064 
00065         virtual void parseParameters(const ParametersMap & parameters);
00066         const std::string & getUrl() const {return _url;}
00067 
00068         void beginTransaction() const;
00069         void commit() const;
00070 
00071         void asyncSave(Signature * s); //ownership transferred
00072         void asyncSave(VisualWord * vw); //ownership transferred
00073         void emptyTrashes(bool async = false);
00074         double getEmptyTrashesTime() const {return _emptyTrashesTime;}
00075         void setTimestampUpdateEnabled(bool enabled) {_timestampUpdate = enabled;} // used on Update Signature and Word queries
00076 
00077 public:
00078         void addStatisticsAfterRun(int stMemSize, int lastSignAdded, int processMemUsed, int databaseMemUsed, int dictionarySize) const;
00079 
00080 public:
00081         // Mutex-protected methods of abstract versions below
00082 
00083         bool openConnection(const std::string & url, bool overwritten = false);
00084         void closeConnection();
00085         bool isConnected() const;
00086         long getMemoryUsed() const; // In bytes
00087 
00088         void executeNoResult(const std::string & sql) const;
00089 
00090         // Load objects
00091         void load(VWDictionary * dictionary) const;
00092         void loadLastNodes(std::list<Signature *> & signatures) const;
00093         void loadSignatures(const std::list<int> & ids, std::list<Signature *> & signatures, std::set<int> * loadedFromTrash = 0);
00094         void loadWords(const std::set<int> & wordIds, std::list<VisualWord *> & vws);
00095 
00096         // Specific queries...
00097         void loadNodeData(std::list<Signature *> & signatures, bool loadMetricData) const;
00098         void getNodeData(int signatureId, cv::Mat & imageCompressed, cv::Mat & depthCompressed, cv::Mat & laserScanCompressed, float & fx, float & fy, float & cx, float & cy, Transform & localTransform, int & laserScanMaxPts) const;
00099         void getNodeData(int signatureId, cv::Mat & imageCompressed) const;
00100         bool getNodeInfo(int signatureId, Transform & pose, int & mapId, int & weight, std::string & label, double & stamp, std::vector<unsigned char> & userData) const;
00101         void loadLinks(int signatureId, std::map<int, Link> & links, Link::Type type = Link::kUndef) const;
00102         void getWeight(int signatureId, int & weight) const;
00103         void getAllNodeIds(std::set<int> & ids, bool ignoreChildren = false) const;
00104         void getLastNodeId(int & id) const;
00105         void getLastWordId(int & id) const;
00106         void getInvertedIndexNi(int signatureId, int & ni) const;
00107         void getNodeIdByLabel(const std::string & label, int & id) const;
00108         void getAllLabels(std::map<int, std::string> & labels) const;
00109 
00110 protected:
00111         DBDriver(const ParametersMap & parameters = ParametersMap());
00112 
00113 private:
00114         virtual bool connectDatabaseQuery(const std::string & url, bool overwritten = false) = 0;
00115         virtual void disconnectDatabaseQuery() = 0;
00116         virtual bool isConnectedQuery() const = 0;
00117         virtual long getMemoryUsedQuery() const = 0; // In bytes
00118 
00119         virtual void executeNoResultQuery(const std::string & sql) const = 0;
00120 
00121         virtual void getWeightQuery(int signatureId, int & weight) const = 0;
00122 
00123         virtual void saveQuery(const std::list<Signature *> & signatures) const = 0;
00124         virtual void saveQuery(const std::list<VisualWord *> & words) const = 0;
00125         virtual void updateQuery(const std::list<Signature *> & signatures, bool updateTimestamp) const = 0;
00126         virtual void updateQuery(const std::list<VisualWord *> & words, bool updateTimestamp) const = 0;
00127 
00128 
00129         // Load objects
00130         virtual void loadQuery(VWDictionary * dictionary) const = 0;
00131         virtual void loadLastNodesQuery(std::list<Signature *> & signatures) const = 0;
00132         virtual void loadSignaturesQuery(const std::list<int> & ids, std::list<Signature *> & signatures) const = 0;
00133         virtual void loadWordsQuery(const std::set<int> & wordIds, std::list<VisualWord *> & vws) const = 0;
00134         virtual void loadLinksQuery(int signatureId, std::map<int, Link> & links, Link::Type type = Link::kUndef) const = 0;
00135 
00136         virtual void loadNodeDataQuery(std::list<Signature *> & signatures, bool loadMetricData) const = 0;
00137         virtual void getNodeDataQuery(int signatureId, cv::Mat & imageCompressed, cv::Mat & depthCompressed, cv::Mat & laserScanCompressed, float & fx, float & fy, float & cx, float & cy, Transform & localTransform, int & laserScanMaxPts) const = 0;
00138         virtual void getNodeDataQuery(int signatureId, cv::Mat & imageCompressed) const = 0;
00139         virtual bool getNodeInfoQuery(int signatureId, Transform & pose, int & mapId, int & weight, std::string & label, double & stamp, std::vector<unsigned char> & userData) const = 0;
00140         virtual void getAllNodeIdsQuery(std::set<int> & ids, bool ignoreChildren) const = 0;
00141         virtual void getLastIdQuery(const std::string & tableName, int & id) const = 0;
00142         virtual void getInvertedIndexNiQuery(int signatureId, int & ni) const = 0;
00143         virtual void getNodeIdByLabelQuery(const std::string & label, int & id) const = 0;
00144         virtual void getAllLabelsQuery(std::map<int, std::string> & labels) const = 0;
00145 
00146 private:
00147         //non-abstract methods
00148         void saveOrUpdate(const std::vector<Signature *> & signatures) const;
00149         void saveOrUpdate(const std::vector<VisualWord *> & words) const;
00150 
00151         //thread stuff
00152         virtual void mainLoop();
00153 
00154 private:
00155         UMutex _transactionMutex;
00156         std::map<int, Signature *> _trashSignatures;//<id, Signature*>
00157         std::map<int, VisualWord *> _trashVisualWords; //<id, VisualWord*>
00158         UMutex _trashesMutex;
00159         UMutex _dbSafeAccessMutex;
00160         USemaphore _addSem;
00161         double _emptyTrashesTime;
00162         std::string _url;
00163         bool _timestampUpdate;
00164 };
00165 
00166 }
00167 
00168 #endif /* DBDRIVER_H_ */


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