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 
00035 typedef struct sqlite3_stmt sqlite3_stmt;
00036 typedef struct sqlite3 sqlite3;
00037 
00038 namespace rtabmap {
00039 
00040 class RTABMAP_EXP DBDriverSqlite3: public DBDriver {
00041 public:
00042         DBDriverSqlite3(const ParametersMap & parameters = ParametersMap());
00043         virtual ~DBDriverSqlite3();
00044 
00045         virtual void parseParameters(const ParametersMap & parameters);
00046         virtual bool isInMemory() const {return getUrl().empty() || _dbInMemory;}
00047         void setDbInMemory(bool dbInMemory);
00048         void setJournalMode(int journalMode);
00049         void setCacheSize(unsigned int cacheSize);
00050         void setSynchronous(int synchronous);
00051         void setTempStore(int tempStore);
00052 
00053 protected:
00054         virtual bool connectDatabaseQuery(const std::string & url, bool overwritten = false);
00055         virtual void disconnectDatabaseQuery(bool save = true, const std::string & outputUrl = "");
00056         virtual bool isConnectedQuery() const;
00057         virtual long getMemoryUsedQuery() const; // In bytes
00058         virtual bool getDatabaseVersionQuery(std::string & version) const;
00059         virtual long getNodesMemoryUsedQuery() const;
00060         virtual long getLinksMemoryUsedQuery() const;
00061         virtual long getImagesMemoryUsedQuery() const;
00062         virtual long getDepthImagesMemoryUsedQuery() const;
00063         virtual long getCalibrationsMemoryUsedQuery() const;
00064         virtual long getGridsMemoryUsedQuery() const;
00065         virtual long getLaserScansMemoryUsedQuery() const;
00066         virtual long getUserDataMemoryUsedQuery() const;
00067         virtual long getWordsMemoryUsedQuery() const;
00068         virtual long getFeaturesMemoryUsedQuery() const;
00069         virtual long getStatisticsMemoryUsedQuery() const;
00070         virtual int getLastNodesSizeQuery() const;
00071         virtual int getLastDictionarySizeQuery() const;
00072         virtual int getTotalNodesSizeQuery() const;
00073         virtual int getTotalDictionarySizeQuery() const;
00074         virtual ParametersMap getLastParametersQuery() const;
00075         virtual std::map<std::string, float> getStatisticsQuery(int nodeId, double & stamp, std::vector<int> * wmState) const;
00076         virtual std::map<int, std::pair<std::map<std::string, float>, double> > getAllStatisticsQuery() const;
00077         virtual std::map<int, std::vector<int> > getAllStatisticsWmStatesQuery() const;
00078 
00079         virtual void executeNoResultQuery(const std::string & sql) const;
00080 
00081         virtual void getWeightQuery(int signatureId, int & weight) const;
00082 
00083         virtual void saveQuery(const std::list<Signature *> & signatures);
00084         virtual void saveQuery(const std::list<VisualWord *> & words) const;
00085         virtual void updateQuery(const std::list<Signature *> & signatures, bool updateTimestamp) const;
00086         virtual void updateQuery(const std::list<VisualWord *> & words, bool updateTimestamp) const;
00087 
00088         virtual void addLinkQuery(const Link & link) const;
00089         virtual void updateLinkQuery(const Link & link) const;
00090 
00091         virtual void updateOccupancyGridQuery(
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) const;
00098 
00099         virtual void updateDepthImageQuery(
00100                         int nodeId,
00101                         const cv::Mat & image) const;
00102 
00103         virtual void addStatisticsQuery(const Statistics & statistics) const;
00104         virtual void savePreviewImageQuery(const cv::Mat & image) const;
00105         virtual cv::Mat loadPreviewImageQuery() const;
00106         virtual void saveOptimizedPosesQuery(const std::map<int, Transform> & optimizedPoses, const Transform & lastlocalizationPose) const;
00107         virtual std::map<int, Transform> loadOptimizedPosesQuery(Transform * lastlocalizationPose) const;
00108         virtual void save2DMapQuery(const cv::Mat & map, float xMin, float yMin, float cellSize) const;
00109         virtual cv::Mat load2DMapQuery(float & xMin, float & yMin, float & cellSize) const;
00110         virtual void saveOptimizedMeshQuery(
00111                         const cv::Mat & cloud,
00112                         const std::vector<std::vector<std::vector<unsigned int> > > & polygons,
00113 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
00114                         const std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > & texCoords,
00115 #else
00116                         const std::vector<std::vector<Eigen::Vector2f> > & texCoords,
00117 #endif
00118                         const cv::Mat & textures) const;
00119         virtual cv::Mat loadOptimizedMeshQuery(
00120                         std::vector<std::vector<std::vector<unsigned int> > > * polygons,
00121 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
00122                         std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > * texCoords,
00123 #else
00124                         std::vector<std::vector<Eigen::Vector2f> > * texCoords,
00125 #endif
00126                         cv::Mat * textures) const;
00127 
00128         // Load objects
00129         virtual void loadQuery(VWDictionary * dictionary, bool lastStateOnly = true) const;
00130         virtual void loadLastNodesQuery(std::list<Signature *> & signatures) const;
00131         virtual void loadSignaturesQuery(const std::list<int> & ids, std::list<Signature *> & signatures) const;
00132         virtual void loadWordsQuery(const std::set<int> & wordIds, std::list<VisualWord *> & vws) const;
00133         virtual void loadLinksQuery(int signatureId, std::map<int, Link> & links, Link::Type type = Link::kUndef) const;
00134 
00135         virtual void loadNodeDataQuery(std::list<Signature *> & signatures, bool images=true, bool scan=true, bool userData=true, bool occupancyGrid=true) const;
00136         virtual bool getCalibrationQuery(int signatureId, std::vector<CameraModel> & models, StereoCameraModel & stereoModel) const;
00137         virtual bool getLaserScanInfoQuery(int signatureId, LaserScan & info) const;
00138         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;
00139         virtual void getAllNodeIdsQuery(std::set<int> & ids, bool ignoreChildren, bool ignoreBadSignatures) const;
00140         virtual void getAllLinksQuery(std::multimap<int, Link> & links, bool ignoreNullLinks) const;
00141         virtual void getLastIdQuery(const std::string & tableName, int & id) const;
00142         virtual void getInvertedIndexNiQuery(int signatureId, int & ni) const;
00143         virtual void getNodeIdByLabelQuery(const std::string & label, int & id) const;
00144         virtual void getAllLabelsQuery(std::map<int, std::string> & labels) const;
00145 
00146 private:
00147         std::string queryStepNode() const;
00148         std::string queryStepImage() const;
00149         std::string queryStepDepth() const;
00150         std::string queryStepDepthUpdate() const;
00151         std::string queryStepSensorData() const;
00152         std::string queryStepLinkUpdate() const;
00153         std::string queryStepLink() const;
00154         std::string queryStepWordsChanged() const;
00155         std::string queryStepKeypoint() const;
00156         std::string queryStepOccupancyGridUpdate() const;
00157         void stepNode(sqlite3_stmt * ppStmt, const Signature * s) const;
00158         void stepImage(
00159                         sqlite3_stmt * ppStmt,
00160                         int id,
00161                         const cv::Mat & imageBytes) const;
00162         void stepDepth(sqlite3_stmt * ppStmt, const SensorData & sensorData) const;
00163         void stepDepthUpdate(sqlite3_stmt * ppStmt, int nodeId, const cv::Mat & imageCompressed) const;
00164         void stepSensorData(sqlite3_stmt * ppStmt, const SensorData & sensorData) const;
00165         void stepLink(sqlite3_stmt * ppStmt, const Link & link) const;
00166         void stepWordsChanged(sqlite3_stmt * ppStmt, int signatureId, int oldWordId, int newWordId) const;
00167         void stepKeypoint(sqlite3_stmt * ppStmt, int signatureId, int wordId, const cv::KeyPoint & kp, const cv::Point3f & pt, const cv::Mat & descriptor) const;
00168         void stepOccupancyGridUpdate(sqlite3_stmt * ppStmt,
00169                         int nodeId,
00170                         const cv::Mat & ground,
00171                         const cv::Mat & obstacles,
00172                         const cv::Mat & empty,
00173                         float cellSize,
00174                         const cv::Point3f & viewpoint) const;
00175 
00176 private:
00177         void loadLinksQuery(std::list<Signature *> & signatures) const;
00178         int loadOrSaveDb(sqlite3 *pInMemory, const std::string & fileName, int isSave) const;
00179 
00180 protected:
00181         sqlite3 * _ppDb;
00182         std::string _version;
00183 
00184 private:
00185         long _memoryUsedEstimate;
00186         bool _dbInMemory;
00187         unsigned int _cacheSize;
00188         int _journalMode;
00189         int _synchronous;
00190         int _tempStore;
00191 };
00192 
00193 }
00194 
00195 #endif /* DBDRIVERSQLITE3_H_ */


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