DBDriver.cpp
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 #include "rtabmap/core/DBDriver.h"
29 
30 #include "rtabmap/core/Signature.h"
34 #include "rtabmap/utilite/UMath.h"
36 #include "rtabmap/utilite/UTimer.h"
37 #include "rtabmap/utilite/UStl.h"
38 
39 namespace rtabmap {
40 
42 {
43  return new DBDriverSqlite3(parameters);
44 }
45 
46 DBDriver::DBDriver(const ParametersMap & parameters) :
49 {
50  this->parseParameters(parameters);
51 }
52 
54 {
55  join(true);
56  this->emptyTrashes();
57 }
58 
59 void DBDriver::parseParameters(const ParametersMap & parameters)
60 {
61  Parameters::parse(parameters, Parameters::kDbTargetVersion(), _targetVersion);
62 }
63 
64 void DBDriver::closeConnection(bool save, const std::string & outputUrl)
65 {
66  UDEBUG("isRunning=%d", this->isRunning());
67  this->join(true);
68  UDEBUG("");
69  if(save)
70  {
71  this->emptyTrashes();
72  }
73  else
74  {
76  _trashSignatures.clear();
77  _trashVisualWords.clear();
79  }
81  this->disconnectDatabaseQuery(save, outputUrl);
83  UDEBUG("");
84 }
85 
86 bool DBDriver::openConnection(const std::string & url, bool overwritten)
87 {
88  UDEBUG("");
89  _url = url;
91  if(this->connectDatabaseQuery(url, overwritten))
92  {
94  return true;
95  }
97  return false;
98 }
99 
101 {
102  bool r;
104  r = isConnectedQuery();
106  return r;
107 }
108 
109 // In bytes
110 unsigned long DBDriver::getMemoryUsed() const
111 {
112  unsigned long bytes;
114  bytes = getMemoryUsedQuery();
116  return bytes;
117 }
118 
120 {
121  long bytes;
123  bytes = getNodesMemoryUsedQuery();
125  return bytes;
126 }
128 {
129  long bytes;
131  bytes = getLinksMemoryUsedQuery();
133  return bytes;
134 }
136 {
137  long bytes;
139  bytes = getImagesMemoryUsedQuery();
141  return bytes;
142 }
144 {
145  long bytes;
149  return bytes;
150 }
152 {
153  long bytes;
157  return bytes;
158 }
160 {
161  long bytes;
163  bytes = getGridsMemoryUsedQuery();
165  return bytes;
166 }
168 {
169  long bytes;
173  return bytes;
174 }
176 {
177  long bytes;
179  bytes = getUserDataMemoryUsedQuery();
181  return bytes;
182 }
184 {
185  long bytes;
187  bytes = getWordsMemoryUsedQuery();
189  return bytes;
190 }
192 {
193  long bytes;
195  bytes = getFeaturesMemoryUsedQuery();
197  return bytes;
198 }
200 {
201  long bytes;
205  return bytes;
206 }
208 {
209  int nodes;
211  nodes = getLastNodesSizeQuery();
213  return nodes;
214 }
216 {
217  int words;
219  words = getLastDictionarySizeQuery();
221  return words;
222 }
224 {
225  int words;
227  words = getTotalNodesSizeQuery();
229  return words;
230 }
232 {
233  int words;
235  words = getTotalDictionarySizeQuery();
237  return words;
238 }
240 {
241  ParametersMap parameters;
243  parameters = getLastParametersQuery();
245  return parameters;
246 }
247 
248 std::map<std::string, float> DBDriver::getStatistics(int nodeId, double & stamp, std::vector<int> * wmState) const
249 {
250  std::map<std::string, float> statistics;
252  statistics = getStatisticsQuery(nodeId, stamp, wmState);
254  return statistics;
255 }
256 
257 std::map<int, std::pair<std::map<std::string, float>, double> > DBDriver::getAllStatistics() const
258 {
259  std::map<int, std::pair<std::map<std::string, float>, double> > statistics;
261  statistics = getAllStatisticsQuery();
263  return statistics;
264 }
265 
266 std::map<int, std::vector<int> > DBDriver::getAllStatisticsWmStates() const
267 {
268  std::map<int, std::vector<int> > wmStates;
270  wmStates = getAllStatisticsWmStatesQuery();
272  return wmStates;
273 }
274 
275 std::string DBDriver::getDatabaseVersion() const
276 {
277  std::string version = "0.0.0";
279  getDatabaseVersionQuery(version);
281  return version;
282 }
283 
285 {
286  this->emptyTrashes();
287  this->kill(); // Do it only once
288 }
289 
291 {
293  ULOGGER_DEBUG("");
294  this->executeNoResultQuery("BEGIN TRANSACTION;");
295 }
296 
297 void DBDriver::commit() const
298 {
299  ULOGGER_DEBUG("");
300  this->executeNoResultQuery("COMMIT;");
302 }
303 
304 void DBDriver::executeNoResult(const std::string & sql) const
305 {
307  this->executeNoResultQuery(sql);
309 }
310 
311 void DBDriver::emptyTrashes(bool async)
312 {
313  if(async)
314  {
315  ULOGGER_DEBUG("Async emptying, start the trash thread");
316  this->start();
317  return;
318  }
319 
320  UTimer totalTime;
321  totalTime.start();
322 
323  std::map<int, Signature*> signatures;
324  std::map<int, VisualWord*> visualWords;
326  {
327  ULOGGER_DEBUG("signatures=%d, visualWords=%d", _trashSignatures.size(), _trashVisualWords.size());
328  signatures = _trashSignatures;
329  visualWords = _trashVisualWords;
330  _trashSignatures.clear();
331  _trashVisualWords.clear();
332 
334  }
336 
337  if(signatures.size() || visualWords.size())
338  {
339  this->beginTransaction();
340  UTimer timer;
341  timer.start();
342  if(signatures.size())
343  {
344  if(this->isConnected())
345  {
346  //Only one query to the database
347  this->saveOrUpdate(uValues(signatures));
348  }
349 
350  for(std::map<int, Signature *>::iterator iter=signatures.begin(); iter!=signatures.end(); ++iter)
351  {
352  delete iter->second;
353  }
354  signatures.clear();
355  ULOGGER_DEBUG("Time emptying memory signatures trash = %f...", timer.ticks());
356  }
357  if(visualWords.size())
358  {
359  if(this->isConnected())
360  {
361  //Only one query to the database
362  this->saveOrUpdate(uValues(visualWords));
363  }
364 
365  for(std::map<int, VisualWord *>::iterator iter=visualWords.begin(); iter!=visualWords.end(); ++iter)
366  {
367  delete (*iter).second;
368  }
369  visualWords.clear();
370  ULOGGER_DEBUG("Time emptying memory visualWords trash = %f...", timer.ticks());
371  }
372 
373  this->commit();
374  }
375 
376  _emptyTrashesTime = totalTime.ticks();
377  ULOGGER_DEBUG("Total time emptying trashes = %fs...", _emptyTrashesTime);
378 
380 }
381 
383 {
384  if(s)
385  {
386  UDEBUG("s=%d", s->id());
388  {
389  _trashSignatures.insert(std::pair<int, Signature*>(s->id(), s));
390  }
392  }
393 }
394 
396 {
397  if(vw)
398  {
400  {
401  _trashVisualWords.insert(std::pair<int, VisualWord*>(vw->id(), vw));
402  }
404  }
405 }
406 
407 void DBDriver::saveOrUpdate(const std::vector<Signature *> & signatures)
408 {
409  ULOGGER_DEBUG("");
410  std::list<Signature *> toSave;
411  std::list<Signature *> toUpdate;
412  if(this->isConnected() && signatures.size())
413  {
414  for(std::vector<Signature *>::const_iterator i=signatures.begin(); i!=signatures.end();++i)
415  {
416  if((*i)->isSaved())
417  {
418  toUpdate.push_back(*i);
419  }
420  else
421  {
422  toSave.push_back(*i);
423  }
424  }
425 
426  if(toUpdate.size())
427  {
428  this->updateQuery(toUpdate, _timestampUpdate);
429  }
430  if(toSave.size())
431  {
432  this->saveQuery(toSave);
433  }
434  }
435 }
436 
437 void DBDriver::saveOrUpdate(const std::vector<VisualWord *> & words) const
438 {
439  ULOGGER_DEBUG("words.size=%d", (int)words.size());
440  std::list<VisualWord *> toSave;
441  std::list<VisualWord *> toUpdate;
442  if(this->isConnected() && words.size())
443  {
444  for(std::vector<VisualWord *>::const_iterator i=words.begin(); i!=words.end();++i)
445  {
446  if((*i)->isSaved())
447  {
448  toUpdate.push_back(*i);
449  }
450  else
451  {
452  toSave.push_back(*i);
453  }
454  }
455 
456  if(toUpdate.size())
457  {
458  this->updateQuery(toUpdate, _timestampUpdate);
459  }
460  if(toSave.size())
461  {
462  this->saveQuery(toSave);
463  }
464  }
465 }
466 
467 void DBDriver::addLink(const Link & link)
468 {
470  this->addLinkQuery(link);
472 }
473 void DBDriver::removeLink(int from, int to)
474 {
475  this->executeNoResult(uFormat("DELETE FROM Link WHERE from_id=%d and to_id=%d", from, to).c_str());
476 }
477 void DBDriver::updateLink(const Link & link)
478 {
480  this->updateLinkQuery(link);
482 }
484  int nodeId,
485  const cv::Mat & ground,
486  const cv::Mat & obstacles,
487  const cv::Mat & empty,
488  float cellSize,
489  const cv::Point3f & viewpoint)
490 {
492  //just to make sure the occupancy grids are compressed for convenience
493  SensorData data;
494  data.setOccupancyGrid(ground, obstacles, empty, cellSize, viewpoint);
496  nodeId,
500  cellSize,
501  viewpoint);
503 }
504 
505 void DBDriver::updateDepthImage(int nodeId, const cv::Mat & image)
506 {
508  this->updateDepthImageQuery(
509  nodeId,
510  image);
512 }
513 
514 void DBDriver::updateLaserScan(int nodeId, const LaserScan & scan)
515 {
517  this->updateLaserScanQuery(
518  nodeId,
519  scan);
521 }
522 
523 void DBDriver::load(VWDictionary * dictionary, bool lastStateOnly) const
524 {
526  this->loadQuery(dictionary, lastStateOnly);
528 }
529 
530 void DBDriver::loadLastNodes(std::list<Signature *> & signatures) const
531 {
533  this->loadLastNodesQuery(signatures);
535 }
536 
537 Signature * DBDriver::loadSignature(int id, bool * loadedFromTrash)
538 {
539  std::list<int> ids;
540  ids.push_back(id);
541  std::list<Signature*> signatures;
542  std::set<int> loadedFromTrashSet;
543  loadSignatures(ids, signatures, &loadedFromTrashSet);
544  if(loadedFromTrash && loadedFromTrashSet.size())
545  {
546  *loadedFromTrash = true;
547  }
548  if(!signatures.empty())
549  {
550  return signatures.front();
551  }
552  return 0;
553 }
554 void DBDriver::loadSignatures(const std::list<int> & signIds,
555  std::list<Signature *> & signatures,
556  std::set<int> * loadedFromTrash)
557 {
558  UDEBUG("");
559  // look up in the trash before the database
560  std::list<int> ids = signIds;
561  bool valueFound = false;
563  {
564  for(std::list<int>::iterator iter = ids.begin(); iter != ids.end();)
565  {
566  valueFound = false;
567  for(std::map<int, Signature*>::iterator sIter = _trashSignatures.begin(); sIter!=_trashSignatures.end();)
568  {
569  if(sIter->first == *iter)
570  {
571  signatures.push_back(sIter->second);
572  _trashSignatures.erase(sIter++);
573 
574  valueFound = true;
575  break;
576  }
577  else
578  {
579  ++sIter;
580  }
581  }
582  if(valueFound)
583  {
584  if(loadedFromTrash)
585  {
586  loadedFromTrash->insert(*iter);
587  }
588  iter = ids.erase(iter);
589  }
590  else
591  {
592  ++iter;
593  }
594  }
595  }
597  UDEBUG("");
598  if(ids.size())
599  {
601  this->loadSignaturesQuery(ids, signatures);
603  }
604 }
605 
606 void DBDriver::loadWords(const std::set<int> & wordIds, std::list<VisualWord *> & vws)
607 {
608  // look up in the trash before the database
609  std::set<int> ids = wordIds;
610  std::map<int, VisualWord*>::iterator wIter;
611  std::list<VisualWord *> puttedBack;
613  {
614  if(_trashVisualWords.size())
615  {
616  for(std::set<int>::iterator iter = ids.begin(); iter != ids.end();)
617  {
618  UASSERT(*iter>0);
619  wIter = _trashVisualWords.find(*iter);
620  if(wIter != _trashVisualWords.end())
621  {
622  UDEBUG("put back word %d from trash", *iter);
623  puttedBack.push_back(wIter->second);
624  _trashVisualWords.erase(wIter);
625  ids.erase(iter++);
626  }
627  else
628  {
629  ++iter;
630  }
631  }
632  }
633  }
635  if(ids.size())
636  {
638  this->loadWordsQuery(ids, vws);
640  uAppend(vws, puttedBack);
641  }
642  else if(puttedBack.size())
643  {
644  uAppend(vws, puttedBack);
645  }
646 }
647 
648 void DBDriver::loadNodeData(Signature * signature, bool images, bool scan, bool userData, bool occupancyGrid) const
649 {
650  std::list<Signature *> signatures;
651  signatures.push_back(signature);
652  this->loadNodeData(signatures, images, scan, userData, occupancyGrid);
653 }
654 
655 void DBDriver::loadNodeData(std::list<Signature *> & signatures, bool images, bool scan, bool userData, bool occupancyGrid) const
656 {
657  // Don't look in the trash, we assume that if we want to load
658  // data of a signature, it is not in thrash! Print an error if so.
660  if(_trashSignatures.size())
661  {
662  for(std::list<Signature *>::iterator iter=signatures.begin(); iter!=signatures.end(); ++iter)
663  {
664  UASSERT(*iter != 0);
665  UASSERT_MSG(!uContains(_trashSignatures, (*iter)->id()), uFormat("Signature %d should not be used when transferred to trash!!!!", (*iter)->id()).c_str());
666  }
667  }
669 
671  this->loadNodeDataQuery(signatures, images, scan, userData, occupancyGrid);
673 }
674 
676  int signatureId,
677  SensorData & data,
678  bool images, bool scan, bool userData, bool occupancyGrid) const
679 {
680  bool found = false;
681  // look in the trash
683  if(uContains(_trashSignatures, signatureId))
684  {
685  const Signature * s = _trashSignatures.at(signatureId);
686  if((!s->isSaved() ||
687  ((!images || !s->sensorData().imageCompressed().empty()) &&
688  (!scan || !s->sensorData().laserScanCompressed().isEmpty()) &&
689  (!userData || !s->sensorData().userDataCompressed().empty()) &&
690  (!occupancyGrid || s->sensorData().gridCellSize() != 0.0f))))
691  {
692  data = (SensorData)s->sensorData();
693  if(!images)
694  {
695  data.setRGBDImage(cv::Mat(), cv::Mat(), std::vector<CameraModel>());
696  }
697  if(!scan)
698  {
699  data.setLaserScan(LaserScan());
700  }
701  if(!userData)
702  {
703  data.setUserData(cv::Mat());
704  }
705  if(!occupancyGrid)
706  {
707  data.setOccupancyGrid(cv::Mat(), cv::Mat(), cv::Mat(), 0, cv::Point3f());
708  }
709  found = true;
710  }
711  }
713 
714  if(!found)
715  {
717  std::list<Signature *> signatures;
718  Signature tmp(signatureId);
719  signatures.push_back(&tmp);
720  loadNodeDataQuery(signatures, images, scan, userData, occupancyGrid);
721  data = signatures.front()->sensorData();
723  }
724 }
725 
727  int signatureId,
728  std::vector<CameraModel> & models,
729  StereoCameraModel & stereoModel) const
730 {
731  UDEBUG("");
732  bool found = false;
733  // look in the trash
735  if(uContains(_trashSignatures, signatureId))
736  {
737  models = _trashSignatures.at(signatureId)->sensorData().cameraModels();
738  stereoModel = _trashSignatures.at(signatureId)->sensorData().stereoCameraModel();
739  found = true;
740  }
742 
743  if(!found)
744  {
746  found = this->getCalibrationQuery(signatureId, models, stereoModel);
748  }
749  return found;
750 }
751 
753  int signatureId,
754  LaserScan & info) const
755 {
756  UDEBUG("");
757  bool found = false;
758  // look in the trash
760  if(uContains(_trashSignatures, signatureId))
761  {
762  info = _trashSignatures.at(signatureId)->sensorData().laserScanCompressed();
763  found = true;
764  }
766 
767  if(!found)
768  {
770  found = this->getLaserScanInfoQuery(signatureId, info);
772  }
773  return found;
774 }
775 
777  int signatureId,
778  Transform & pose,
779  int & mapId,
780  int & weight,
781  std::string & label,
782  double & stamp,
783  Transform & groundTruthPose,
784  std::vector<float> & velocity,
785  GPS & gps,
786  EnvSensors & sensors) const
787 {
788  bool found = false;
789  // look in the trash
791  if(uContains(_trashSignatures, signatureId))
792  {
793  pose = _trashSignatures.at(signatureId)->getPose().clone();
794  mapId = _trashSignatures.at(signatureId)->mapId();
795  weight = _trashSignatures.at(signatureId)->getWeight();
796  label = std::string(_trashSignatures.at(signatureId)->getLabel());
797  stamp = _trashSignatures.at(signatureId)->getStamp();
798  groundTruthPose = _trashSignatures.at(signatureId)->getGroundTruthPose().clone();
799  velocity = std::vector<float>(_trashSignatures.at(signatureId)->getVelocity());
800  gps = GPS(_trashSignatures.at(signatureId)->sensorData().gps());
801  sensors = EnvSensors(_trashSignatures.at(signatureId)->sensorData().envSensors());
802  found = true;
803  }
805 
806  if(!found)
807  {
809  found = this->getNodeInfoQuery(signatureId, pose, mapId, weight, label, stamp, groundTruthPose, velocity, gps, sensors);
811  }
812  return found;
813 }
814 
815 void DBDriver::loadLinks(int signatureId, std::multimap<int, Link> & links, Link::Type type) const
816 {
817  bool found = false;
818  // look in the trash
820  if(uContains(_trashSignatures, signatureId))
821  {
822  const Signature * s = _trashSignatures.at(signatureId);
823  UASSERT(s != 0);
824  for(std::map<int, Link>::const_iterator nIter = s->getLinks().begin();
825  nIter!=s->getLinks().end();
826  ++nIter)
827  {
828  if(type == Link::kAllWithoutLandmarks || type == Link::kAllWithLandmarks || nIter->second.type() == type)
829  {
830  links.insert(*nIter);
831  }
832  }
833  if(type == Link::kLandmark || type == Link::kAllWithLandmarks)
834  {
835  links.insert(s->getLandmarks().begin(), s->getLandmarks().end());
836  }
837  found = true;
838  }
840 
841  if(!found)
842  {
844  this->loadLinksQuery(signatureId, links, type);
846  }
847 }
848 
849 void DBDriver::getWeight(int signatureId, int & weight) const
850 {
851  bool found = false;
852  // look in the trash
854  if(uContains(_trashSignatures, signatureId))
855  {
856  weight = _trashSignatures.at(signatureId)->getWeight();
857  found = true;
858  }
860 
861  if(!found)
862  {
864  this->getWeightQuery(signatureId, weight);
866  }
867 }
868 
869 void DBDriver::getLastNodeIds(std::set<int> & ids) const
870 {
872  this->getLastNodeIdsQuery(ids);
874 }
875 
876 void DBDriver::getAllNodeIds(std::set<int> & ids, bool ignoreChildren, bool ignoreBadSignatures) const
877 {
878  // look in the trash
880  if(_trashSignatures.size())
881  {
882  for(std::map<int, Signature*>::const_iterator sIter = _trashSignatures.begin(); sIter!=_trashSignatures.end(); ++sIter)
883  {
884  bool hasNeighbors = !ignoreChildren;
885  if(ignoreChildren)
886  {
887  for(std::map<int, Link>::const_iterator nIter = sIter->second->getLinks().begin();
888  nIter!=sIter->second->getLinks().end();
889  ++nIter)
890  {
891  if(nIter->second.type() == Link::kNeighbor ||
892  nIter->second.type() == Link::kNeighborMerged)
893  {
894  hasNeighbors = true;
895  break;
896  }
897  }
898  }
899  if(hasNeighbors)
900  {
901  ids.insert(sIter->first);
902  }
903  }
904 
905  std::vector<int> keys = uKeys(_trashSignatures);
906 
907  }
909 
911  this->getAllNodeIdsQuery(ids, ignoreChildren, ignoreBadSignatures);
913 }
914 
915 void DBDriver::getAllLinks(std::multimap<int, Link> & links, bool ignoreNullLinks, bool withLandmarks) const
916 {
918  this->getAllLinksQuery(links, ignoreNullLinks, withLandmarks);
920 
921  // look in the trash
923  if(_trashSignatures.size())
924  {
925  for(std::map<int, Signature*>::const_iterator iter=_trashSignatures.begin(); iter!=_trashSignatures.end(); ++iter)
926  {
927  links.erase(iter->first);
928  for(std::map<int, Link>::const_iterator jter=iter->second->getLinks().begin();
929  jter!=iter->second->getLinks().end();
930  ++jter)
931  {
932  if(!ignoreNullLinks || jter->second.isValid())
933  {
934  links.insert(std::make_pair(iter->first, jter->second));
935  }
936  }
937  if(withLandmarks)
938  {
939  for(std::map<int, Link>::const_iterator jter=iter->second->getLandmarks().begin();
940  jter!=iter->second->getLandmarks().end();
941  ++jter)
942  {
943  if(!ignoreNullLinks || jter->second.isValid())
944  {
945  links.insert(std::make_pair(iter->first, jter->second));
946  }
947  }
948  }
949  }
950  }
952 }
953 
954 void DBDriver::getLastNodeId(int & id) const
955 {
956  // look in the trash
958  if(_trashSignatures.size())
959  {
960  id = _trashSignatures.rbegin()->first;
961  }
963 
965  this->getLastIdQuery("Node", id);
966  int statisticsId = 0;
967  if(uStrNumCmp(this->getDatabaseVersion(), "0.11.11") >= 0)
968  {
969  this->getLastIdQuery("Statistics", statisticsId);
970  if(statisticsId > id)
971  {
972  id = statisticsId;
973  }
974  }
976 }
977 
978 void DBDriver::getLastMapId(int & mapId) const
979 {
980  // look in the trash
982  if(_trashSignatures.size())
983  {
984  mapId = _trashSignatures.rbegin()->second->mapId();
985  }
987 
989  this->getLastIdQuery("Node", mapId, "map_id");
991 }
992 
993 void DBDriver::getLastWordId(int & id) const
994 {
995  // look in the trash
997  if(_trashVisualWords.size())
998  {
999  id = _trashVisualWords.rbegin()->first;
1000  }
1002 
1004  this->getLastIdQuery("Word", id);
1006 }
1007 
1008 void DBDriver::getInvertedIndexNi(int signatureId, int & ni) const
1009 {
1010  bool found = false;
1011  // look in the trash
1012  _trashesMutex.lock();
1013  if(uContains(_trashSignatures, signatureId))
1014  {
1015  ni = _trashSignatures.at(signatureId)->getWords().size();
1016  found = true;
1017  }
1019 
1020  if(!found)
1021  {
1023  this->getInvertedIndexNiQuery(signatureId, ni);
1025  }
1026 }
1027 
1028 void DBDriver::getNodesObservingLandmark(int landmarkId, std::map<int, Link> & nodes) const
1029 {
1030  if(landmarkId < 0)
1031  {
1032  // look in the trash
1033  _trashesMutex.lock();
1034  for(std::map<int, Signature*>::const_iterator sIter = _trashSignatures.begin(); sIter!=_trashSignatures.end(); ++sIter)
1035  {
1036  std::map<int, Link>::const_iterator kter = sIter->second->getLandmarks().find(landmarkId);
1037  if(kter != sIter->second->getLandmarks().end())
1038  {
1039  nodes.insert(std::make_pair(sIter->second->id(), kter->second));
1040  }
1041  }
1043 
1044  // then look in the database
1046  this->getNodesObservingLandmarkQuery(landmarkId, nodes);
1048  }
1049  else
1050  {
1051  UWARN("Can't search with an empty label!");
1052  }
1053 }
1054 
1055 void DBDriver::getNodeIdByLabel(const std::string & label, int & id) const
1056 {
1057  if(!label.empty())
1058  {
1059  int idFound = 0;
1060  // look in the trash
1061  _trashesMutex.lock();
1062  for(std::map<int, Signature*>::const_iterator sIter = _trashSignatures.begin(); sIter!=_trashSignatures.end(); ++sIter)
1063  {
1064  if(sIter->second->getLabel().compare(label) == 0)
1065  {
1066  idFound = sIter->first;
1067  break;
1068  }
1069  }
1071 
1072  // then look in the database
1073  if(idFound == 0)
1074  {
1076  this->getNodeIdByLabelQuery(label, id);
1078  }
1079  else
1080  {
1081  id = idFound;
1082  }
1083  }
1084  else
1085  {
1086  UWARN("Can't search with an empty label!");
1087  }
1088 }
1089 
1090 void DBDriver::getAllLabels(std::map<int, std::string> & labels) const
1091 {
1092  // look in the trash
1093  _trashesMutex.lock();
1094  for(std::map<int, Signature*>::const_iterator sIter = _trashSignatures.begin(); sIter!=_trashSignatures.end(); ++sIter)
1095  {
1096  if(!sIter->second->getLabel().empty())
1097  {
1098  labels.insert(std::make_pair(sIter->first, sIter->second->getLabel()));
1099  }
1100  }
1102 
1103  // then look in the database
1105  this->getAllLabelsQuery(labels);
1107 }
1108 
1110  int stMemSize,
1111  int lastSignAdded,
1112  int processMemUsed,
1113  int databaseMemUsed,
1114  int dictionarySize,
1115  const ParametersMap & parameters) const
1116 {
1117  ULOGGER_DEBUG("");
1118  if(this->isConnected())
1119  {
1120  std::stringstream query;
1121  if(uStrNumCmp(this->getDatabaseVersion(), "0.11.8") >= 0)
1122  {
1123  std::string param = Parameters::serialize(parameters);
1124  if(uStrNumCmp(this->getDatabaseVersion(), "0.11.11") >= 0)
1125  {
1126  query << "INSERT INTO Info(STM_size,last_sign_added,process_mem_used,database_mem_used,dictionary_size,parameters) values("
1127  << stMemSize << ","
1128  << lastSignAdded << ","
1129  << processMemUsed << ","
1130  << databaseMemUsed << ","
1131  << dictionarySize << ","
1132  "\"" << param.c_str() << "\");";
1133  }
1134  else
1135  {
1136  query << "INSERT INTO Statistics(STM_size,last_sign_added,process_mem_used,database_mem_used,dictionary_size,parameters) values("
1137  << stMemSize << ","
1138  << lastSignAdded << ","
1139  << processMemUsed << ","
1140  << databaseMemUsed << ","
1141  << dictionarySize << ","
1142  "\"" << param.c_str() << "\");";
1143  }
1144  }
1145  else
1146  {
1147  query << "INSERT INTO Statistics(STM_size,last_sign_added,process_mem_used,database_mem_used,dictionary_size) values("
1148  << stMemSize << ","
1149  << lastSignAdded << ","
1150  << processMemUsed << ","
1151  << databaseMemUsed << ","
1152  << dictionarySize << ");";
1153  }
1154 
1155  this->executeNoResultQuery(query.str());
1156  }
1157 }
1158 
1159 void DBDriver::addStatistics(const Statistics & statistics, bool saveWmState) const
1160 {
1162  addStatisticsQuery(statistics, saveWmState);
1164 }
1165 
1166 void DBDriver::savePreviewImage(const cv::Mat & image) const
1167 {
1169  savePreviewImageQuery(image);
1171 }
1172 
1174 {
1176  cv::Mat image = loadPreviewImageQuery();
1178  return image;
1179 }
1180 
1181 void DBDriver::saveOptimizedPoses(const std::map<int, Transform> & optimizedPoses, const Transform & lastlocalizationPose) const
1182 {
1184  saveOptimizedPosesQuery(optimizedPoses, lastlocalizationPose);
1186 }
1187 std::map<int, Transform> DBDriver::loadOptimizedPoses(Transform * lastlocalizationPose) const
1188 {
1190  std::map<int, Transform> poses = loadOptimizedPosesQuery(lastlocalizationPose);
1192  return poses;
1193 }
1194 
1195 void DBDriver::save2DMap(const cv::Mat & map, float xMin, float yMin, float cellSize) const
1196 {
1198  save2DMapQuery(map, xMin, yMin, cellSize);
1200 }
1201 
1202 cv::Mat DBDriver::load2DMap(float & xMin, float & yMin, float & cellSize) const
1203 {
1205  cv::Mat map = load2DMapQuery(xMin, yMin, cellSize);
1207  return map;
1208 }
1209 
1211  const cv::Mat & cloud,
1212  const std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > & polygons,
1213 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
1214  const std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > & texCoords,
1215 #else
1216  const std::vector<std::vector<Eigen::Vector2f> > & texCoords,
1217 #endif
1218  const cv::Mat & textures) const
1219 {
1221  saveOptimizedMeshQuery(cloud, polygons, texCoords, textures);
1223 }
1224 
1226  std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > * polygons,
1227 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
1228  std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > * texCoords,
1229 #else
1230  std::vector<std::vector<Eigen::Vector2f> > * texCoords,
1231 #endif
1232  cv::Mat * textures) const
1233 {
1235  cv::Mat cloud = loadOptimizedMeshQuery(polygons, texCoords, textures);
1237  return cloud;
1238 }
1239 
1241  const std::string & fileName,
1242  const std::set<int> & idsInput,
1243  const std::map<int, Signature *> & otherSignatures)
1244 {
1245  if(this->isConnected())
1246  {
1247  if(!fileName.empty())
1248  {
1249  FILE* fout = 0;
1250  #ifdef _MSC_VER
1251  fopen_s(&fout, fileName.c_str(), "w");
1252  #else
1253  fout = fopen(fileName.c_str(), "w");
1254  #endif
1255 
1256  if (!fout)
1257  {
1258  UERROR("Cannot open file %s!", fileName.c_str());
1259  return;
1260  }
1261 
1262  std::set<int> ids;
1263  if(idsInput.size() == 0)
1264  {
1265  this->getAllNodeIds(ids);
1266  UDEBUG("ids.size()=%d", ids.size());
1267  for(std::map<int, Signature*>::const_iterator iter=otherSignatures.begin(); iter!=otherSignatures.end(); ++iter)
1268  {
1269  ids.insert(iter->first);
1270  }
1271  }
1272  else
1273  {
1274  ids = idsInput;
1275  }
1276 
1277  const char * colorG = "green";
1278  const char * colorP = "pink";
1279  const char * colorNM = "blue";
1280  UINFO("Generating map with %d locations", ids.size());
1281  fprintf(fout, "digraph G {\n");
1282  for(std::set<int>::iterator i=ids.begin(); i!=ids.end(); ++i)
1283  {
1284  if(otherSignatures.find(*i) == otherSignatures.end())
1285  {
1286  int id = *i;
1287  std::multimap<int, Link> links;
1288  this->loadLinks(id, links);
1289  int weight = 0;
1290  this->getWeight(id, weight);
1291  for(std::multimap<int, Link>::iterator iter = links.begin(); iter!=links.end(); ++iter)
1292  {
1293  int weightNeighbor = 0;
1294  if(otherSignatures.find(iter->first) == otherSignatures.end())
1295  {
1296  this->getWeight(iter->first, weightNeighbor);
1297  }
1298  else
1299  {
1300  weightNeighbor = otherSignatures.find(iter->first)->second->getWeight();
1301  }
1302  //UDEBUG("Add neighbor link from %d to %d", id, iter->first);
1303  if(iter->second.type() == Link::kNeighbor)
1304  {
1305  fprintf(fout, " \"%d\\n%d\" -> \"%d\\n%d\"\n",
1306  id,
1307  weight,
1308  iter->first,
1309  weightNeighbor);
1310  }
1311  else if(iter->second.type() == Link::kNeighborMerged)
1312  {
1313  //merged neighbor
1314  fprintf(fout, " \"%d\\n%d\" -> \"%d\\n%d\" [label=\"M\", fontcolor=%s, fontsize=8];\n",
1315  id,
1316  weight,
1317  iter->first,
1318  weightNeighbor,
1319  colorNM);
1320  }
1321  else if(iter->first > id)
1322  {
1323  //loop
1324  fprintf(fout, " \"%d\\n%d\" -> \"%d\\n%d\" [label=\"L\", fontcolor=%s, fontsize=8];\n",
1325  id,
1326  weight,
1327  iter->first,
1328  weightNeighbor,
1329  colorG);
1330  }
1331  else
1332  {
1333  //child
1334  fprintf(fout, " \"%d\\n%d\" -> \"%d\\n%d\" [label=\"C\", fontcolor=%s, fontsize=8];\n",
1335  id,
1336  weight,
1337  iter->first,
1338  weightNeighbor,
1339  colorP);
1340  }
1341  }
1342  }
1343  }
1344  for(std::map<int, Signature*>::const_iterator i=otherSignatures.begin(); i!=otherSignatures.end(); ++i)
1345  {
1346  if(ids.find(i->first) != ids.end())
1347  {
1348  int id = i->second->id();
1349  const std::multimap<int, Link> & links = i->second->getLinks();
1350  int weight = i->second->getWeight();
1351  for(std::multimap<int, Link>::const_iterator iter = links.begin(); iter!=links.end(); ++iter)
1352  {
1353  int weightNeighbor = 0;
1354  const Signature * s = uValue(otherSignatures, iter->first, (Signature*)0);
1355  if(s)
1356  {
1357  weightNeighbor = s->getWeight();
1358  }
1359  else
1360  {
1361  this->getWeight(iter->first, weightNeighbor);
1362  }
1363  //UDEBUG("Add neighbor link from %d to %d", id, iter->first);
1364  if(iter->second.type() == Link::kNeighbor)
1365  {
1366  fprintf(fout, " \"%d\\n%d\" -> \"%d\\n%d\"\n",
1367  id,
1368  weight,
1369  iter->first,
1370  weightNeighbor);
1371  }
1372  else if(iter->second.type() == Link::kNeighborMerged)
1373  {
1374  fprintf(fout, " \"%d\\n%d\" -> \"%d\\n%d\" [label=\"M\", fontcolor=%s, fontsize=8];\n",
1375  id,
1376  weight,
1377  iter->first,
1378  weightNeighbor,
1379  colorNM);
1380  }
1381  else if(iter->first > id)
1382  {
1383  //loop
1384  fprintf(fout, " \"%d\\n%d\" -> \"%d\\n%d\" [label=\"L\", fontcolor=%s, fontsize=8];\n",
1385  id,
1386  weight,
1387  iter->first,
1388  weightNeighbor,
1389  colorG);
1390  }
1391  else if(iter->first != id)
1392  {
1393  //child
1394  fprintf(fout, " \"%d\\n%d\" -> \"%d\\n%d\" [label=\"C\", fontcolor=%s, fontsize=8];\n",
1395  id,
1396  weight,
1397  iter->first,
1398  weightNeighbor,
1399  colorP);
1400  }
1401  }
1402  }
1403  }
1404  fprintf(fout, "}\n");
1405  fclose(fout);
1406  UINFO("Graph saved to \"%s\" (Tip: $ neato -Tpdf \"%s\" -o out.pdf)", fileName.c_str(), fileName.c_str());
1407  }
1408  }
1409 }
1410 
1411 } // namespace rtabmap
UMutex _dbSafeAccessMutex
Definition: DBDriver.h:300
std::string _targetVersion
Definition: DBDriver.h:304
void getNodesObservingLandmark(int landmarkId, std::map< int, Link > &nodes) const
Definition: DBDriver.cpp:1028
static bool parse(const ParametersMap &parameters, const std::string &key, bool &value)
Definition: Parameters.cpp:476
virtual void addLinkQuery(const Link &link) const =0
void getLastNodeId(int &id) const
Definition: DBDriver.cpp:954
virtual void addStatisticsQuery(const Statistics &statistics, bool saveWmState) const =0
cv::Mat loadPreviewImage() const
Definition: DBDriver.cpp:1173
void asyncSave(Signature *s)
Definition: DBDriver.cpp:382
Definition: UTimer.h:46
virtual bool getDatabaseVersionQuery(std::string &version) const =0
virtual void loadNodeDataQuery(std::list< Signature * > &signatures, bool images=true, bool scan=true, bool userData=true, bool occupancyGrid=true) const =0
long getFeaturesMemoryUsed() const
Definition: DBDriver.cpp:191
long getGridsMemoryUsed() const
Definition: DBDriver.cpp:159
virtual void getAllLinksQuery(std::multimap< int, Link > &links, bool ignoreNullLinks, bool withLandmarks) const =0
void start()
Definition: UThread.cpp:122
void setOccupancyGrid(const cv::Mat &ground, const cv::Mat &obstacles, const cv::Mat &empty, float cellSize, const cv::Point3f &viewPoint)
Definition: SensorData.cpp:400
long getImagesMemoryUsed() const
Definition: DBDriver.cpp:135
std::map< int, Signature * > _trashSignatures
Definition: DBDriver.h:297
virtual void getAllNodeIdsQuery(std::set< int > &ids, bool ignoreChildren, bool ignoreBadSignatures) const =0
void commit() const
Definition: DBDriver.cpp:297
void saveOptimizedPoses(const std::map< int, Transform > &optimizedPoses, const Transform &lastlocalizationPose) const
Definition: DBDriver.cpp:1181
unsigned long getMemoryUsed() const
Definition: DBDriver.cpp:110
virtual void savePreviewImageQuery(const cv::Mat &image) const =0
std::vector< K > uKeys(const std::multimap< K, V > &mm)
Definition: UStl.h:67
Signature * loadSignature(int id, bool *loadedFromTrash=0)
Definition: DBDriver.cpp:537
long getUserDataMemoryUsed() const
Definition: DBDriver.cpp:175
void addInfoAfterRun(int stMemSize, int lastSignAdded, int processMemUsed, int databaseMemUsed, int dictionarySize, const ParametersMap &parameters) const
Definition: DBDriver.cpp:1109
const LaserScan & laserScanCompressed() const
Definition: SensorData.h:162
void updateLaserScan(int nodeId, const LaserScan &scan)
Definition: DBDriver.cpp:514
int lock() const
Definition: UMutex.h:87
void setLaserScan(const LaserScan &laserScan, bool clearPreviousData=true)
Definition: SensorData.cpp:337
void executeNoResult(const std::string &sql) const
Definition: DBDriver.cpp:304
void beginTransaction() const
Definition: DBDriver.cpp:290
virtual cv::Mat load2DMapQuery(float &xMin, float &yMin, float &cellSize) const =0
void saveOptimizedMesh(const cv::Mat &cloud, const std::vector< std::vector< std::vector< RTABMAP_PCL_INDEX > > > &polygons=std::vector< std::vector< std::vector< RTABMAP_PCL_INDEX > > >(), const std::vector< std::vector< Eigen::Vector2f > > &texCoords=std::vector< std::vector< Eigen::Vector2f > >(), const cv::Mat &textures=cv::Mat()) const
Definition: DBDriver.cpp:1210
virtual void updateQuery(const std::list< Signature * > &signatures, bool updateTimestamp) const =0
virtual bool isConnectedQuery() const =0
int uStrNumCmp(const std::string &a, const std::string &b)
Definition: UStl.h:719
virtual void updateOccupancyGridQuery(int nodeId, const cv::Mat &ground, const cv::Mat &obstacles, const cv::Mat &empty, float cellSize, const cv::Point3f &viewpoint) const =0
void getAllNodeIds(std::set< int > &ids, bool ignoreChildren=false, bool ignoreBadSignatures=false) const
Definition: DBDriver.cpp:876
virtual void saveOptimizedMeshQuery(const cv::Mat &cloud, const std::vector< std::vector< std::vector< RTABMAP_PCL_INDEX > > > &polygons, const std::vector< std::vector< Eigen::Vector2f > > &texCoords, const cv::Mat &textures) const =0
void kill()
Definition: UThread.cpp:48
bool isRunning() const
Definition: UThread.cpp:245
long getWordsMemoryUsed() const
Definition: DBDriver.cpp:183
bool isEmpty() const
Definition: LaserScan.h:101
void setRGBDImage(const cv::Mat &rgb, const cv::Mat &depth, const CameraModel &model, bool clearPreviousData=true)
Definition: SensorData.cpp:193
virtual void getAllLabelsQuery(std::map< int, std::string > &labels) const =0
void getNodeData(int signatureId, SensorData &data, bool images=true, bool scan=true, bool userData=true, bool occupancyGrid=true) const
Definition: DBDriver.cpp:675
virtual ~DBDriver()
Definition: DBDriver.cpp:53
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
virtual long getNodesMemoryUsedQuery() const =0
void loadWords(const std::set< int > &wordIds, std::list< VisualWord * > &vws)
Definition: DBDriver.cpp:606
float gridCellSize() const
Definition: SensorData.h:245
Basic mathematics functions.
void load(VWDictionary *dictionary, bool lastStateOnly=true) const
Definition: DBDriver.cpp:523
const cv::Mat & gridObstacleCellsCompressed() const
Definition: SensorData.h:242
UMutex _trashesMutex
Definition: DBDriver.h:299
Some conversion functions.
virtual void loadLastNodesQuery(std::list< Signature * > &signatures) const =0
virtual void getLastNodeIdsQuery(std::set< int > &ids) const =0
const cv::Mat & gridGroundCellsCompressed() const
Definition: SensorData.h:240
virtual std::map< int, Transform > loadOptimizedPosesQuery(Transform *lastlocalizationPose=0) const =0
void loadLinks(int signatureId, std::multimap< int, Link > &links, Link::Type type=Link::kUndef) const
Definition: DBDriver.cpp:815
const cv::Mat & gridEmptyCellsCompressed() const
Definition: SensorData.h:244
virtual int getTotalNodesSizeQuery() const =0
void generateGraph(const std::string &fileName, const std::set< int > &ids=std::set< int >(), const std::map< int, Signature * > &otherSignatures=std::map< int, Signature * >())
Definition: DBDriver.cpp:1240
virtual void executeNoResultQuery(const std::string &sql) const =0
int id() const
Definition: VisualWord.h:49
bool isSaved() const
Definition: Signature.h:101
bool isConnected() const
Definition: DBDriver.cpp:100
void getAllLabels(std::map< int, std::string > &labels) const
Definition: DBDriver.cpp:1090
std::map< std::string, float > getStatistics(int nodeId, double &stamp, std::vector< int > *wmState=0) const
Definition: DBDriver.cpp:248
virtual void saveQuery(const std::list< Signature * > &signatures)=0
std::map< int, std::vector< int > > getAllStatisticsWmStates() const
Definition: DBDriver.cpp:266
void getNodeIdByLabel(const std::string &label, int &id) const
Definition: DBDriver.cpp:1055
bool openConnection(const std::string &url, bool overwritten=false)
Definition: DBDriver.cpp:86
bool _timestampUpdate
Definition: DBDriver.h:305
virtual long getImagesMemoryUsedQuery() const =0
#define UASSERT(condition)
virtual void loadSignaturesQuery(const std::list< int > &ids, std::list< Signature * > &signatures) const =0
Wrappers of STL for convenient functions.
void getWeight(int signatureId, int &weight) const
Definition: DBDriver.cpp:849
virtual void getInvertedIndexNiQuery(int signatureId, int &ni) const =0
void getLastNodeIds(std::set< int > &ids) const
Definition: DBDriver.cpp:869
bool getLaserScanInfo(int signatureId, LaserScan &info) const
Definition: DBDriver.cpp:752
virtual long getLinksMemoryUsedQuery() const =0
#define true
Definition: ConvertUTF.c:57
virtual int getTotalDictionarySizeQuery() const =0
static std::string serialize(const ParametersMap &parameters)
Definition: Parameters.cpp:93
const std::multimap< int, Link > & getLinks() const
Definition: Signature.h:100
#define ULOGGER_DEBUG(...)
Definition: ULogger.h:53
void getAllLinks(std::multimap< int, Link > &links, bool ignoreNullLinks=true, bool withLandmarks=false) const
Definition: DBDriver.cpp:915
virtual long getCalibrationsMemoryUsedQuery() const =0
virtual ParametersMap getLastParametersQuery() const =0
virtual bool getCalibrationQuery(int signatureId, std::vector< CameraModel > &models, StereoCameraModel &stereoModel) const =0
virtual void save2DMapQuery(const cv::Mat &map, float xMin, float yMin, float cellSize) const =0
#define UASSERT_MSG(condition, msg_str)
Definition: ULogger.h:67
long getLaserScansMemoryUsed() const
Definition: DBDriver.cpp:167
void closeConnection(bool save=true, const std::string &outputUrl="")
Definition: DBDriver.cpp:64
void loadNodeData(Signature *signature, bool images=true, bool scan=true, bool userData=true, bool occupancyGrid=true) const
Definition: DBDriver.cpp:648
void loadSignatures(const std::list< int > &ids, std::list< Signature * > &signatures, std::set< int > *loadedFromTrash=0)
Definition: DBDriver.cpp:554
virtual void updateLaserScanQuery(int nodeId, const LaserScan &scan) const =0
std::map< int, std::pair< std::map< std::string, float >, double > > getAllStatistics() const
Definition: DBDriver.cpp:257
cv::Mat load2DMap(float &xMin, float &yMin, float &cellSize) const
Definition: DBDriver.cpp:1202
void addStatistics(const Statistics &statistics, bool saveWmState) const
Definition: DBDriver.cpp:1159
virtual long getStatisticsMemoryUsedQuery() const =0
bool getCalibration(int signatureId, std::vector< CameraModel > &models, StereoCameraModel &stereoModel) const
Definition: DBDriver.cpp:726
int getLastDictionarySize() const
Definition: DBDriver.cpp:215
virtual std::map< std::string, float > getStatisticsQuery(int nodeId, double &stamp, std::vector< int > *wmState) const =0
virtual bool getLaserScanInfoQuery(int signatureId, LaserScan &info) const =0
void updateLink(const Link &link)
Definition: DBDriver.cpp:477
long getStatisticsMemoryUsed() const
Definition: DBDriver.cpp:199
int id() const
Definition: Signature.h:70
long getCalibrationsMemoryUsed() const
Definition: DBDriver.cpp:151
virtual long getGridsMemoryUsedQuery() const =0
virtual void getLastIdQuery(const std::string &tableName, int &id, const std::string &fieldName="id") const =0
void updateDepthImage(int nodeId, const cv::Mat &image)
Definition: DBDriver.cpp:505
void start()
Definition: UTimer.cpp:87
virtual long getDepthImagesMemoryUsedQuery() const =0
virtual std::map< int, std::vector< int > > getAllStatisticsWmStatesQuery() const =0
const std::map< int, Link > & getLandmarks() const
Definition: Signature.h:94
long getDepthImagesMemoryUsed() const
Definition: DBDriver.cpp:143
int getWeight() const
Definition: Signature.h:74
bool uContains(const std::list< V > &list, const V &value)
Definition: UStl.h:409
cv::Mat loadOptimizedMesh(std::vector< std::vector< std::vector< RTABMAP_PCL_INDEX > > > *polygons=0, std::vector< std::vector< Eigen::Vector2f > > *texCoords=0, cv::Mat *textures=0) const
Definition: DBDriver.cpp:1225
std::string _url
Definition: DBDriver.h:303
int getTotalNodesSize() const
Definition: DBDriver.cpp:223
virtual long getWordsMemoryUsedQuery() const =0
static DBDriver * create(const ParametersMap &parameters=ParametersMap())
Definition: DBDriver.cpp:41
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
Definition: DBDriver.cpp:776
void setUserData(const cv::Mat &userData, bool clearPreviousData=true)
Definition: SensorData.cpp:378
virtual long getLaserScansMemoryUsedQuery() const =0
const cv::Mat & userDataCompressed() const
Definition: SensorData.h:228
virtual void disconnectDatabaseQuery(bool save=true, const std::string &outputUrl="")=0
virtual void loadLinksQuery(int signatureId, std::multimap< int, Link > &links, Link::Type type=Link::kUndef) const =0
virtual std::map< int, std::pair< std::map< std::string, float >, double > > getAllStatisticsQuery() const =0
std::vector< V > uValues(const std::multimap< K, V > &mm)
Definition: UStl.h:100
virtual void getWeightQuery(int signatureId, int &weight) const =0
virtual long getUserDataMemoryUsedQuery() const =0
std::map< int, VisualWord * > _trashVisualWords
Definition: DBDriver.h:298
virtual void mainLoop()
Definition: DBDriver.cpp:284
#define UDEBUG(...)
SensorData & sensorData()
Definition: Signature.h:137
DBDriver(const ParametersMap &parameters=ParametersMap())
Definition: DBDriver.cpp:46
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
int unlock() const
Definition: UMutex.h:113
void savePreviewImage(const cv::Mat &image) const
Definition: DBDriver.cpp:1166
#define UERROR(...)
void updateOccupancyGrid(int nodeId, const cv::Mat &ground, const cv::Mat &obstacles, const cv::Mat &empty, float cellSize, const cv::Point3f &viewpoint)
Definition: DBDriver.cpp:483
ParametersMap getLastParameters() const
Definition: DBDriver.cpp:239
ULogger class and convenient macros.
#define UWARN(...)
double ticks()
Definition: UTimer.cpp:117
int getTotalDictionarySize() const
Definition: DBDriver.cpp:231
const cv::Mat & imageCompressed() const
Definition: SensorData.h:160
std::string getDatabaseVersion() const
Definition: DBDriver.cpp:275
virtual void updateLinkQuery(const Link &link) const =0
virtual void loadWordsQuery(const std::set< int > &wordIds, std::list< VisualWord * > &vws) const =0
void loadLastNodes(std::list< Signature * > &signatures) const
Definition: DBDriver.cpp:530
virtual void updateDepthImageQuery(int nodeId, const cv::Mat &image) const =0
void uAppend(std::list< V > &list, const std::list< V > &newItems)
Definition: UStl.h:526
double _emptyTrashesTime
Definition: DBDriver.h:302
virtual void loadQuery(VWDictionary *dictionary, bool lastStateOnly=true) const =0
std::map< EnvSensor::Type, EnvSensor > EnvSensors
Definition: EnvSensor.h:81
virtual int getLastNodesSizeQuery() const =0
virtual void getNodesObservingLandmarkQuery(int landmarkId, std::map< int, Link > &nodes) const =0
void join(bool killFirst=false)
Definition: UThread.cpp:85
virtual long getFeaturesMemoryUsedQuery() const =0
virtual bool connectDatabaseQuery(const std::string &url, bool overwritten=false)=0
void getLastMapId(int &mapId) const
Definition: DBDriver.cpp:978
virtual unsigned long getMemoryUsedQuery() const =0
void addLink(const Link &link)
Definition: DBDriver.cpp:467
virtual cv::Mat loadOptimizedMeshQuery(std::vector< std::vector< std::vector< RTABMAP_PCL_INDEX > > > *polygons, std::vector< std::vector< Eigen::Vector2f > > *texCoords, cv::Mat *textures) const =0
void getInvertedIndexNi(int signatureId, int &ni) const
Definition: DBDriver.cpp:1008
void save2DMap(const cv::Mat &map, float xMin, float yMin, float cellSize) const
Definition: DBDriver.cpp:1195
void removeLink(int from, int to)
Definition: DBDriver.cpp:473
std::string UTILITE_EXP uFormat(const char *fmt,...)
virtual int getLastDictionarySizeQuery() const =0
virtual cv::Mat loadPreviewImageQuery() const =0
UMutex _transactionMutex
Definition: DBDriver.h:296
long getLinksMemoryUsed() const
Definition: DBDriver.cpp:127
void getLastWordId(int &id) const
Definition: DBDriver.cpp:993
virtual void parseParameters(const ParametersMap &parameters)
Definition: DBDriver.cpp:59
int getLastNodesSize() const
Definition: DBDriver.cpp:207
V uValue(const std::map< K, V > &m, const K &key, const V &defaultValue=V())
Definition: UStl.h:240
virtual void getNodeIdByLabelQuery(const std::string &label, int &id) const =0
void emptyTrashes(bool async=false)
Definition: DBDriver.cpp:311
void saveOrUpdate(const std::vector< Signature * > &signatures)
Definition: DBDriver.cpp:407
long getNodesMemoryUsed() const
Definition: DBDriver.cpp:119
virtual void saveOptimizedPosesQuery(const std::map< int, Transform > &optimizedPoses, const Transform &lastlocalizationPose) const =0
std::map< int, Transform > loadOptimizedPoses(Transform *lastlocalizationPose=0) const
Definition: DBDriver.cpp:1187
#define UINFO(...)


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