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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Feb 13 2025 03:44:53