DBDriver.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 DBDRIVER_H_
29 #define DBDRIVER_H_
30 
31 #include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
32 
33 #include <string>
34 #include <list>
35 #include <map>
36 #include <set>
37 #include <opencv2/core/core.hpp>
38 #include "rtabmap/utilite/UMutex.h"
43 
44 #include <rtabmap/core/Transform.h>
45 #include <rtabmap/core/Link.h>
46 
47 namespace rtabmap {
48 
49 class Signature;
50 class VWDictionary;
51 class VisualWord;
52 
53 // Todo This class needs a refactoring, the _dbSafeAccessMutex problem when the trash is emptying (transaction)
54 // "Of course, it has always been the case and probably always will be
55 //that you cannot use the same sqlite3 connection in two or more
56 //threads at the same time. You can use different sqlite3 connections
57 //at the same time in different threads, or you can move the same
58 //sqlite3 connection across threads (subject to the constraints above)
59 //but never, never try to use the same connection simultaneously in
60 //two or more threads."
61 //
62 class RTABMAP_CORE_EXPORT DBDriver : public UThreadNode
63 {
64 public:
65  static DBDriver * create(const ParametersMap & parameters = ParametersMap());
66 
67 public:
68  virtual ~DBDriver();
69 
70  virtual void parseParameters(const ParametersMap & parameters);
71  virtual bool isInMemory() const {return _url.empty();}
72  const std::string & getUrl() const {return _url;}
73  const std::string & getTargetVersion() const {return _targetVersion;}
74 
75  void beginTransaction() const;
76  void commit() const;
77 
78  void asyncSave(Signature * s); //ownership transferred
79  void asyncSave(VisualWord * vw); //ownership transferred
80  void emptyTrashes(bool async = false);
81  double getEmptyTrashesTime() const {return _emptyTrashesTime;}
82  void setTimestampUpdateEnabled(bool enabled) {_timestampUpdate = enabled;} // used on Update Signature and Word queries
83 
84  // Warning: the following functions don't look in the trash, direct database modifications
85  void generateGraph(
86  const std::string & fileName,
87  const std::set<int> & ids = std::set<int>(),
88  const std::map<int, Signature *> & otherSignatures = std::map<int, Signature *>());
89  void addLink(const Link & link);
90  void removeLink(int from, int to);
91  void updateLink(const Link & link);
92  void updateOccupancyGrid(
93  int nodeId,
94  const cv::Mat & ground,
95  const cv::Mat & obstacles,
96  const cv::Mat & empty,
97  float cellSize,
98  const cv::Point3f & viewpoint);
99  void updateCalibration(
100  int nodeId,
101  const std::vector<CameraModel> & models,
102  const std::vector<StereoCameraModel> & stereoModels);
103  void updateDepthImage(int nodeId, const cv::Mat & image, const std::string & format);
104  void updateLaserScan(int nodeId, const LaserScan & scan);
105 
106 public:
107  void addInfoAfterRun(int stMemSize, int lastSignAdded, int processMemUsed, int databaseMemUsed, int dictionarySize, const ParametersMap & parameters) const;
108  void addStatistics(const Statistics & statistics, bool saveWmState) const;
109  void savePreviewImage(const cv::Mat & image) const;
110  cv::Mat loadPreviewImage() const;
111  void saveOptimizedPoses(const std::map<int, Transform> & optimizedPoses, const Transform & lastlocalizationPose) const;
112  std::map<int, Transform> loadOptimizedPoses(Transform * lastlocalizationPose = 0) const;
113  void save2DMap(const cv::Mat & map, float xMin, float yMin, float cellSize) const;
114  cv::Mat load2DMap(float & xMin, float & yMin, float & cellSize) const;
115  void saveOptimizedMesh(
116  const cv::Mat & cloud,
117  const std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > & polygons = std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > >(), // Textures -> polygons -> vertices
118 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
119  const std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > & texCoords = std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > >(), // Textures -> uv coords for each vertex of the polygons
120 #else
121  const std::vector<std::vector<Eigen::Vector2f> > & texCoords = std::vector<std::vector<Eigen::Vector2f> >(), // Textures -> uv coords for each vertex of the polygons
122 #endif
123  const cv::Mat & textures = cv::Mat()) const; // concatenated textures (assuming square textures with all same size);
124  cv::Mat loadOptimizedMesh(
125  std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > * polygons = 0,
126 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
127  std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > * texCoords = 0,
128 #else
129  std::vector<std::vector<Eigen::Vector2f> > * texCoords = 0,
130 #endif
131  cv::Mat * textures = 0) const;
132 
133 public:
134  // Mutex-protected methods of abstract versions below
135 
136  bool openConnection(const std::string & url, bool overwritten = false);
137  void closeConnection(bool save = true, const std::string & outputUrl = "");
138  bool isConnected() const;
139  unsigned long getMemoryUsed() const; // In bytes
140  std::string getDatabaseVersion() const;
141  long getNodesMemoryUsed() const;
142  long getLinksMemoryUsed() const;
143  long getImagesMemoryUsed() const;
144  long getDepthImagesMemoryUsed() const;
145  long getCalibrationsMemoryUsed() const;
146  long getGridsMemoryUsed() const;
147  long getLaserScansMemoryUsed() const;
148  long getUserDataMemoryUsed() const;
149  long getWordsMemoryUsed() const;
150  long getFeaturesMemoryUsed() const;
151  long getStatisticsMemoryUsed() const;
152  int getLastNodesSize() const; // working memory
153  int getLastDictionarySize() const; // working memory
154  int getTotalNodesSize() const;
155  int getTotalDictionarySize() const;
156  ParametersMap getLastParameters() const;
157  std::map<std::string, float> getStatistics(int nodeId, double & stamp, std::vector<int> * wmState=0) const;
158  std::map<int, std::pair<std::map<std::string, float>, double> > getAllStatistics() const;
159  std::map<int, std::vector<int> > getAllStatisticsWmStates() const;
160 
161  void executeNoResult(const std::string & sql) const;
162 
163  // Load objects
164  void load(VWDictionary * dictionary, bool lastStateOnly = true) const;
165  void loadLastNodes(std::list<Signature *> & signatures) const; // returned signatures must be freed after usage
166  Signature * loadSignature(int id, bool * loadedFromTrash = 0); // returned signature must be freed after usage, call loadSignatures() instead if more than one signature should be loaded
167  void loadSignatures(const std::list<int> & ids, std::list<Signature *> & signatures, std::set<int> * loadedFromTrash = 0); // returned signatures must be freed after usage
168  void loadWords(const std::set<int> & wordIds, std::list<VisualWord *> & vws); // returned words must be freed after usage
169 
170  // Specific queries...
171  void loadNodeData(Signature * signature, bool images = true, bool scan = true, bool userData = true, bool occupancyGrid = true) const;
172  void loadNodeData(std::list<Signature *> & signatures, bool images = true, bool scan = true, bool userData = true, bool occupancyGrid = true) const;
173  void getNodeData(int signatureId, SensorData & data, bool images = true, bool scan = true, bool userData = true, bool occupancyGrid = true) const;
174  bool getCalibration(int signatureId, std::vector<CameraModel> & models, std::vector<StereoCameraModel> & stereoModels) const;
175  bool getLaserScanInfo(int signatureId, LaserScan & info) const;
176  bool getNodeInfo(int signatureId, Transform & pose, int & mapId, int & weight, std::string & label, double & stamp, Transform & groundTruthPose, std::vector<float> & velocity, GPS & gps, EnvSensors & sensors) const;
177  void loadLinks(int signatureId, std::multimap<int, Link> & links, Link::Type type = Link::kUndef) const;
178  void getWeight(int signatureId, int & weight) const;
179  void getLastNodeIds(std::set<int> & ids) const;
180  void getAllNodeIds(std::set<int> & ids, bool ignoreChildren = false, bool ignoreBadSignatures = false, bool ignoreIntermediateNodes = false) const;
181  void getAllOdomPoses(std::map<int, Transform> & poses, bool ignoreChildren = false, bool ignoreIntermediateNodes = false) const;
182  void getAllLinks(std::multimap<int, Link> & links, bool ignoreNullLinks = true, bool withLandmarks = false) const;
183  void getLastNodeId(int & id) const;
184  void getLastMapId(int & mapId) const;
185  void getLastWordId(int & id) const;
186  void getInvertedIndexNi(int signatureId, int & ni) const;
187  void getNodesObservingLandmark(int landmarkId, std::map<int, Link> & nodes) const;
188  void getNodeIdByLabel(const std::string & label, int & id) const;
189  void getAllLabels(std::map<int, std::string> & labels) const;
190 
191 protected:
192  DBDriver(const ParametersMap & parameters = ParametersMap());
193 
194  virtual bool connectDatabaseQuery(const std::string & url, bool overwritten = false) = 0;
195  virtual void disconnectDatabaseQuery(bool save = true, const std::string & outputUrl = "") = 0;
196  virtual bool isConnectedQuery() const = 0;
197  virtual unsigned long getMemoryUsedQuery() const = 0; // In bytes
198  virtual bool getDatabaseVersionQuery(std::string & version) const = 0;
199  virtual long getNodesMemoryUsedQuery() const = 0;
200  virtual long getLinksMemoryUsedQuery() const = 0;
201  virtual long getImagesMemoryUsedQuery() const = 0;
202  virtual long getDepthImagesMemoryUsedQuery() const = 0;
203  virtual long getCalibrationsMemoryUsedQuery() const = 0;
204  virtual long getGridsMemoryUsedQuery() const = 0;
205  virtual long getLaserScansMemoryUsedQuery() const = 0;
206  virtual long getUserDataMemoryUsedQuery() const = 0;
207  virtual long getWordsMemoryUsedQuery() const = 0;
208  virtual long getFeaturesMemoryUsedQuery() const = 0;
209  virtual long getStatisticsMemoryUsedQuery() const = 0;
210  virtual int getLastNodesSizeQuery() const = 0;
211  virtual int getLastDictionarySizeQuery() const = 0;
212  virtual int getTotalNodesSizeQuery() const = 0;
213  virtual int getTotalDictionarySizeQuery() const = 0;
214  virtual ParametersMap getLastParametersQuery() const = 0;
215  virtual std::map<std::string, float> getStatisticsQuery(int nodeId, double & stamp, std::vector<int> * wmState) const = 0;
216  virtual std::map<int, std::pair<std::map<std::string, float>, double> > getAllStatisticsQuery() const = 0;
217  virtual std::map<int, std::vector<int> > getAllStatisticsWmStatesQuery() const = 0;
218 
219  virtual void executeNoResultQuery(const std::string & sql) const = 0;
220 
221  virtual void getWeightQuery(int signatureId, int & weight) const = 0;
222 
223  virtual void saveQuery(const std::list<Signature *> & signatures) = 0;
224  virtual void saveQuery(const std::list<VisualWord *> & words) const = 0;
225  virtual void updateQuery(const std::list<Signature *> & signatures, bool updateTimestamp) const = 0;
226  virtual void updateQuery(const std::list<VisualWord *> & words, bool updateTimestamp) const = 0;
227 
228  virtual void addLinkQuery(const Link & link) const = 0;
229  virtual void updateLinkQuery(const Link & link) const = 0;
230 
231  virtual void updateOccupancyGridQuery(
232  int nodeId,
233  const cv::Mat & ground,
234  const cv::Mat & obstacles,
235  const cv::Mat & empty,
236  float cellSize,
237  const cv::Point3f & viewpoint) const = 0;
238 
239  virtual void updateCalibrationQuery(
240  int nodeId,
241  const std::vector<CameraModel> & models,
242  const std::vector<StereoCameraModel> & stereoModels) const = 0;
243 
244  virtual void updateDepthImageQuery(
245  int nodeId,
246  const cv::Mat & image,
247  const std::string & format) const = 0;
248 
249  virtual void updateLaserScanQuery(
250  int nodeId,
251  const LaserScan & scan) const = 0;
252 
253  virtual void addStatisticsQuery(const Statistics & statistics, bool saveWmState) const = 0;
254  virtual void savePreviewImageQuery(const cv::Mat & image) const = 0;
255  virtual cv::Mat loadPreviewImageQuery() const = 0;
256  virtual void saveOptimizedPosesQuery(const std::map<int, Transform> & optimizedPoses, const Transform & lastlocalizationPose) const = 0;
257  virtual std::map<int, Transform> loadOptimizedPosesQuery(Transform * lastlocalizationPose = 0) const = 0;
258  virtual void save2DMapQuery(const cv::Mat & map, float xMin, float yMin, float cellSize) const = 0;
259  virtual cv::Mat load2DMapQuery(float & xMin, float & yMin, float & cellSize) const = 0;
260  virtual void saveOptimizedMeshQuery(
261  const cv::Mat & cloud,
262  const std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > & polygons,
263 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
264  const std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > & texCoords,
265 #else
266  const std::vector<std::vector<Eigen::Vector2f> > & texCoords,
267 #endif
268  const cv::Mat & textures) const = 0;
269  virtual cv::Mat loadOptimizedMeshQuery(
270  std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > * polygons,
271 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
272  std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > * texCoords,
273 #else
274  std::vector<std::vector<Eigen::Vector2f> > * texCoords,
275 #endif
276  cv::Mat * textures) const = 0;
277 
278  // Load objects
279  virtual void loadQuery(VWDictionary * dictionary, bool lastStateOnly = true) const = 0;
280  virtual void loadLastNodesQuery(std::list<Signature *> & signatures) const = 0;
281  virtual void loadSignaturesQuery(const std::list<int> & ids, std::list<Signature *> & signatures) const = 0;
282  virtual void loadWordsQuery(const std::set<int> & wordIds, std::list<VisualWord *> & vws) const = 0;
283  virtual void loadLinksQuery(int signatureId, std::multimap<int, Link> & links, Link::Type type = Link::kUndef) const = 0;
284 
285  virtual void loadNodeDataQuery(std::list<Signature *> & signatures, bool images=true, bool scan=true, bool userData=true, bool occupancyGrid=true) const = 0;
286  virtual bool getCalibrationQuery(int signatureId, std::vector<CameraModel> & models, std::vector<StereoCameraModel> & stereoModels) const = 0;
287  virtual bool getLaserScanInfoQuery(int signatureId, LaserScan & info) const = 0;
288  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 = 0;
289  virtual void getLastNodeIdsQuery(std::set<int> & ids) const = 0;
290  virtual void getAllNodeIdsQuery(std::set<int> & ids, bool ignoreChildren, bool ignoreBadSignatures, bool ignoreIntermediateNodes) const = 0;
291  virtual void getAllOdomPosesQuery(std::map<int, Transform> & poses, bool ignoreChildren, bool ignoreIntermediateNodes) const = 0;
292  virtual void getAllLinksQuery(std::multimap<int, Link> & links, bool ignoreNullLinks, bool withLandmarks) const = 0;
293  virtual void getLastIdQuery(const std::string & tableName, int & id, const std::string & fieldName="id") const = 0;
294  virtual void getInvertedIndexNiQuery(int signatureId, int & ni) const = 0;
295  virtual void getNodesObservingLandmarkQuery(int landmarkId, std::map<int, Link> & nodes) const = 0;
296  virtual void getNodeIdByLabelQuery(const std::string & label, int & id) const = 0;
297  virtual void getAllLabelsQuery(std::map<int, std::string> & labels) const = 0;
298 
299 private:
300  //non-abstract methods
301  void saveOrUpdate(const std::vector<Signature *> & signatures);
302  void saveOrUpdate(const std::vector<VisualWord *> & words) const;
303 
304  //thread stuff
305  virtual void mainLoop();
306 
307 private:
309  std::map<int, Signature *> _trashSignatures;//<id, Signature*>
310  std::map<int, VisualWord *> _trashVisualWords; //<id, VisualWord*>
315  std::string _url;
316  std::string _targetVersion;
318 };
319 
320 }
321 
322 #endif /* DBDRIVER_H_ */
rtabmap::SensorData
Definition: SensorData.h:51
rtabmap::DBDriver::_trashVisualWords
std::map< int, VisualWord * > _trashVisualWords
Definition: DBDriver.h:310
create
ADT create(const Signature &signature)
rtabmap::Statistics
Definition: Statistics.h:53
UThreadNode.h
rtabmap::DBDriver::_timestampUpdate
bool _timestampUpdate
Definition: DBDriver.h:317
rtabmap::DBDriver::_trashSignatures
std::map< int, Signature * > _trashSignatures
Definition: DBDriver.h:309
SensorData.h
rtabmap::GPS
Definition: GPS.h:35
Transform.h
type
rtabmap::LaserScan
Definition: LaserScan.h:37
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
rtabmap::VisualWord
Definition: VisualWord.h:38
Parameters.h
rtabmap::DBDriver::_emptyTrashesTime
double _emptyTrashesTime
Definition: DBDriver.h:314
rtabmap::DBDriver::setTimestampUpdateEnabled
void setTimestampUpdateEnabled(bool enabled)
Definition: DBDriver.h:82
rtabmap::DBDriver::_url
std::string _url
Definition: DBDriver.h:315
rtabmap::DBDriver::isInMemory
virtual bool isInMemory() const
Definition: DBDriver.h:71
Eigen::aligned_allocator
UMutex
Definition: UMutex.h:54
rtabmap::DBDriver::_transactionMutex
UMutex _transactionMutex
Definition: DBDriver.h:308
rtabmap::DBDriver::getUrl
const std::string & getUrl() const
Definition: DBDriver.h:72
UMutex.h
rtabmap::DBDriver::_targetVersion
std::string _targetVersion
Definition: DBDriver.h:316
rtabmap::DBDriver::getTargetVersion
const std::string & getTargetVersion() const
Definition: DBDriver.h:73
rtabmap::DBDriver
Definition: DBDriver.h:62
rtabmap::Transform
Definition: Transform.h:41
empty
rtabmap::VWDictionary
Definition: VWDictionary.h:46
UThread
Definition: UThread.h:86
rtabmap::EnvSensors
std::map< EnvSensor::Type, EnvSensor > EnvSensors
Definition: EnvSensor.h:81
rtabmap::DBDriver::_dbSafeAccessMutex
UMutex _dbSafeAccessMutex
Definition: DBDriver.h:312
rtabmap::DBDriver::_addSem
USemaphore _addSem
Definition: DBDriver.h:313
USemaphore
Definition: USemaphore.h:54
Statistics.h
rtabmap::DBDriver::_trashesMutex
UMutex _trashesMutex
Definition: DBDriver.h:311
rtabmap::DBDriver::getEmptyTrashesTime
double getEmptyTrashesTime() const
Definition: DBDriver.h:81
rtabmap
Definition: CameraARCore.cpp:35
load
NearestNeighbourSearch< T >::Matrix load(const char *fileName)
rtabmap::Signature
Definition: Signature.h:48


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