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/RtabmapExp.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 //
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 updateDepthImage(int nodeId, const cv::Mat & image);
100  void updateLaserScan(int nodeId, const LaserScan & scan);
101 
102 public:
103  void addInfoAfterRun(int stMemSize, int lastSignAdded, int processMemUsed, int databaseMemUsed, int dictionarySize, const ParametersMap & parameters) const;
104  void addStatistics(const Statistics & statistics, bool saveWmState) const;
105  void savePreviewImage(const cv::Mat & image) const;
106  cv::Mat loadPreviewImage() const;
107  void saveOptimizedPoses(const std::map<int, Transform> & optimizedPoses, const Transform & lastlocalizationPose) const;
108  std::map<int, Transform> loadOptimizedPoses(Transform * lastlocalizationPose = 0) const;
109  void save2DMap(const cv::Mat & map, float xMin, float yMin, float cellSize) const;
110  cv::Mat load2DMap(float & xMin, float & yMin, float & cellSize) const;
111  void saveOptimizedMesh(
112  const cv::Mat & cloud,
113  const std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > & polygons = std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > >(), // Textures -> polygons -> vertices
114 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
115  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
116 #else
117  const std::vector<std::vector<Eigen::Vector2f> > & texCoords = std::vector<std::vector<Eigen::Vector2f> >(), // Textures -> uv coords for each vertex of the polygons
118 #endif
119  const cv::Mat & textures = cv::Mat()) const; // concatenated textures (assuming square textures with all same size);
120  cv::Mat loadOptimizedMesh(
121  std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > * polygons = 0,
122 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
123  std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > * texCoords = 0,
124 #else
125  std::vector<std::vector<Eigen::Vector2f> > * texCoords = 0,
126 #endif
127  cv::Mat * textures = 0) const;
128 
129 public:
130  // Mutex-protected methods of abstract versions below
131 
132  bool openConnection(const std::string & url, bool overwritten = false);
133  void closeConnection(bool save = true, const std::string & outputUrl = "");
134  bool isConnected() const;
135  unsigned long getMemoryUsed() const; // In bytes
136  std::string getDatabaseVersion() const;
137  long getNodesMemoryUsed() const;
138  long getLinksMemoryUsed() const;
139  long getImagesMemoryUsed() const;
140  long getDepthImagesMemoryUsed() const;
141  long getCalibrationsMemoryUsed() const;
142  long getGridsMemoryUsed() const;
143  long getLaserScansMemoryUsed() const;
144  long getUserDataMemoryUsed() const;
145  long getWordsMemoryUsed() const;
146  long getFeaturesMemoryUsed() const;
147  long getStatisticsMemoryUsed() const;
148  int getLastNodesSize() const; // working memory
149  int getLastDictionarySize() const; // working memory
150  int getTotalNodesSize() const;
151  int getTotalDictionarySize() const;
152  ParametersMap getLastParameters() const;
153  std::map<std::string, float> getStatistics(int nodeId, double & stamp, std::vector<int> * wmState=0) const;
154  std::map<int, std::pair<std::map<std::string, float>, double> > getAllStatistics() const;
155  std::map<int, std::vector<int> > getAllStatisticsWmStates() const;
156 
157  void executeNoResult(const std::string & sql) const;
158 
159  // Load objects
160  void load(VWDictionary * dictionary, bool lastStateOnly = true) const;
161  void loadLastNodes(std::list<Signature *> & signatures) const; // returned signatures must be freed after usage
162  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
163  void loadSignatures(const std::list<int> & ids, std::list<Signature *> & signatures, std::set<int> * loadedFromTrash = 0); // returned signatures must be freed after usage
164  void loadWords(const std::set<int> & wordIds, std::list<VisualWord *> & vws); // returned words must be freed after usage
165 
166  // Specific queries...
167  void loadNodeData(Signature * signature, bool images = true, bool scan = true, bool userData = true, bool occupancyGrid = true) const;
168  void loadNodeData(std::list<Signature *> & signatures, bool images = true, bool scan = true, bool userData = true, bool occupancyGrid = true) const;
169  void getNodeData(int signatureId, SensorData & data, bool images = true, bool scan = true, bool userData = true, bool occupancyGrid = true) const;
170  bool getCalibration(int signatureId, std::vector<CameraModel> & models, StereoCameraModel & stereoModel) const;
171  bool getLaserScanInfo(int signatureId, LaserScan & info) const;
172  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;
173  void loadLinks(int signatureId, std::multimap<int, Link> & links, Link::Type type = Link::kUndef) const;
174  void getWeight(int signatureId, int & weight) const;
175  void getLastNodeIds(std::set<int> & ids) const;
176  void getAllNodeIds(std::set<int> & ids, bool ignoreChildren = false, bool ignoreBadSignatures = false) const;
177  void getAllLinks(std::multimap<int, Link> & links, bool ignoreNullLinks = true, bool withLandmarks = false) const;
178  void getLastNodeId(int & id) const;
179  void getLastMapId(int & mapId) const;
180  void getLastWordId(int & id) const;
181  void getInvertedIndexNi(int signatureId, int & ni) const;
182  void getNodesObservingLandmark(int landmarkId, std::map<int, Link> & nodes) const;
183  void getNodeIdByLabel(const std::string & label, int & id) const;
184  void getAllLabels(std::map<int, std::string> & labels) const;
185 
186 protected:
187  DBDriver(const ParametersMap & parameters = ParametersMap());
188 
189  virtual bool connectDatabaseQuery(const std::string & url, bool overwritten = false) = 0;
190  virtual void disconnectDatabaseQuery(bool save = true, const std::string & outputUrl = "") = 0;
191  virtual bool isConnectedQuery() const = 0;
192  virtual unsigned long getMemoryUsedQuery() const = 0; // In bytes
193  virtual bool getDatabaseVersionQuery(std::string & version) const = 0;
194  virtual long getNodesMemoryUsedQuery() const = 0;
195  virtual long getLinksMemoryUsedQuery() const = 0;
196  virtual long getImagesMemoryUsedQuery() const = 0;
197  virtual long getDepthImagesMemoryUsedQuery() const = 0;
198  virtual long getCalibrationsMemoryUsedQuery() const = 0;
199  virtual long getGridsMemoryUsedQuery() const = 0;
200  virtual long getLaserScansMemoryUsedQuery() const = 0;
201  virtual long getUserDataMemoryUsedQuery() const = 0;
202  virtual long getWordsMemoryUsedQuery() const = 0;
203  virtual long getFeaturesMemoryUsedQuery() const = 0;
204  virtual long getStatisticsMemoryUsedQuery() const = 0;
205  virtual int getLastNodesSizeQuery() const = 0;
206  virtual int getLastDictionarySizeQuery() const = 0;
207  virtual int getTotalNodesSizeQuery() const = 0;
208  virtual int getTotalDictionarySizeQuery() const = 0;
209  virtual ParametersMap getLastParametersQuery() const = 0;
210  virtual std::map<std::string, float> getStatisticsQuery(int nodeId, double & stamp, std::vector<int> * wmState) const = 0;
211  virtual std::map<int, std::pair<std::map<std::string, float>, double> > getAllStatisticsQuery() const = 0;
212  virtual std::map<int, std::vector<int> > getAllStatisticsWmStatesQuery() const = 0;
213 
214  virtual void executeNoResultQuery(const std::string & sql) const = 0;
215 
216  virtual void getWeightQuery(int signatureId, int & weight) const = 0;
217 
218  virtual void saveQuery(const std::list<Signature *> & signatures) = 0;
219  virtual void saveQuery(const std::list<VisualWord *> & words) const = 0;
220  virtual void updateQuery(const std::list<Signature *> & signatures, bool updateTimestamp) const = 0;
221  virtual void updateQuery(const std::list<VisualWord *> & words, bool updateTimestamp) const = 0;
222 
223  virtual void addLinkQuery(const Link & link) const = 0;
224  virtual void updateLinkQuery(const Link & link) const = 0;
225 
226  virtual void updateOccupancyGridQuery(
227  int nodeId,
228  const cv::Mat & ground,
229  const cv::Mat & obstacles,
230  const cv::Mat & empty,
231  float cellSize,
232  const cv::Point3f & viewpoint) const = 0;
233 
234  virtual void updateDepthImageQuery(
235  int nodeId,
236  const cv::Mat & image) const = 0;
237 
238  virtual void updateLaserScanQuery(
239  int nodeId,
240  const LaserScan & scan) const = 0;
241 
242  virtual void addStatisticsQuery(const Statistics & statistics, bool saveWmState) const = 0;
243  virtual void savePreviewImageQuery(const cv::Mat & image) const = 0;
244  virtual cv::Mat loadPreviewImageQuery() const = 0;
245  virtual void saveOptimizedPosesQuery(const std::map<int, Transform> & optimizedPoses, const Transform & lastlocalizationPose) const = 0;
246  virtual std::map<int, Transform> loadOptimizedPosesQuery(Transform * lastlocalizationPose = 0) const = 0;
247  virtual void save2DMapQuery(const cv::Mat & map, float xMin, float yMin, float cellSize) const = 0;
248  virtual cv::Mat load2DMapQuery(float & xMin, float & yMin, float & cellSize) const = 0;
249  virtual void saveOptimizedMeshQuery(
250  const cv::Mat & cloud,
251  const std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > & polygons,
252 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
253  const std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > & texCoords,
254 #else
255  const std::vector<std::vector<Eigen::Vector2f> > & texCoords,
256 #endif
257  const cv::Mat & textures) const = 0;
258  virtual cv::Mat loadOptimizedMeshQuery(
259  std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > * polygons,
260 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
261  std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > * texCoords,
262 #else
263  std::vector<std::vector<Eigen::Vector2f> > * texCoords,
264 #endif
265  cv::Mat * textures) const = 0;
266 
267  // Load objects
268  virtual void loadQuery(VWDictionary * dictionary, bool lastStateOnly = true) const = 0;
269  virtual void loadLastNodesQuery(std::list<Signature *> & signatures) const = 0;
270  virtual void loadSignaturesQuery(const std::list<int> & ids, std::list<Signature *> & signatures) const = 0;
271  virtual void loadWordsQuery(const std::set<int> & wordIds, std::list<VisualWord *> & vws) const = 0;
272  virtual void loadLinksQuery(int signatureId, std::multimap<int, Link> & links, Link::Type type = Link::kUndef) const = 0;
273 
274  virtual void loadNodeDataQuery(std::list<Signature *> & signatures, bool images=true, bool scan=true, bool userData=true, bool occupancyGrid=true) const = 0;
275  virtual bool getCalibrationQuery(int signatureId, std::vector<CameraModel> & models, StereoCameraModel & stereoModel) const = 0;
276  virtual bool getLaserScanInfoQuery(int signatureId, LaserScan & info) const = 0;
277  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;
278  virtual void getLastNodeIdsQuery(std::set<int> & ids) const = 0;
279  virtual void getAllNodeIdsQuery(std::set<int> & ids, bool ignoreChildren, bool ignoreBadSignatures) const = 0;
280  virtual void getAllLinksQuery(std::multimap<int, Link> & links, bool ignoreNullLinks, bool withLandmarks) const = 0;
281  virtual void getLastIdQuery(const std::string & tableName, int & id, const std::string & fieldName="id") const = 0;
282  virtual void getInvertedIndexNiQuery(int signatureId, int & ni) const = 0;
283  virtual void getNodesObservingLandmarkQuery(int landmarkId, std::map<int, Link> & nodes) const = 0;
284  virtual void getNodeIdByLabelQuery(const std::string & label, int & id) const = 0;
285  virtual void getAllLabelsQuery(std::map<int, std::string> & labels) const = 0;
286 
287 private:
288  //non-abstract methods
289  void saveOrUpdate(const std::vector<Signature *> & signatures);
290  void saveOrUpdate(const std::vector<VisualWord *> & words) const;
291 
292  //thread stuff
293  virtual void mainLoop();
294 
295 private:
297  std::map<int, Signature *> _trashSignatures;//<id, Signature*>
298  std::map<int, VisualWord *> _trashVisualWords; //<id, VisualWord*>
303  std::string _url;
304  std::string _targetVersion;
306 };
307 
308 }
309 
310 #endif /* DBDRIVER_H_ */
UMutex _dbSafeAccessMutex
Definition: DBDriver.h:300
std::string _targetVersion
Definition: DBDriver.h:304
const std::string & getTargetVersion() const
Definition: DBDriver.h:73
std::map< int, Signature * > _trashSignatures
Definition: DBDriver.h:297
USemaphore _addSem
Definition: DBDriver.h:301
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
UMutex _trashesMutex
Definition: DBDriver.h:299
const std::string & getUrl() const
Definition: DBDriver.h:72
double getEmptyTrashesTime() const
Definition: DBDriver.h:81
bool _timestampUpdate
Definition: DBDriver.h:305
#define RTABMAP_EXP
Definition: RtabmapExp.h:38
Definition: UMutex.h:54
std::string _url
Definition: DBDriver.h:303
std::map< int, VisualWord * > _trashVisualWords
Definition: DBDriver.h:298
void setTimestampUpdateEnabled(bool enabled)
Definition: DBDriver.h:82
double _emptyTrashesTime
Definition: DBDriver.h:302
std::map< EnvSensor::Type, EnvSensor > EnvSensors
Definition: EnvSensor.h:81
virtual bool isInMemory() const
Definition: DBDriver.h:71
UMutex _transactionMutex
Definition: DBDriver.h:296


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