DBDriverSqlite3.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 DBDRIVERSQLITE3_H_
00029 #define DBDRIVERSQLITE3_H_
00030 
00031 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
00032 #include "rtabmap/core/DBDriver.h"
00033 #include <opencv2/features2d/features2d.hpp>
00034 #include "sqlite3/sqlite3.h"
00035 
00036 namespace rtabmap {
00037 
00038 class RTABMAP_EXP DBDriverSqlite3: public DBDriver {
00039 public:
00040         DBDriverSqlite3(const ParametersMap & parameters = ParametersMap());
00041         virtual ~DBDriverSqlite3();
00042 
00043         virtual void parseParameters(const ParametersMap & parameters);
00044         void setDbInMemory(bool dbInMemory);
00045         void setJournalMode(int journalMode);
00046         void setCacheSize(unsigned int cacheSize);
00047         void setSynchronous(int synchronous);
00048         void setTempStore(int tempStore);
00049 
00050 private:
00051         virtual bool connectDatabaseQuery(const std::string & url, bool overwritten = false);
00052         virtual void disconnectDatabaseQuery(bool save = true);
00053         virtual bool isConnectedQuery() const;
00054         virtual long getMemoryUsedQuery() const; // In bytes
00055         virtual bool getDatabaseVersionQuery(std::string & version) const;
00056         virtual long getImagesMemoryUsedQuery() const;
00057         virtual long getDepthImagesMemoryUsedQuery() const;
00058         virtual long getLaserScansMemoryUsedQuery() const;
00059         virtual long getUserDataMemoryUsedQuery() const;
00060         virtual long getWordsMemoryUsedQuery() const;
00061         virtual int getLastNodesSizeQuery() const;
00062         virtual int getLastDictionarySizeQuery() const;
00063         virtual int getTotalNodesSizeQuery() const;
00064         virtual int getTotalDictionarySizeQuery() const;
00065         virtual ParametersMap getLastParametersQuery() const;
00066 
00067         virtual void executeNoResultQuery(const std::string & sql) const;
00068 
00069         virtual void getWeightQuery(int signatureId, int & weight) const;
00070 
00071         virtual void saveQuery(const std::list<Signature *> & signatures) const;
00072         virtual void saveQuery(const std::list<VisualWord *> & words) const;
00073         virtual void updateQuery(const std::list<Signature *> & signatures, bool updateTimestamp) const;
00074         virtual void updateQuery(const std::list<VisualWord *> & words, bool updateTimestamp) const;
00075 
00076         virtual void addLinkQuery(const Link & link) const;
00077         virtual void updateLinkQuery(const Link & link) const;
00078 
00079         // Load objects
00080         virtual void loadQuery(VWDictionary * dictionary) const;
00081         virtual void loadLastNodesQuery(std::list<Signature *> & signatures) const;
00082         virtual void loadSignaturesQuery(const std::list<int> & ids, std::list<Signature *> & signatures) const;
00083         virtual void loadWordsQuery(const std::set<int> & wordIds, std::list<VisualWord *> & vws) const;
00084         virtual void loadLinksQuery(int signatureId, std::map<int, Link> & links, Link::Type type = Link::kUndef) const;
00085 
00086         virtual void loadNodeDataQuery(std::list<Signature *> & signatures) const;
00087         virtual bool getCalibrationQuery(int signatureId, std::vector<CameraModel> & models, StereoCameraModel & stereoModel) const;
00088         virtual bool getNodeInfoQuery(int signatureId, Transform & pose, int & mapId, int & weight, std::string & label, double & stamp, Transform & groundTruthPose) const;
00089         virtual void getAllNodeIdsQuery(std::set<int> & ids, bool ignoreChildren, bool ignoreBadSignatures) const;
00090         virtual void getAllLinksQuery(std::multimap<int, Link> & links, bool ignoreNullLinks) const;
00091         virtual void getLastIdQuery(const std::string & tableName, int & id) const;
00092         virtual void getInvertedIndexNiQuery(int signatureId, int & ni) const;
00093         virtual void getNodeIdByLabelQuery(const std::string & label, int & id) const;
00094         virtual void getAllLabelsQuery(std::map<int, std::string> & labels) const;
00095 
00096 private:
00097         std::string queryStepNode() const;
00098         std::string queryStepImage() const;
00099         std::string queryStepDepth() const;
00100         std::string queryStepSensorData() const;
00101         std::string queryStepLinkUpdate() const;
00102         std::string queryStepLink() const;
00103         std::string queryStepWordsChanged() const;
00104         std::string queryStepKeypoint() const;
00105         void stepNode(sqlite3_stmt * ppStmt, const Signature * s) const;
00106         void stepImage(
00107                         sqlite3_stmt * ppStmt,
00108                         int id,
00109                         const cv::Mat & imageBytes) const;
00110         void stepDepth(sqlite3_stmt * ppStmt, const SensorData & sensorData) const;
00111         void stepSensorData(sqlite3_stmt * ppStmt, const SensorData & sensorData) const;
00112         void stepLink(sqlite3_stmt * ppStmt, const Link & link) const;
00113         void stepWordsChanged(sqlite3_stmt * ppStmt, int signatureId, int oldWordId, int newWordId) const;
00114         void stepKeypoint(sqlite3_stmt * ppStmt, int signatureId, int wordId, const cv::KeyPoint & kp, const cv::Point3f & pt, const cv::Mat & descriptor) const;
00115 
00116 private:
00117         void loadLinksQuery(std::list<Signature *> & signatures) const;
00118         int loadOrSaveDb(sqlite3 *pInMemory, const std::string & fileName, int isSave) const;
00119 
00120 private:
00121         sqlite3 * _ppDb;
00122         std::string _version;
00123         bool _dbInMemory;
00124         unsigned int _cacheSize;
00125         int _journalMode;
00126         int _synchronous;
00127         int _tempStore;
00128 };
00129 
00130 }
00131 
00132 #endif /* DBDRIVERSQLITE3_H_ */


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