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 
00043 #include <rtabmap/core/Transform.h>
00044 #include <rtabmap/core/Link.h>
00045 
00046 namespace rtabmap {
00047 
00048 class Signature;
00049 class VWDictionary;
00050 class VisualWord;
00051 
00052 // Todo This class needs a refactoring, the _dbSafeAccessMutex problem when the trash is emptying (transaction)
00053 // "Of course, it has always been the case and probably always will be
00054 //that you cannot use the same sqlite3 connection in two or more
00055 //threads at the same time.  You can use different sqlite3 connections
00056 //at the same time in different threads, or you can move the same
00057 //sqlite3 connection across threads (subject to the constraints above)
00058 //but never, never try to use the same connection simultaneously in
00059 //two or more threads."
00060 //
00061 class RTABMAP_EXP DBDriver : public UThreadNode
00062 {
00063 public:
00064         static DBDriver * create(const ParametersMap & parameters = ParametersMap());
00065 
00066 public:
00067         virtual ~DBDriver();
00068 
00069         virtual void parseParameters(const ParametersMap & parameters);
00070         const std::string & getUrl() const {return _url;}
00071 
00072         void beginTransaction() const;
00073         void commit() const;
00074 
00075         void asyncSave(Signature * s); //ownership transferred
00076         void asyncSave(VisualWord * vw); //ownership transferred
00077         void emptyTrashes(bool async = false);
00078         double getEmptyTrashesTime() const {return _emptyTrashesTime;}
00079         void setTimestampUpdateEnabled(bool enabled) {_timestampUpdate = enabled;} // used on Update Signature and Word queries
00080 
00081         // Warning: the following functions don't look in the trash, direct database modifications
00082         void generateGraph(
00083                         const std::string & fileName,
00084                         const std::set<int> & ids = std::set<int>(),
00085                         const std::map<int, Signature *> & otherSignatures = std::map<int, Signature *>());
00086         void addLink(const Link & link);
00087         void removeLink(int from, int to);
00088         void updateLink(const Link & link);
00089 
00090 public:
00091         void addStatisticsAfterRun(int stMemSize, int lastSignAdded, int processMemUsed, int databaseMemUsed, int dictionarySize, const ParametersMap & parameters) const;
00092 
00093 public:
00094         // Mutex-protected methods of abstract versions below
00095 
00096         bool openConnection(const std::string & url, bool overwritten = false);
00097         void closeConnection(bool save = true);
00098         bool isConnected() const;
00099         long getMemoryUsed() const; // In bytes
00100         std::string getDatabaseVersion() const;
00101         long getImagesMemoryUsed() const;
00102         long getDepthImagesMemoryUsed() const;
00103         long getLaserScansMemoryUsed() const;
00104         long getUserDataMemoryUsed() const;
00105         long getWordsMemoryUsed() const;
00106         int getLastNodesSize() const; // working memory
00107         int getLastDictionarySize() const; // working memory
00108         int getTotalNodesSize() const;
00109         int getTotalDictionarySize() const;
00110         ParametersMap getLastParameters() const;
00111 
00112         void executeNoResult(const std::string & sql) const;
00113 
00114         // Load objects
00115         void load(VWDictionary * dictionary) const;
00116         void loadLastNodes(std::list<Signature *> & signatures) const;
00117         void loadSignatures(const std::list<int> & ids, std::list<Signature *> & signatures, std::set<int> * loadedFromTrash = 0);
00118         void loadWords(const std::set<int> & wordIds, std::list<VisualWord *> & vws);
00119 
00120         // Specific queries...
00121         void loadNodeData(std::list<Signature *> & signatures) const;
00122         void getNodeData(int signatureId, SensorData & data) const;
00123         bool getCalibration(int signatureId, std::vector<CameraModel> & models, StereoCameraModel & stereoModel) const;
00124         bool getNodeInfo(int signatureId, Transform & pose, int & mapId, int & weight, std::string & label, double & stamp, Transform & groundTruthPose) const;
00125         void loadLinks(int signatureId, std::map<int, Link> & links, Link::Type type = Link::kUndef) const;
00126         void getWeight(int signatureId, int & weight) const;
00127         void getAllNodeIds(std::set<int> & ids, bool ignoreChildren = false, bool ignoreBadSignatures = false) const;
00128         void getAllLinks(std::multimap<int, Link> & links, bool ignoreNullLinks = true) const;
00129         void getLastNodeId(int & id) const;
00130         void getLastWordId(int & id) const;
00131         void getInvertedIndexNi(int signatureId, int & ni) const;
00132         void getNodeIdByLabel(const std::string & label, int & id) const;
00133         void getAllLabels(std::map<int, std::string> & labels) const;
00134 
00135 protected:
00136         DBDriver(const ParametersMap & parameters = ParametersMap());
00137 
00138 private:
00139         virtual bool connectDatabaseQuery(const std::string & url, bool overwritten = false) = 0;
00140         virtual void disconnectDatabaseQuery(bool save = true) = 0;
00141         virtual bool isConnectedQuery() const = 0;
00142         virtual long getMemoryUsedQuery() const = 0; // In bytes
00143         virtual bool getDatabaseVersionQuery(std::string & version) const = 0;
00144         virtual long getImagesMemoryUsedQuery() const = 0;
00145         virtual long getDepthImagesMemoryUsedQuery() const = 0;
00146         virtual long getLaserScansMemoryUsedQuery() const = 0;
00147         virtual long getUserDataMemoryUsedQuery() const = 0;
00148         virtual long getWordsMemoryUsedQuery() const = 0;
00149         virtual int getLastNodesSizeQuery() const = 0;
00150         virtual int getLastDictionarySizeQuery() const = 0;
00151         virtual int getTotalNodesSizeQuery() const = 0;
00152         virtual int getTotalDictionarySizeQuery() const = 0;
00153         virtual ParametersMap getLastParametersQuery() const = 0;
00154 
00155         virtual void executeNoResultQuery(const std::string & sql) const = 0;
00156 
00157         virtual void getWeightQuery(int signatureId, int & weight) const = 0;
00158 
00159         virtual void saveQuery(const std::list<Signature *> & signatures) const = 0;
00160         virtual void saveQuery(const std::list<VisualWord *> & words) const = 0;
00161         virtual void updateQuery(const std::list<Signature *> & signatures, bool updateTimestamp) const = 0;
00162         virtual void updateQuery(const std::list<VisualWord *> & words, bool updateTimestamp) const = 0;
00163 
00164         virtual void addLinkQuery(const Link & link) const = 0;
00165         virtual void updateLinkQuery(const Link & link) const = 0;
00166 
00167         // Load objects
00168         virtual void loadQuery(VWDictionary * dictionary) const = 0;
00169         virtual void loadLastNodesQuery(std::list<Signature *> & signatures) const = 0;
00170         virtual void loadSignaturesQuery(const std::list<int> & ids, std::list<Signature *> & signatures) const = 0;
00171         virtual void loadWordsQuery(const std::set<int> & wordIds, std::list<VisualWord *> & vws) const = 0;
00172         virtual void loadLinksQuery(int signatureId, std::map<int, Link> & links, Link::Type type = Link::kUndef) const = 0;
00173 
00174         virtual void loadNodeDataQuery(std::list<Signature *> & signatures) const = 0;
00175         virtual bool getCalibrationQuery(int signatureId, std::vector<CameraModel> & models, StereoCameraModel & stereoModel) const = 0;
00176         virtual bool getNodeInfoQuery(int signatureId, Transform & pose, int & mapId, int & weight, std::string & label, double & stamp, Transform & groundTruthPose) const = 0;
00177         virtual void getAllNodeIdsQuery(std::set<int> & ids, bool ignoreChildren, bool ignoreBadSignatures) const = 0;
00178         virtual void getAllLinksQuery(std::multimap<int, Link> & links, bool ignoreNullLinks) const = 0;
00179         virtual void getLastIdQuery(const std::string & tableName, int & id) const = 0;
00180         virtual void getInvertedIndexNiQuery(int signatureId, int & ni) const = 0;
00181         virtual void getNodeIdByLabelQuery(const std::string & label, int & id) const = 0;
00182         virtual void getAllLabelsQuery(std::map<int, std::string> & labels) const = 0;
00183 
00184 private:
00185         //non-abstract methods
00186         void saveOrUpdate(const std::vector<Signature *> & signatures) const;
00187         void saveOrUpdate(const std::vector<VisualWord *> & words) const;
00188 
00189         //thread stuff
00190         virtual void mainLoop();
00191 
00192 private:
00193         UMutex _transactionMutex;
00194         std::map<int, Signature *> _trashSignatures;//<id, Signature*>
00195         std::map<int, VisualWord *> _trashVisualWords; //<id, VisualWord*>
00196         UMutex _trashesMutex;
00197         UMutex _dbSafeAccessMutex;
00198         USemaphore _addSem;
00199         double _emptyTrashesTime;
00200         std::string _url;
00201         bool _timestampUpdate;
00202 };
00203 
00204 }
00205 
00206 #endif /* DBDRIVER_H_ */


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