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  // well, we only have Sqlite3 database type for now :P
44  return new DBDriverSqlite3(parameters);
45 }
46 
47 DBDriver::DBDriver(const ParametersMap & parameters) :
50 {
51  this->parseParameters(parameters);
52 }
53 
55 {
56  join(true);
57  this->emptyTrashes();
58 }
59 
60 void DBDriver::parseParameters(const ParametersMap & parameters)
61 {
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
111 {
112  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::load(VWDictionary * dictionary, bool lastStateOnly) const
515 {
517  this->loadQuery(dictionary, lastStateOnly);
519 }
520 
521 void DBDriver::loadLastNodes(std::list<Signature *> & signatures) const
522 {
524  this->loadLastNodesQuery(signatures);
526 }
527 
528 void DBDriver::loadSignatures(const std::list<int> & signIds,
529  std::list<Signature *> & signatures,
530  std::set<int> * loadedFromTrash)
531 {
532  UDEBUG("");
533  // look up in the trash before the database
534  std::list<int> ids = signIds;
535  bool valueFound = false;
537  {
538  for(std::list<int>::iterator iter = ids.begin(); iter != ids.end();)
539  {
540  valueFound = false;
541  for(std::map<int, Signature*>::iterator sIter = _trashSignatures.begin(); sIter!=_trashSignatures.end();)
542  {
543  if(sIter->first == *iter)
544  {
545  signatures.push_back(sIter->second);
546  _trashSignatures.erase(sIter++);
547 
548  valueFound = true;
549  break;
550  }
551  else
552  {
553  ++sIter;
554  }
555  }
556  if(valueFound)
557  {
558  if(loadedFromTrash)
559  {
560  loadedFromTrash->insert(*iter);
561  }
562  iter = ids.erase(iter);
563  }
564  else
565  {
566  ++iter;
567  }
568  }
569  }
571  UDEBUG("");
572  if(ids.size())
573  {
575  this->loadSignaturesQuery(ids, signatures);
577  }
578 }
579 
580 void DBDriver::loadWords(const std::set<int> & wordIds, std::list<VisualWord *> & vws)
581 {
582  // look up in the trash before the database
583  std::set<int> ids = wordIds;
584  std::map<int, VisualWord*>::iterator wIter;
585  std::list<VisualWord *> puttedBack;
587  {
588  if(_trashVisualWords.size())
589  {
590  for(std::set<int>::iterator iter = ids.begin(); iter != ids.end();)
591  {
592  UASSERT(*iter>0);
593  wIter = _trashVisualWords.find(*iter);
594  if(wIter != _trashVisualWords.end())
595  {
596  UDEBUG("put back word %d from trash", *iter);
597  puttedBack.push_back(wIter->second);
598  _trashVisualWords.erase(wIter);
599  ids.erase(iter++);
600  }
601  else
602  {
603  ++iter;
604  }
605  }
606  }
607  }
609  if(ids.size())
610  {
612  this->loadWordsQuery(ids, vws);
614  uAppend(vws, puttedBack);
615  }
616  else if(puttedBack.size())
617  {
618  uAppend(vws, puttedBack);
619  }
620 }
621 
622 void DBDriver::loadNodeData(std::list<Signature *> & signatures, bool images, bool scan, bool userData, bool occupancyGrid) const
623 {
624  // Don't look in the trash, we assume that if we want to load
625  // data of a signature, it is not in thrash! Print an error if so.
627  if(_trashSignatures.size())
628  {
629  for(std::list<Signature *>::iterator iter=signatures.begin(); iter!=signatures.end(); ++iter)
630  {
631  UASSERT(*iter != 0);
632  UASSERT_MSG(!uContains(_trashSignatures, (*iter)->id()), uFormat("Signature %d should not be used when transferred to trash!!!!", (*iter)->id()).c_str());
633  }
634  }
636 
638  this->loadNodeDataQuery(signatures, images, scan, userData, occupancyGrid);
640 }
641 
643  int signatureId,
644  SensorData & data,
645  bool images, bool scan, bool userData, bool occupancyGrid) const
646 {
647  bool found = false;
648  // look in the trash
650  if(uContains(_trashSignatures, signatureId))
651  {
652  const Signature * s = _trashSignatures.at(signatureId);
653  if(!s->sensorData().imageCompressed().empty() ||
655  !s->sensorData().userDataCompressed().empty() ||
656  s->sensorData().gridCellSize() != 0.0f ||
657  !s->isSaved())
658  {
659  data = (SensorData)s->sensorData();
660  found = true;
661  }
662  }
664 
665  if(!found)
666  {
668  std::list<Signature *> signatures;
669  Signature tmp(signatureId);
670  signatures.push_back(&tmp);
671  loadNodeDataQuery(signatures, images, scan, userData, occupancyGrid);
672  data = signatures.front()->sensorData();
674  }
675 }
676 
678  int signatureId,
679  std::vector<CameraModel> & models,
680  StereoCameraModel & stereoModel) const
681 {
682  UDEBUG("");
683  bool found = false;
684  // look in the trash
686  if(uContains(_trashSignatures, signatureId))
687  {
688  models = _trashSignatures.at(signatureId)->sensorData().cameraModels();
689  stereoModel = _trashSignatures.at(signatureId)->sensorData().stereoCameraModel();
690  found = true;
691  }
693 
694  if(!found)
695  {
697  found = this->getCalibrationQuery(signatureId, models, stereoModel);
699  }
700  return found;
701 }
702 
704  int signatureId,
705  LaserScan & info) const
706 {
707  UDEBUG("");
708  bool found = false;
709  // look in the trash
711  if(uContains(_trashSignatures, signatureId))
712  {
713  info = _trashSignatures.at(signatureId)->sensorData().laserScanCompressed();
714  found = true;
715  }
717 
718  if(!found)
719  {
721  found = this->getLaserScanInfoQuery(signatureId, info);
723  }
724  return found;
725 }
726 
728  int signatureId,
729  Transform & pose,
730  int & mapId,
731  int & weight,
732  std::string & label,
733  double & stamp,
734  Transform & groundTruthPose,
735  std::vector<float> & velocity,
736  GPS & gps) const
737 {
738  bool found = false;
739  // look in the trash
741  if(uContains(_trashSignatures, signatureId))
742  {
743  pose = _trashSignatures.at(signatureId)->getPose();
744  mapId = _trashSignatures.at(signatureId)->mapId();
745  weight = _trashSignatures.at(signatureId)->getWeight();
746  label = _trashSignatures.at(signatureId)->getLabel();
747  stamp = _trashSignatures.at(signatureId)->getStamp();
748  groundTruthPose = _trashSignatures.at(signatureId)->getGroundTruthPose();
749  gps = _trashSignatures.at(signatureId)->sensorData().gps();
750  found = true;
751  }
753 
754  if(!found)
755  {
757  found = this->getNodeInfoQuery(signatureId, pose, mapId, weight, label, stamp, groundTruthPose, velocity, gps);
759  }
760  return found;
761 }
762 
763 void DBDriver::loadLinks(int signatureId, std::map<int, Link> & links, Link::Type type) const
764 {
765  bool found = false;
766  // look in the trash
768  if(uContains(_trashSignatures, signatureId))
769  {
770  const Signature * s = _trashSignatures.at(signatureId);
771  UASSERT(s != 0);
772  for(std::map<int, Link>::const_iterator nIter = s->getLinks().begin();
773  nIter!=s->getLinks().end();
774  ++nIter)
775  {
776  if(type == Link::kUndef || nIter->second.type() == type)
777  {
778  links.insert(*nIter);
779  }
780  }
781  found = true;
782  }
784 
785  if(!found)
786  {
788  this->loadLinksQuery(signatureId, links, type);
790  }
791 }
792 
793 void DBDriver::getWeight(int signatureId, int & weight) const
794 {
795  bool found = false;
796  // look in the trash
798  if(uContains(_trashSignatures, signatureId))
799  {
800  weight = _trashSignatures.at(signatureId)->getWeight();
801  found = true;
802  }
804 
805  if(!found)
806  {
808  this->getWeightQuery(signatureId, weight);
810  }
811 }
812 
813 void DBDriver::getAllNodeIds(std::set<int> & ids, bool ignoreChildren, bool ignoreBadSignatures) const
814 {
815  // look in the trash
817  if(_trashSignatures.size())
818  {
819  for(std::map<int, Signature*>::const_iterator sIter = _trashSignatures.begin(); sIter!=_trashSignatures.end(); ++sIter)
820  {
821  bool hasNeighbors = !ignoreChildren;
822  if(ignoreChildren)
823  {
824  for(std::map<int, Link>::const_iterator nIter = sIter->second->getLinks().begin();
825  nIter!=sIter->second->getLinks().end();
826  ++nIter)
827  {
828  if(nIter->second.type() == Link::kNeighbor ||
829  nIter->second.type() == Link::kNeighborMerged)
830  {
831  hasNeighbors = true;
832  break;
833  }
834  }
835  }
836  if(hasNeighbors)
837  {
838  ids.insert(sIter->first);
839  }
840  }
841 
842  std::vector<int> keys = uKeys(_trashSignatures);
843 
844  }
846 
848  this->getAllNodeIdsQuery(ids, ignoreChildren, ignoreBadSignatures);
850 }
851 
852 void DBDriver::getAllLinks(std::multimap<int, Link> & links, bool ignoreNullLinks) const
853 {
855  this->getAllLinksQuery(links, ignoreNullLinks);
857 
858  // look in the trash
860  if(_trashSignatures.size())
861  {
862  for(std::map<int, Signature*>::const_iterator iter=_trashSignatures.begin(); iter!=_trashSignatures.end(); ++iter)
863  {
864  links.erase(iter->first);
865  for(std::map<int, Link>::const_iterator jter=iter->second->getLinks().begin();
866  jter!=iter->second->getLinks().end();
867  ++jter)
868  {
869  if(!ignoreNullLinks || jter->second.isValid())
870  {
871  links.insert(std::make_pair(iter->first, jter->second));
872  }
873  }
874  }
875  }
877 }
878 
879 void DBDriver::getLastNodeId(int & id) const
880 {
881  // look in the trash
883  if(_trashSignatures.size())
884  {
885  id = _trashSignatures.rbegin()->first;
886  }
888 
890  this->getLastIdQuery("Node", id);
891  int statisticsId = 0;
892  if(uStrNumCmp(this->getDatabaseVersion(), "0.11.11") >= 0)
893  {
894  this->getLastIdQuery("Statistics", statisticsId);
895  if(statisticsId > id)
896  {
897  id = statisticsId;
898  }
899  }
901 }
902 
903 void DBDriver::getLastWordId(int & id) const
904 {
905  // look in the trash
907  if(_trashVisualWords.size())
908  {
909  id = _trashVisualWords.rbegin()->first;
910  }
912 
914  this->getLastIdQuery("Word", id);
916 }
917 
918 void DBDriver::getInvertedIndexNi(int signatureId, int & ni) const
919 {
920  bool found = false;
921  // look in the trash
923  if(uContains(_trashSignatures, signatureId))
924  {
925  ni = _trashSignatures.at(signatureId)->getWords().size();
926  found = true;
927  }
929 
930  if(!found)
931  {
933  this->getInvertedIndexNiQuery(signatureId, ni);
935  }
936 }
937 
938 void DBDriver::getNodeIdByLabel(const std::string & label, int & id) const
939 {
940  if(!label.empty())
941  {
942  int idFound = 0;
943  // look in the trash
945  for(std::map<int, Signature*>::const_iterator sIter = _trashSignatures.begin(); sIter!=_trashSignatures.end(); ++sIter)
946  {
947  if(sIter->second->getLabel().compare(label) == 0)
948  {
949  idFound = sIter->first;
950  break;
951  }
952  }
954 
955  // then look in the database
956  if(idFound == 0)
957  {
959  this->getNodeIdByLabelQuery(label, id);
961  }
962  else
963  {
964  id = idFound;
965  }
966  }
967  else
968  {
969  UWARN("Can't search with an empty label!");
970  }
971 }
972 
973 void DBDriver::getAllLabels(std::map<int, std::string> & labels) const
974 {
975  // look in the trash
977  for(std::map<int, Signature*>::const_iterator sIter = _trashSignatures.begin(); sIter!=_trashSignatures.end(); ++sIter)
978  {
979  if(!sIter->second->getLabel().empty())
980  {
981  labels.insert(std::make_pair(sIter->first, sIter->second->getLabel()));
982  }
983  }
985 
986  // then look in the database
988  this->getAllLabelsQuery(labels);
990 }
991 
993  int stMemSize,
994  int lastSignAdded,
995  int processMemUsed,
996  int databaseMemUsed,
997  int dictionarySize,
998  const ParametersMap & parameters) const
999 {
1000  ULOGGER_DEBUG("");
1001  if(this->isConnected())
1002  {
1003  std::stringstream query;
1004  if(uStrNumCmp(this->getDatabaseVersion(), "0.11.8") >= 0)
1005  {
1006  std::string param = Parameters::serialize(parameters);
1007  if(uStrNumCmp(this->getDatabaseVersion(), "0.11.11") >= 0)
1008  {
1009  query << "INSERT INTO Info(STM_size,last_sign_added,process_mem_used,database_mem_used,dictionary_size,parameters) values("
1010  << stMemSize << ","
1011  << lastSignAdded << ","
1012  << processMemUsed << ","
1013  << databaseMemUsed << ","
1014  << dictionarySize << ","
1015  "\"" << param.c_str() << "\");";
1016  }
1017  else
1018  {
1019  query << "INSERT INTO Statistics(STM_size,last_sign_added,process_mem_used,database_mem_used,dictionary_size,parameters) values("
1020  << stMemSize << ","
1021  << lastSignAdded << ","
1022  << processMemUsed << ","
1023  << databaseMemUsed << ","
1024  << dictionarySize << ","
1025  "\"" << param.c_str() << "\");";
1026  }
1027  }
1028  else
1029  {
1030  query << "INSERT INTO Statistics(STM_size,last_sign_added,process_mem_used,database_mem_used,dictionary_size) values("
1031  << stMemSize << ","
1032  << lastSignAdded << ","
1033  << processMemUsed << ","
1034  << databaseMemUsed << ","
1035  << dictionarySize << ");";
1036  }
1037 
1038  this->executeNoResultQuery(query.str());
1039  }
1040 }
1041 
1042 void DBDriver::addStatistics(const Statistics & statistics) const
1043 {
1045  addStatisticsQuery(statistics);
1047 }
1048 
1049 void DBDriver::savePreviewImage(const cv::Mat & image) const
1050 {
1052  savePreviewImageQuery(image);
1054 }
1055 
1057 {
1059  cv::Mat image = loadPreviewImageQuery();
1061  return image;
1062 }
1063 
1064 void DBDriver::saveOptimizedPoses(const std::map<int, Transform> & optimizedPoses, const Transform & lastlocalizationPose) const
1065 {
1067  saveOptimizedPosesQuery(optimizedPoses, lastlocalizationPose);
1069 }
1070 std::map<int, Transform> DBDriver::loadOptimizedPoses(Transform * lastlocalizationPose) const
1071 {
1073  std::map<int, Transform> poses = loadOptimizedPosesQuery(lastlocalizationPose);
1075  return poses;
1076 }
1077 
1078 void DBDriver::save2DMap(const cv::Mat & map, float xMin, float yMin, float cellSize) const
1079 {
1081  save2DMapQuery(map, xMin, yMin, cellSize);
1083 }
1084 
1085 cv::Mat DBDriver::load2DMap(float & xMin, float & yMin, float & cellSize) const
1086 {
1088  cv::Mat map = load2DMapQuery(xMin, yMin, cellSize);
1090  return map;
1091 }
1092 
1094  const cv::Mat & cloud,
1095  const std::vector<std::vector<std::vector<unsigned int> > > & polygons,
1096 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
1097  const std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > & texCoords,
1098 #else
1099  const std::vector<std::vector<Eigen::Vector2f> > & texCoords,
1100 #endif
1101  const cv::Mat & textures) const
1102 {
1104  saveOptimizedMeshQuery(cloud, polygons, texCoords, textures);
1106 }
1107 
1109  std::vector<std::vector<std::vector<unsigned int> > > * polygons,
1110 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
1111  std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > * texCoords,
1112 #else
1113  std::vector<std::vector<Eigen::Vector2f> > * texCoords,
1114 #endif
1115  cv::Mat * textures) const
1116 {
1118  cv::Mat cloud = loadOptimizedMeshQuery(polygons, texCoords, textures);
1120  return cloud;
1121 }
1122 
1124  const std::string & fileName,
1125  const std::set<int> & idsInput,
1126  const std::map<int, Signature *> & otherSignatures)
1127 {
1128  if(this->isConnected())
1129  {
1130  if(!fileName.empty())
1131  {
1132  FILE* fout = 0;
1133  #ifdef _MSC_VER
1134  fopen_s(&fout, fileName.c_str(), "w");
1135  #else
1136  fout = fopen(fileName.c_str(), "w");
1137  #endif
1138 
1139  if (!fout)
1140  {
1141  UERROR("Cannot open file %s!", fileName.c_str());
1142  return;
1143  }
1144 
1145  std::set<int> ids;
1146  if(idsInput.size() == 0)
1147  {
1148  this->getAllNodeIds(ids);
1149  UDEBUG("ids.size()=%d", ids.size());
1150  for(std::map<int, Signature*>::const_iterator iter=otherSignatures.begin(); iter!=otherSignatures.end(); ++iter)
1151  {
1152  ids.insert(iter->first);
1153  }
1154  }
1155  else
1156  {
1157  ids = idsInput;
1158  }
1159 
1160  const char * colorG = "green";
1161  const char * colorP = "pink";
1162  const char * colorNM = "blue";
1163  UINFO("Generating map with %d locations", ids.size());
1164  fprintf(fout, "digraph G {\n");
1165  for(std::set<int>::iterator i=ids.begin(); i!=ids.end(); ++i)
1166  {
1167  if(otherSignatures.find(*i) == otherSignatures.end())
1168  {
1169  int id = *i;
1170  std::map<int, Link> links;
1171  this->loadLinks(id, links);
1172  int weight = 0;
1173  this->getWeight(id, weight);
1174  for(std::map<int, Link>::iterator iter = links.begin(); iter!=links.end(); ++iter)
1175  {
1176  int weightNeighbor = 0;
1177  if(otherSignatures.find(iter->first) == otherSignatures.end())
1178  {
1179  this->getWeight(iter->first, weightNeighbor);
1180  }
1181  else
1182  {
1183  weightNeighbor = otherSignatures.find(iter->first)->second->getWeight();
1184  }
1185  //UDEBUG("Add neighbor link from %d to %d", id, iter->first);
1186  if(iter->second.type() == Link::kNeighbor)
1187  {
1188  fprintf(fout, " \"%d\\n%d\" -> \"%d\\n%d\"\n",
1189  id,
1190  weight,
1191  iter->first,
1192  weightNeighbor);
1193  }
1194  else if(iter->second.type() == Link::kNeighborMerged)
1195  {
1196  //merged neighbor
1197  fprintf(fout, " \"%d\\n%d\" -> \"%d\\n%d\" [label=\"M\", fontcolor=%s, fontsize=8];\n",
1198  id,
1199  weight,
1200  iter->first,
1201  weightNeighbor,
1202  colorNM);
1203  }
1204  else if(iter->first > id)
1205  {
1206  //loop
1207  fprintf(fout, " \"%d\\n%d\" -> \"%d\\n%d\" [label=\"L\", fontcolor=%s, fontsize=8];\n",
1208  id,
1209  weight,
1210  iter->first,
1211  weightNeighbor,
1212  colorG);
1213  }
1214  else
1215  {
1216  //child
1217  fprintf(fout, " \"%d\\n%d\" -> \"%d\\n%d\" [label=\"C\", fontcolor=%s, fontsize=8];\n",
1218  id,
1219  weight,
1220  iter->first,
1221  weightNeighbor,
1222  colorP);
1223  }
1224  }
1225  }
1226  }
1227  for(std::map<int, Signature*>::const_iterator i=otherSignatures.begin(); i!=otherSignatures.end(); ++i)
1228  {
1229  if(ids.find(i->first) != ids.end())
1230  {
1231  int id = i->second->id();
1232  const std::map<int, Link> & links = i->second->getLinks();
1233  int weight = i->second->getWeight();
1234  for(std::map<int, Link>::const_iterator iter = links.begin(); iter!=links.end(); ++iter)
1235  {
1236  int weightNeighbor = 0;
1237  const Signature * s = uValue(otherSignatures, iter->first, (Signature*)0);
1238  if(s)
1239  {
1240  weightNeighbor = s->getWeight();
1241  }
1242  else
1243  {
1244  this->getWeight(iter->first, weightNeighbor);
1245  }
1246  //UDEBUG("Add neighbor link from %d to %d", id, iter->first);
1247  if(iter->second.type() == Link::kNeighbor)
1248  {
1249  fprintf(fout, " \"%d\\n%d\" -> \"%d\\n%d\"\n",
1250  id,
1251  weight,
1252  iter->first,
1253  weightNeighbor);
1254  }
1255  else if(iter->second.type() == Link::kNeighborMerged)
1256  {
1257  fprintf(fout, " \"%d\\n%d\" -> \"%d\\n%d\" [label=\"M\", fontcolor=%s, fontsize=8];\n",
1258  id,
1259  weight,
1260  iter->first,
1261  weightNeighbor,
1262  colorNM);
1263  }
1264  else if(iter->first > id)
1265  {
1266  //loop
1267  fprintf(fout, " \"%d\\n%d\" -> \"%d\\n%d\" [label=\"L\", fontcolor=%s, fontsize=8];\n",
1268  id,
1269  weight,
1270  iter->first,
1271  weightNeighbor,
1272  colorG);
1273  }
1274  else if(iter->first != id)
1275  {
1276  //child
1277  fprintf(fout, " \"%d\\n%d\" -> \"%d\\n%d\" [label=\"C\", fontcolor=%s, fontsize=8];\n",
1278  id,
1279  weight,
1280  iter->first,
1281  weightNeighbor,
1282  colorP);
1283  }
1284  }
1285  }
1286  }
1287  fprintf(fout, "}\n");
1288  fclose(fout);
1289  UINFO("Graph saved to \"%s\" (Tip: $ neato -Tpdf \"%s\" -o out.pdf)", fileName.c_str(), fileName.c_str());
1290  }
1291  }
1292 }
1293 
1294 } // namespace rtabmap
UMutex _dbSafeAccessMutex
Definition: DBDriver.h:287
virtual void addLinkQuery(const Link &link) const =0
void getLastNodeId(int &id) const
Definition: DBDriver.cpp:879
cv::Mat loadPreviewImage() const
Definition: DBDriver.cpp:1056
virtual void getLastIdQuery(const std::string &tableName, int &id) const =0
virtual void addStatisticsQuery(const Statistics &statistics) const =0
cv::Mat loadOptimizedMesh(std::vector< std::vector< std::vector< unsigned int > > > *polygons=0, std::vector< std::vector< Eigen::Vector2f > > *texCoords=0, cv::Mat *textures=0) const
Definition: DBDriver.cpp:1108
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
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:482
long getImagesMemoryUsed() const
Definition: DBDriver.cpp:135
std::map< int, Signature * > _trashSignatures
Definition: DBDriver.h:284
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:1064
virtual void savePreviewImageQuery(const cv::Mat &image) const =0
std::vector< K > uKeys(const std::multimap< K, V > &mm)
Definition: UStl.h:67
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:992
const LaserScan & laserScanCompressed() const
Definition: SensorData.h:159
int lock() const
Definition: UMutex.h:87
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 loadLinks(int signatureId, std::map< int, Link > &links, Link::Type type=Link::kUndef) const
Definition: DBDriver.cpp:763
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:813
void kill()
Definition: UThread.cpp:48
virtual std::map< int, Transform > loadOptimizedPosesQuery(Transform *lastlocalizationPose) const =0
void getAllLinks(std::multimap< int, Link > &links, bool ignoreNullLinks=true) const
Definition: DBDriver.cpp:852
bool isRunning() const
Definition: UThread.cpp:245
long getWordsMemoryUsed() const
Definition: DBDriver.cpp:183
bool isEmpty() const
Definition: LaserScan.h:69
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:642
virtual ~DBDriver()
Definition: DBDriver.cpp:54
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:41
virtual long getNodesMemoryUsedQuery() const =0
void loadWords(const std::set< int > &wordIds, std::list< VisualWord * > &vws)
Definition: DBDriver.cpp:580
float gridCellSize() const
Definition: SensorData.h:223
Basic mathematics functions.
void load(VWDictionary *dictionary, bool lastStateOnly=true) const
Definition: DBDriver.cpp:514
const cv::Mat & gridObstacleCellsCompressed() const
Definition: SensorData.h:220
UMutex _trashesMutex
Definition: DBDriver.h:286
Some conversion functions.
virtual void loadLastNodesQuery(std::list< Signature * > &signatures) const =0
const cv::Mat & gridGroundCellsCompressed() const
Definition: SensorData.h:218
bool getNodeInfo(int signatureId, Transform &pose, int &mapId, int &weight, std::string &label, double &stamp, Transform &groundTruthPose, std::vector< float > &velocity, GPS &gps) const
Definition: DBDriver.cpp:727
const cv::Mat & gridEmptyCellsCompressed() const
Definition: SensorData.h:222
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:1123
virtual void executeNoResultQuery(const std::string &sql) const =0
int id() const
Definition: VisualWord.h:48
bool isSaved() const
Definition: Signature.h:97
virtual void saveOptimizedMeshQuery(const cv::Mat &cloud, const std::vector< std::vector< std::vector< unsigned int > > > &polygons, const std::vector< std::vector< Eigen::Vector2f > > &texCoords, const cv::Mat &textures) const =0
bool isConnected() const
Definition: DBDriver.cpp:100
void getAllLabels(std::map< int, std::string > &labels) const
Definition: DBDriver.cpp:973
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
virtual void getAllLinksQuery(std::multimap< int, Link > &links, bool ignoreNullLinks) const =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:938
bool openConnection(const std::string &url, bool overwritten=false)
Definition: DBDriver.cpp:86
bool _timestampUpdate
Definition: DBDriver.h:291
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:793
virtual void getInvertedIndexNiQuery(int signatureId, int &ni) const =0
virtual cv::Mat loadOptimizedMeshQuery(std::vector< std::vector< std::vector< unsigned int > > > *polygons, std::vector< std::vector< Eigen::Vector2f > > *texCoords, cv::Mat *textures) const =0
bool getLaserScanInfo(int signatureId, LaserScan &info) const
Definition: DBDriver.cpp:703
virtual long getLinksMemoryUsedQuery() const =0
virtual void loadLinksQuery(int signatureId, std::map< int, Link > &links, Link::Type type=Link::kUndef) const =0
#define true
Definition: ConvertUTF.c:57
virtual int getTotalDictionarySizeQuery() const =0
static std::string serialize(const ParametersMap &parameters)
Definition: Parameters.cpp:85
std::map< int, Transform > loadOptimizedPoses(Transform *lastlocalizationPose) const
Definition: DBDriver.cpp:1070
#define ULOGGER_DEBUG(...)
Definition: ULogger.h:53
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 loadSignatures(const std::list< int > &ids, std::list< Signature * > &signatures, std::set< int > *loadedFromTrash=0)
Definition: DBDriver.cpp:528
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:1085
virtual long getStatisticsMemoryUsedQuery() const =0
bool getCalibration(int signatureId, std::vector< CameraModel > &models, StereoCameraModel &stereoModel) const
Definition: DBDriver.cpp:677
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 getMemoryUsed() const
Definition: DBDriver.cpp:110
long getCalibrationsMemoryUsed() const
Definition: DBDriver.cpp:151
void loadNodeData(std::list< Signature * > &signatures, bool images=true, bool scan=true, bool userData=true, bool occupancyGrid=true) const
Definition: DBDriver.cpp:622
virtual long getGridsMemoryUsedQuery() const =0
void saveOptimizedMesh(const cv::Mat &cloud, const std::vector< std::vector< std::vector< unsigned int > > > &polygons=std::vector< std::vector< std::vector< unsigned int > > >(), const std::vector< std::vector< Eigen::Vector2f > > &texCoords=std::vector< std::vector< Eigen::Vector2f > >(), const cv::Mat &textures=cv::Mat()) const
Definition: DBDriver.cpp:1093
void updateDepthImage(int nodeId, const cv::Mat &image)
Definition: DBDriver.cpp:505
void start()
Definition: UTimer.cpp:80
virtual long getDepthImagesMemoryUsedQuery() const =0
virtual std::map< int, std::vector< int > > getAllStatisticsWmStatesQuery() const =0
long getDepthImagesMemoryUsed() const
Definition: DBDriver.cpp:143
int getWeight() const
Definition: Signature.h:74
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
void addStatistics(const Statistics &statistics) const
Definition: DBDriver.cpp:1042
bool uContains(const std::list< V > &list, const V &value)
Definition: UStl.h:409
std::string _url
Definition: DBDriver.h:290
int getTotalNodesSize() const
Definition: DBDriver.cpp:223
virtual long getWordsMemoryUsedQuery() const =0
static DBDriver * create(const ParametersMap &parameters=ParametersMap())
Definition: DBDriver.cpp:41
virtual long getLaserScansMemoryUsedQuery() const =0
const cv::Mat & userDataCompressed() const
Definition: SensorData.h:206
virtual void disconnectDatabaseQuery(bool save=true, const std::string &outputUrl="")=0
const std::map< int, Link > & getLinks() const
Definition: Signature.h:96
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:285
virtual void mainLoop()
Definition: DBDriver.cpp:284
#define UDEBUG(...)
SensorData & sensorData()
Definition: Signature.h:134
DBDriver(const ParametersMap &parameters=ParametersMap())
Definition: DBDriver.cpp:47
int unlock() const
Definition: UMutex.h:113
void savePreviewImage(const cv::Mat &image) const
Definition: DBDriver.cpp:1049
#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:110
int getTotalDictionarySize() const
Definition: DBDriver.cpp:231
const cv::Mat & imageCompressed() const
Definition: SensorData.h:157
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:521
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:289
virtual void loadQuery(VWDictionary *dictionary, bool lastStateOnly=true) const =0
virtual int getLastNodesSizeQuery() 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 addLink(const Link &link)
Definition: DBDriver.cpp:467
void getInvertedIndexNi(int signatureId, int &ni) const
Definition: DBDriver.cpp:918
void save2DMap(const cv::Mat &map, float xMin, float yMin, float cellSize) const
Definition: DBDriver.cpp:1078
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:283
long getLinksMemoryUsed() const
Definition: DBDriver.cpp:127
void getLastWordId(int &id) const
Definition: DBDriver.cpp:903
virtual void parseParameters(const ParametersMap &parameters)
Definition: DBDriver.cpp:60
virtual long getMemoryUsedQuery() const =0
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
#define UINFO(...)


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