DBDriverSqlite3.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #ifndef DBDRIVERSQLITE3_H_
29 #define DBDRIVERSQLITE3_H_
30 
31 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
32 #include "rtabmap/core/DBDriver.h"
33 #include <opencv2/features2d/features2d.hpp>
34 
35 typedef struct sqlite3_stmt sqlite3_stmt;
36 typedef struct sqlite3 sqlite3;
37 
38 namespace rtabmap {
39 
41 public:
42  DBDriverSqlite3(const ParametersMap & parameters = ParametersMap());
43  virtual ~DBDriverSqlite3();
44 
45  virtual void parseParameters(const ParametersMap & parameters);
46  virtual bool isInMemory() const {return getUrl().empty() || _dbInMemory;}
47  void setDbInMemory(bool dbInMemory);
48  void setJournalMode(int journalMode);
49  void setCacheSize(unsigned int cacheSize);
50  void setSynchronous(int synchronous);
51  void setTempStore(int tempStore);
52 
53 protected:
54  virtual bool connectDatabaseQuery(const std::string & url, bool overwritten = false);
55  virtual void disconnectDatabaseQuery(bool save = true, const std::string & outputUrl = "");
56  virtual bool isConnectedQuery() const;
57  virtual long getMemoryUsedQuery() const; // In bytes
58  virtual bool getDatabaseVersionQuery(std::string & version) const;
59  virtual long getNodesMemoryUsedQuery() const;
60  virtual long getLinksMemoryUsedQuery() const;
61  virtual long getImagesMemoryUsedQuery() const;
62  virtual long getDepthImagesMemoryUsedQuery() const;
63  virtual long getCalibrationsMemoryUsedQuery() const;
64  virtual long getGridsMemoryUsedQuery() const;
65  virtual long getLaserScansMemoryUsedQuery() const;
66  virtual long getUserDataMemoryUsedQuery() const;
67  virtual long getWordsMemoryUsedQuery() const;
68  virtual long getFeaturesMemoryUsedQuery() const;
69  virtual long getStatisticsMemoryUsedQuery() const;
70  virtual int getLastNodesSizeQuery() const;
71  virtual int getLastDictionarySizeQuery() const;
72  virtual int getTotalNodesSizeQuery() const;
73  virtual int getTotalDictionarySizeQuery() const;
74  virtual ParametersMap getLastParametersQuery() const;
75  virtual std::map<std::string, float> getStatisticsQuery(int nodeId, double & stamp, std::vector<int> * wmState) const;
76  virtual std::map<int, std::pair<std::map<std::string, float>, double> > getAllStatisticsQuery() const;
77  virtual std::map<int, std::vector<int> > getAllStatisticsWmStatesQuery() const;
78 
79  virtual void executeNoResultQuery(const std::string & sql) const;
80 
81  virtual void getWeightQuery(int signatureId, int & weight) const;
82 
83  virtual void saveQuery(const std::list<Signature *> & signatures);
84  virtual void saveQuery(const std::list<VisualWord *> & words) const;
85  virtual void updateQuery(const std::list<Signature *> & signatures, bool updateTimestamp) const;
86  virtual void updateQuery(const std::list<VisualWord *> & words, bool updateTimestamp) const;
87 
88  virtual void addLinkQuery(const Link & link) const;
89  virtual void updateLinkQuery(const Link & link) const;
90 
91  virtual void updateOccupancyGridQuery(
92  int nodeId,
93  const cv::Mat & ground,
94  const cv::Mat & obstacles,
95  const cv::Mat & empty,
96  float cellSize,
97  const cv::Point3f & viewpoint) const;
98 
99  virtual void updateDepthImageQuery(
100  int nodeId,
101  const cv::Mat & image) const;
102 
103  virtual void addStatisticsQuery(const Statistics & statistics) const;
104  virtual void savePreviewImageQuery(const cv::Mat & image) const;
105  virtual cv::Mat loadPreviewImageQuery() const;
106  virtual void saveOptimizedPosesQuery(const std::map<int, Transform> & optimizedPoses, const Transform & lastlocalizationPose) const;
107  virtual std::map<int, Transform> loadOptimizedPosesQuery(Transform * lastlocalizationPose) const;
108  virtual void save2DMapQuery(const cv::Mat & map, float xMin, float yMin, float cellSize) const;
109  virtual cv::Mat load2DMapQuery(float & xMin, float & yMin, float & cellSize) const;
110  virtual void saveOptimizedMeshQuery(
111  const cv::Mat & cloud,
112  const std::vector<std::vector<std::vector<unsigned int> > > & polygons,
113 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
114  const std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > & texCoords,
115 #else
116  const std::vector<std::vector<Eigen::Vector2f> > & texCoords,
117 #endif
118  const cv::Mat & textures) const;
119  virtual cv::Mat loadOptimizedMeshQuery(
120  std::vector<std::vector<std::vector<unsigned int> > > * polygons,
121 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
122  std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > * texCoords,
123 #else
124  std::vector<std::vector<Eigen::Vector2f> > * texCoords,
125 #endif
126  cv::Mat * textures) const;
127 
128  // Load objects
129  virtual void loadQuery(VWDictionary * dictionary, bool lastStateOnly = true) const;
130  virtual void loadLastNodesQuery(std::list<Signature *> & signatures) const;
131  virtual void loadSignaturesQuery(const std::list<int> & ids, std::list<Signature *> & signatures) const;
132  virtual void loadWordsQuery(const std::set<int> & wordIds, std::list<VisualWord *> & vws) const;
133  virtual void loadLinksQuery(int signatureId, std::map<int, Link> & links, Link::Type type = Link::kUndef) const;
134 
135  virtual void loadNodeDataQuery(std::list<Signature *> & signatures, bool images=true, bool scan=true, bool userData=true, bool occupancyGrid=true) const;
136  virtual bool getCalibrationQuery(int signatureId, std::vector<CameraModel> & models, StereoCameraModel & stereoModel) const;
137  virtual bool getLaserScanInfoQuery(int signatureId, LaserScan & info) const;
138  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;
139  virtual void getAllNodeIdsQuery(std::set<int> & ids, bool ignoreChildren, bool ignoreBadSignatures) const;
140  virtual void getAllLinksQuery(std::multimap<int, Link> & links, bool ignoreNullLinks) const;
141  virtual void getLastIdQuery(const std::string & tableName, int & id) const;
142  virtual void getInvertedIndexNiQuery(int signatureId, int & ni) const;
143  virtual void getNodeIdByLabelQuery(const std::string & label, int & id) const;
144  virtual void getAllLabelsQuery(std::map<int, std::string> & labels) const;
145 
146 private:
147  std::string queryStepNode() const;
148  std::string queryStepImage() const;
149  std::string queryStepDepth() const;
150  std::string queryStepDepthUpdate() const;
151  std::string queryStepSensorData() const;
152  std::string queryStepLinkUpdate() const;
153  std::string queryStepLink() const;
154  std::string queryStepWordsChanged() const;
155  std::string queryStepKeypoint() const;
156  std::string queryStepOccupancyGridUpdate() const;
157  void stepNode(sqlite3_stmt * ppStmt, const Signature * s) const;
158  void stepImage(
159  sqlite3_stmt * ppStmt,
160  int id,
161  const cv::Mat & imageBytes) const;
162  void stepDepth(sqlite3_stmt * ppStmt, const SensorData & sensorData) const;
163  void stepDepthUpdate(sqlite3_stmt * ppStmt, int nodeId, const cv::Mat & imageCompressed) const;
164  void stepSensorData(sqlite3_stmt * ppStmt, const SensorData & sensorData) const;
165  void stepLink(sqlite3_stmt * ppStmt, const Link & link) const;
166  void stepWordsChanged(sqlite3_stmt * ppStmt, int signatureId, int oldWordId, int newWordId) const;
167  void stepKeypoint(sqlite3_stmt * ppStmt, int signatureId, int wordId, const cv::KeyPoint & kp, const cv::Point3f & pt, const cv::Mat & descriptor) const;
168  void stepOccupancyGridUpdate(sqlite3_stmt * ppStmt,
169  int nodeId,
170  const cv::Mat & ground,
171  const cv::Mat & obstacles,
172  const cv::Mat & empty,
173  float cellSize,
174  const cv::Point3f & viewpoint) const;
175 
176 private:
177  void loadLinksQuery(std::list<Signature *> & signatures) const;
178  int loadOrSaveDb(sqlite3 *pInMemory, const std::string & fileName, int isSave) const;
179 
180 protected:
182  std::string _version;
183 
184 private:
187  unsigned int _cacheSize;
191 };
192 
193 }
194 
195 #endif /* DBDRIVERSQLITE3_H_ */
struct sqlite3_stmt sqlite3_stmt
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:41
#define RTABMAP_EXP
Definition: RtabmapExp.h:38
virtual bool isInMemory() const


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:31