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


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