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 unsigned 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  void updateLaserScanQuery(
104  int nodeId,
105  const LaserScan & scan) const;
106 
107  virtual void addStatisticsQuery(const Statistics & statistics, bool saveWmState) const;
108  virtual void savePreviewImageQuery(const cv::Mat & image) const;
109  virtual cv::Mat loadPreviewImageQuery() const;
110  virtual void saveOptimizedPosesQuery(const std::map<int, Transform> & optimizedPoses, const Transform & lastlocalizationPose) const;
111  virtual std::map<int, Transform> loadOptimizedPosesQuery(Transform * lastlocalizationPose = 0) const;
112  virtual void save2DMapQuery(const cv::Mat & map, float xMin, float yMin, float cellSize) const;
113  virtual cv::Mat load2DMapQuery(float & xMin, float & yMin, float & cellSize) const;
114  virtual void saveOptimizedMeshQuery(
115  const cv::Mat & cloud,
116  const std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > & polygons,
117 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
118  const std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > & texCoords,
119 #else
120  const std::vector<std::vector<Eigen::Vector2f> > & texCoords,
121 #endif
122  const cv::Mat & textures) const;
123  virtual cv::Mat loadOptimizedMeshQuery(
124  std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > * polygons,
125 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
126  std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > * texCoords,
127 #else
128  std::vector<std::vector<Eigen::Vector2f> > * texCoords,
129 #endif
130  cv::Mat * textures) const;
131 
132  // Load objects
133  virtual void loadQuery(VWDictionary * dictionary, bool lastStateOnly = true) const;
134  virtual void loadLastNodesQuery(std::list<Signature *> & signatures) const;
135  virtual void loadSignaturesQuery(const std::list<int> & ids, std::list<Signature *> & signatures) const;
136  virtual void loadWordsQuery(const std::set<int> & wordIds, std::list<VisualWord *> & vws) const;
137  virtual void loadLinksQuery(int signatureId, std::multimap<int, Link> & links, Link::Type type = Link::kUndef) const;
138 
139  virtual void loadNodeDataQuery(std::list<Signature *> & signatures, bool images=true, bool scan=true, bool userData=true, bool occupancyGrid=true) const;
140  virtual bool getCalibrationQuery(int signatureId, std::vector<CameraModel> & models, StereoCameraModel & stereoModel) const;
141  virtual bool getLaserScanInfoQuery(int signatureId, LaserScan & info) const;
142  virtual bool getNodeInfoQuery(int signatureId, Transform & pose, int & mapId, int & weight, std::string & label, double & stamp, Transform & groundTruthPose, std::vector<float> & velocity, GPS & gps, EnvSensors & sensors) const;
143  virtual void getLastNodeIdsQuery(std::set<int> & ids) const;
144  virtual void getAllNodeIdsQuery(std::set<int> & ids, bool ignoreChildren, bool ignoreBadSignatures) const;
145  virtual void getAllLinksQuery(std::multimap<int, Link> & links, bool ignoreNullLinks, bool withLandmarks) const;
146  virtual void getLastIdQuery(const std::string & tableName, int & id, const std::string & fieldName="id") const;
147  virtual void getInvertedIndexNiQuery(int signatureId, int & ni) const;
148  virtual void getNodesObservingLandmarkQuery(int landmarkId, std::map<int, Link> & nodes) const;
149  virtual void getNodeIdByLabelQuery(const std::string & label, int & id) const;
150  virtual void getAllLabelsQuery(std::map<int, std::string> & labels) const;
151 
152 private:
153  std::string queryStepNode() const;
154  std::string queryStepImage() const;
155  std::string queryStepDepth() const;
156  std::string queryStepDepthUpdate() const;
157  std::string queryStepScanUpdate() const;
158  std::string queryStepSensorData() const;
159  std::string queryStepLinkUpdate() const;
160  std::string queryStepLink() const;
161  std::string queryStepWordsChanged() const;
162  std::string queryStepKeypoint() const;
163  std::string queryStepGlobalDescriptor() const;
164  std::string queryStepOccupancyGridUpdate() const;
165  void stepNode(sqlite3_stmt * ppStmt, const Signature * s) const;
166  void stepImage(sqlite3_stmt * ppStmt, int id, const cv::Mat & imageBytes) const;
167  void stepDepth(sqlite3_stmt * ppStmt, const SensorData & sensorData) const;
168  void stepDepthUpdate(sqlite3_stmt * ppStmt, int nodeId, const cv::Mat & imageCompressed) const;
169  void stepScanUpdate(sqlite3_stmt * ppStmt, int nodeId, const LaserScan & image) const;
170  void stepSensorData(sqlite3_stmt * ppStmt, const SensorData & sensorData) const;
171  void stepLink(sqlite3_stmt * ppStmt, const Link & link) const;
172  void stepWordsChanged(sqlite3_stmt * ppStmt, int signatureId, int oldWordId, int newWordId) const;
173  void stepKeypoint(sqlite3_stmt * ppStmt, int nodeID, int wordId, const cv::KeyPoint & kp, const cv::Point3f & pt, const cv::Mat & descriptor) const;
174  void stepGlobalDescriptor(sqlite3_stmt * ppStmt, int nodeId, const GlobalDescriptor & descriptor) const;
175  void stepOccupancyGridUpdate(sqlite3_stmt * ppStmt,
176  int nodeId,
177  const cv::Mat & ground,
178  const cv::Mat & obstacles,
179  const cv::Mat & empty,
180  float cellSize,
181  const cv::Point3f & viewpoint) const;
182 
183 private:
184  void loadLinksQuery(std::list<Signature *> & signatures) const;
185  int loadOrSaveDb(sqlite3 *pInMemory, const std::string & fileName, int isSave) const;
186 
187 protected:
189  std::string _version;
190 
191 private:
192  unsigned long _memoryUsedEstimate;
194  unsigned int _cacheSize;
198 };
199 
200 }
201 
202 #endif /* DBDRIVERSQLITE3_H_ */
struct sqlite3_stmt sqlite3_stmt
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
#define RTABMAP_EXP
Definition: RtabmapExp.h:38
unsigned long _memoryUsedEstimate
virtual bool isInMemory() const
std::map< EnvSensor::Type, EnvSensor > EnvSensors
Definition: EnvSensor.h:81


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:34:58