31 #include "rtabmap/core/rtabmap_core_export.h"
37 #include <opencv2/core/core.hpp>
70 virtual void parseParameters(
const ParametersMap & parameters);
72 const std::string &
getUrl()
const {
return _url;}
75 void beginTransaction()
const;
80 void emptyTrashes(
bool async =
false);
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(
94 const cv::Mat & ground,
95 const cv::Mat & obstacles,
96 const cv::Mat &
empty,
98 const cv::Point3f & viewpoint);
99 void updateCalibration(
101 const std::vector<CameraModel> & models,
102 const std::vector<StereoCameraModel> & stereoModels);
103 void updateDepthImage(
int nodeId,
const cv::Mat & image);
104 void updateLaserScan(
int nodeId,
const LaserScan & scan);
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> > >(),
118 #
if PCL_VERSION_COMPARE(>=, 1, 8, 0)
121 const std::vector<std::vector<Eigen::Vector2f> > & texCoords = std::vector<std::vector<Eigen::Vector2f> >(),
123 const cv::Mat & textures = cv::Mat())
const;
124 cv::Mat loadOptimizedMesh(
125 std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > * polygons = 0,
126 #
if PCL_VERSION_COMPARE(>=, 1, 8, 0)
129 std::vector<std::vector<Eigen::Vector2f> > * texCoords = 0,
131 cv::Mat * textures = 0)
const;
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;
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;
153 int getLastDictionarySize()
const;
154 int getTotalNodesSize()
const;
155 int getTotalDictionarySize()
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;
161 void executeNoResult(
const std::string & sql)
const;
165 void loadLastNodes(std::list<Signature *> & signatures)
const;
166 Signature * loadSignature(
int id,
bool * loadedFromTrash = 0);
167 void loadSignatures(
const std::list<int> & ids, std::list<Signature *> & signatures, std::set<int> * loadedFromTrash = 0);
168 void loadWords(
const std::set<int> & wordIds, std::list<VisualWord *> & vws);
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;
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 getAllLinks(std::multimap<int, Link> & links,
bool ignoreNullLinks =
true,
bool withLandmarks =
false)
const;
182 void getLastNodeId(
int &
id)
const;
183 void getLastMapId(
int & mapId)
const;
184 void getLastWordId(
int &
id)
const;
185 void getInvertedIndexNi(
int signatureId,
int & ni)
const;
186 void getNodesObservingLandmark(
int landmarkId, std::map<int, Link> & nodes)
const;
187 void getNodeIdByLabel(
const std::string & label,
int &
id)
const;
188 void getAllLabels(std::map<int, std::string> & labels)
const;
193 virtual bool connectDatabaseQuery(
const std::string & url,
bool overwritten =
false) = 0;
194 virtual void disconnectDatabaseQuery(
bool save =
true,
const std::string & outputUrl =
"") = 0;
195 virtual bool isConnectedQuery()
const = 0;
196 virtual unsigned long getMemoryUsedQuery()
const = 0;
197 virtual bool getDatabaseVersionQuery(std::string & version)
const = 0;
198 virtual long getNodesMemoryUsedQuery()
const = 0;
199 virtual long getLinksMemoryUsedQuery()
const = 0;
200 virtual long getImagesMemoryUsedQuery()
const = 0;
201 virtual long getDepthImagesMemoryUsedQuery()
const = 0;
202 virtual long getCalibrationsMemoryUsedQuery()
const = 0;
203 virtual long getGridsMemoryUsedQuery()
const = 0;
204 virtual long getLaserScansMemoryUsedQuery()
const = 0;
205 virtual long getUserDataMemoryUsedQuery()
const = 0;
206 virtual long getWordsMemoryUsedQuery()
const = 0;
207 virtual long getFeaturesMemoryUsedQuery()
const = 0;
208 virtual long getStatisticsMemoryUsedQuery()
const = 0;
209 virtual int getLastNodesSizeQuery()
const = 0;
210 virtual int getLastDictionarySizeQuery()
const = 0;
211 virtual int getTotalNodesSizeQuery()
const = 0;
212 virtual int getTotalDictionarySizeQuery()
const = 0;
214 virtual std::map<std::string, float> getStatisticsQuery(
int nodeId,
double & stamp, std::vector<int> * wmState)
const = 0;
215 virtual std::map<int, std::pair<std::map<std::string, float>,
double> > getAllStatisticsQuery()
const = 0;
216 virtual std::map<int, std::vector<int> > getAllStatisticsWmStatesQuery()
const = 0;
218 virtual void executeNoResultQuery(
const std::string & sql)
const = 0;
220 virtual void getWeightQuery(
int signatureId,
int & weight)
const = 0;
222 virtual void saveQuery(
const std::list<Signature *> & signatures) = 0;
223 virtual void saveQuery(
const std::list<VisualWord *> & words)
const = 0;
224 virtual void updateQuery(
const std::list<Signature *> & signatures,
bool updateTimestamp)
const = 0;
225 virtual void updateQuery(
const std::list<VisualWord *> & words,
bool updateTimestamp)
const = 0;
227 virtual void addLinkQuery(
const Link & link)
const = 0;
228 virtual void updateLinkQuery(
const Link & link)
const = 0;
230 virtual void updateOccupancyGridQuery(
232 const cv::Mat & ground,
233 const cv::Mat & obstacles,
234 const cv::Mat &
empty,
236 const cv::Point3f & viewpoint)
const = 0;
238 virtual void updateCalibrationQuery(
240 const std::vector<CameraModel> & models,
241 const std::vector<StereoCameraModel> & stereoModels)
const = 0;
243 virtual void updateDepthImageQuery(
245 const cv::Mat & image)
const = 0;
247 virtual void updateLaserScanQuery(
251 virtual void addStatisticsQuery(
const Statistics & statistics,
bool saveWmState)
const = 0;
252 virtual void savePreviewImageQuery(
const cv::Mat & image)
const = 0;
253 virtual cv::Mat loadPreviewImageQuery()
const = 0;
254 virtual void saveOptimizedPosesQuery(
const std::map<int, Transform> & optimizedPoses,
const Transform & lastlocalizationPose)
const = 0;
255 virtual std::map<int, Transform> loadOptimizedPosesQuery(
Transform * lastlocalizationPose = 0)
const = 0;
256 virtual void save2DMapQuery(
const cv::Mat & map,
float xMin,
float yMin,
float cellSize)
const = 0;
257 virtual cv::Mat load2DMapQuery(
float & xMin,
float & yMin,
float & cellSize)
const = 0;
258 virtual void saveOptimizedMeshQuery(
259 const cv::Mat & cloud,
260 const std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > & polygons,
261 #
if PCL_VERSION_COMPARE(>=, 1, 8, 0)
264 const std::vector<std::vector<Eigen::Vector2f> > & texCoords,
266 const cv::Mat & textures)
const = 0;
267 virtual cv::Mat loadOptimizedMeshQuery(
268 std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > * polygons,
269 #
if PCL_VERSION_COMPARE(>=, 1, 8, 0)
272 std::vector<std::vector<Eigen::Vector2f> > * texCoords,
274 cv::Mat * textures)
const = 0;
277 virtual void loadQuery(
VWDictionary * dictionary,
bool lastStateOnly =
true)
const = 0;
278 virtual void loadLastNodesQuery(std::list<Signature *> & signatures)
const = 0;
279 virtual void loadSignaturesQuery(
const std::list<int> & ids, std::list<Signature *> & signatures)
const = 0;
280 virtual void loadWordsQuery(
const std::set<int> & wordIds, std::list<VisualWord *> & vws)
const = 0;
283 virtual void loadNodeDataQuery(std::list<Signature *> & signatures,
bool images=
true,
bool scan=
true,
bool userData=
true,
bool occupancyGrid=
true)
const = 0;
284 virtual bool getCalibrationQuery(
int signatureId, std::vector<CameraModel> & models, std::vector<StereoCameraModel> & stereoModels)
const = 0;
285 virtual bool getLaserScanInfoQuery(
int signatureId,
LaserScan & info)
const = 0;
286 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;
287 virtual void getLastNodeIdsQuery(std::set<int> & ids)
const = 0;
288 virtual void getAllNodeIdsQuery(std::set<int> & ids,
bool ignoreChildren,
bool ignoreBadSignatures,
bool ignoreIntermediateNodes)
const = 0;
289 virtual void getAllLinksQuery(std::multimap<int, Link> & links,
bool ignoreNullLinks,
bool withLandmarks)
const = 0;
290 virtual void getLastIdQuery(
const std::string & tableName,
int &
id,
const std::string & fieldName=
"id")
const = 0;
291 virtual void getInvertedIndexNiQuery(
int signatureId,
int & ni)
const = 0;
292 virtual void getNodesObservingLandmarkQuery(
int landmarkId, std::map<int, Link> & nodes)
const = 0;
293 virtual void getNodeIdByLabelQuery(
const std::string & label,
int &
id)
const = 0;
294 virtual void getAllLabelsQuery(std::map<int, std::string> & labels)
const = 0;
298 void saveOrUpdate(
const std::vector<Signature *> & signatures);
299 void saveOrUpdate(
const std::vector<VisualWord *> & words)
const;
302 virtual void mainLoop();