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 updateDepthImage(
int nodeId,
const cv::Mat & image);
100 void updateLaserScan(
int nodeId,
const LaserScan & scan);
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> > >(),
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> > >(),
117 const std::vector<std::vector<Eigen::Vector2f> > & texCoords = std::vector<std::vector<Eigen::Vector2f> >(),
119 const cv::Mat & textures = cv::Mat())
const;
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,
125 std::vector<std::vector<Eigen::Vector2f> > * texCoords = 0,
127 cv::Mat * textures = 0)
const;
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;
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;
149 int getLastDictionarySize()
const;
150 int getTotalNodesSize()
const;
151 int getTotalDictionarySize()
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;
157 void executeNoResult(
const std::string & sql)
const;
161 void loadLastNodes(std::list<Signature *> & signatures)
const;
162 Signature * loadSignature(
int id,
bool * loadedFromTrash = 0);
163 void loadSignatures(
const std::list<int> & ids, std::list<Signature *> & signatures, std::set<int> * loadedFromTrash = 0);
164 void loadWords(
const std::set<int> & wordIds, std::list<VisualWord *> & vws);
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, std::vector<StereoCameraModel> & stereoModels)
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;
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,
bool ignoreIntermediateNodes =
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;
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;
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;
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;
214 virtual void executeNoResultQuery(
const std::string & sql)
const = 0;
216 virtual void getWeightQuery(
int signatureId,
int & weight)
const = 0;
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;
223 virtual void addLinkQuery(
const Link & link)
const = 0;
224 virtual void updateLinkQuery(
const Link & link)
const = 0;
226 virtual void updateOccupancyGridQuery(
228 const cv::Mat & ground,
229 const cv::Mat & obstacles,
230 const cv::Mat & empty,
232 const cv::Point3f & viewpoint)
const = 0;
234 virtual void updateDepthImageQuery(
236 const cv::Mat & image)
const = 0;
238 virtual void updateLaserScanQuery(
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,
255 const std::vector<std::vector<Eigen::Vector2f> > & texCoords,
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,
263 std::vector<std::vector<Eigen::Vector2f> > * texCoords,
265 cv::Mat * textures)
const = 0;
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;
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, std::vector<StereoCameraModel> & stereoModels)
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,
bool ignoreIntermediateNodes)
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;
289 void saveOrUpdate(
const std::vector<Signature *> & signatures);
290 void saveOrUpdate(
const std::vector<VisualWord *> & words)
const;
293 virtual void mainLoop();
UMutex _dbSafeAccessMutex
std::string _targetVersion
const std::string & getTargetVersion() const
std::map< int, Signature * > _trashSignatures
virtual bool isInMemory() const
std::map< std::string, std::string > ParametersMap
double getEmptyTrashesTime() const
std::map< int, VisualWord * > _trashVisualWords
void setTimestampUpdateEnabled(bool enabled)
std::map< EnvSensor::Type, EnvSensor > EnvSensors
NearestNeighbourSearch< T >::Matrix load(const char *fileName)
const std::string & getUrl() const