00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #include "rtabmap/core/DBDriver.h"
00029
00030 #include "rtabmap/core/Signature.h"
00031 #include "rtabmap/core/VisualWord.h"
00032 #include "rtabmap/core/DBDriverSqlite3.h"
00033 #include "rtabmap/utilite/UConversion.h"
00034 #include "rtabmap/utilite/UMath.h"
00035 #include "rtabmap/utilite/ULogger.h"
00036 #include "rtabmap/utilite/UTimer.h"
00037 #include "rtabmap/utilite/UStl.h"
00038
00039 namespace rtabmap {
00040
00041 DBDriver * DBDriver::create(const ParametersMap & parameters)
00042 {
00043
00044 return new DBDriverSqlite3(parameters);
00045 }
00046
00047 DBDriver::DBDriver(const ParametersMap & parameters) :
00048 _emptyTrashesTime(0),
00049 _timestampUpdate(true)
00050 {
00051 this->parseParameters(parameters);
00052 }
00053
00054 DBDriver::~DBDriver()
00055 {
00056 join(true);
00057 this->emptyTrashes();
00058 }
00059
00060 void DBDriver::parseParameters(const ParametersMap & parameters)
00061 {
00062 }
00063
00064 void DBDriver::closeConnection(bool save, const std::string & outputUrl)
00065 {
00066 UDEBUG("isRunning=%d", this->isRunning());
00067 this->join(true);
00068 UDEBUG("");
00069 if(save)
00070 {
00071 this->emptyTrashes();
00072 }
00073 else
00074 {
00075 _trashesMutex.lock();
00076 _trashSignatures.clear();
00077 _trashVisualWords.clear();
00078 _trashesMutex.unlock();
00079 }
00080 _dbSafeAccessMutex.lock();
00081 this->disconnectDatabaseQuery(save, outputUrl);
00082 _dbSafeAccessMutex.unlock();
00083 UDEBUG("");
00084 }
00085
00086 bool DBDriver::openConnection(const std::string & url, bool overwritten)
00087 {
00088 UDEBUG("");
00089 _url = url;
00090 _dbSafeAccessMutex.lock();
00091 if(this->connectDatabaseQuery(url, overwritten))
00092 {
00093 _dbSafeAccessMutex.unlock();
00094 return true;
00095 }
00096 _dbSafeAccessMutex.unlock();
00097 return false;
00098 }
00099
00100 bool DBDriver::isConnected() const
00101 {
00102 bool r;
00103 _dbSafeAccessMutex.lock();
00104 r = isConnectedQuery();
00105 _dbSafeAccessMutex.unlock();
00106 return r;
00107 }
00108
00109
00110 long DBDriver::getMemoryUsed() const
00111 {
00112 long bytes;
00113 _dbSafeAccessMutex.lock();
00114 bytes = getMemoryUsedQuery();
00115 _dbSafeAccessMutex.unlock();
00116 return bytes;
00117 }
00118
00119 long DBDriver::getNodesMemoryUsed() const
00120 {
00121 long bytes;
00122 _dbSafeAccessMutex.lock();
00123 bytes = getNodesMemoryUsedQuery();
00124 _dbSafeAccessMutex.unlock();
00125 return bytes;
00126 }
00127 long DBDriver::getLinksMemoryUsed() const
00128 {
00129 long bytes;
00130 _dbSafeAccessMutex.lock();
00131 bytes = getLinksMemoryUsedQuery();
00132 _dbSafeAccessMutex.unlock();
00133 return bytes;
00134 }
00135 long DBDriver::getImagesMemoryUsed() const
00136 {
00137 long bytes;
00138 _dbSafeAccessMutex.lock();
00139 bytes = getImagesMemoryUsedQuery();
00140 _dbSafeAccessMutex.unlock();
00141 return bytes;
00142 }
00143 long DBDriver::getDepthImagesMemoryUsed() const
00144 {
00145 long bytes;
00146 _dbSafeAccessMutex.lock();
00147 bytes = getDepthImagesMemoryUsedQuery();
00148 _dbSafeAccessMutex.unlock();
00149 return bytes;
00150 }
00151 long DBDriver::getCalibrationsMemoryUsed() const
00152 {
00153 long bytes;
00154 _dbSafeAccessMutex.lock();
00155 bytes = getCalibrationsMemoryUsedQuery();
00156 _dbSafeAccessMutex.unlock();
00157 return bytes;
00158 }
00159 long DBDriver::getGridsMemoryUsed() const
00160 {
00161 long bytes;
00162 _dbSafeAccessMutex.lock();
00163 bytes = getGridsMemoryUsedQuery();
00164 _dbSafeAccessMutex.unlock();
00165 return bytes;
00166 }
00167 long DBDriver::getLaserScansMemoryUsed() const
00168 {
00169 long bytes;
00170 _dbSafeAccessMutex.lock();
00171 bytes = getLaserScansMemoryUsedQuery();
00172 _dbSafeAccessMutex.unlock();
00173 return bytes;
00174 }
00175 long DBDriver::getUserDataMemoryUsed() const
00176 {
00177 long bytes;
00178 _dbSafeAccessMutex.lock();
00179 bytes = getUserDataMemoryUsedQuery();
00180 _dbSafeAccessMutex.unlock();
00181 return bytes;
00182 }
00183 long DBDriver::getWordsMemoryUsed() const
00184 {
00185 long bytes;
00186 _dbSafeAccessMutex.lock();
00187 bytes = getWordsMemoryUsedQuery();
00188 _dbSafeAccessMutex.unlock();
00189 return bytes;
00190 }
00191 long DBDriver::getFeaturesMemoryUsed() const
00192 {
00193 long bytes;
00194 _dbSafeAccessMutex.lock();
00195 bytes = getFeaturesMemoryUsedQuery();
00196 _dbSafeAccessMutex.unlock();
00197 return bytes;
00198 }
00199 long DBDriver::getStatisticsMemoryUsed() const
00200 {
00201 long bytes;
00202 _dbSafeAccessMutex.lock();
00203 bytes = getStatisticsMemoryUsedQuery();
00204 _dbSafeAccessMutex.unlock();
00205 return bytes;
00206 }
00207 int DBDriver::getLastNodesSize() const
00208 {
00209 int nodes;
00210 _dbSafeAccessMutex.lock();
00211 nodes = getLastNodesSizeQuery();
00212 _dbSafeAccessMutex.unlock();
00213 return nodes;
00214 }
00215 int DBDriver::getLastDictionarySize() const
00216 {
00217 int words;
00218 _dbSafeAccessMutex.lock();
00219 words = getLastDictionarySizeQuery();
00220 _dbSafeAccessMutex.unlock();
00221 return words;
00222 }
00223 int DBDriver::getTotalNodesSize() const
00224 {
00225 int words;
00226 _dbSafeAccessMutex.lock();
00227 words = getTotalNodesSizeQuery();
00228 _dbSafeAccessMutex.unlock();
00229 return words;
00230 }
00231 int DBDriver::getTotalDictionarySize() const
00232 {
00233 int words;
00234 _dbSafeAccessMutex.lock();
00235 words = getTotalDictionarySizeQuery();
00236 _dbSafeAccessMutex.unlock();
00237 return words;
00238 }
00239 ParametersMap DBDriver::getLastParameters() const
00240 {
00241 ParametersMap parameters;
00242 _dbSafeAccessMutex.lock();
00243 parameters = getLastParametersQuery();
00244 _dbSafeAccessMutex.unlock();
00245 return parameters;
00246 }
00247
00248 std::map<std::string, float> DBDriver::getStatistics(int nodeId, double & stamp, std::vector<int> * wmState) const
00249 {
00250 std::map<std::string, float> statistics;
00251 _dbSafeAccessMutex.lock();
00252 statistics = getStatisticsQuery(nodeId, stamp, wmState);
00253 _dbSafeAccessMutex.unlock();
00254 return statistics;
00255 }
00256
00257 std::map<int, std::pair<std::map<std::string, float>, double> > DBDriver::getAllStatistics() const
00258 {
00259 std::map<int, std::pair<std::map<std::string, float>, double> > statistics;
00260 _dbSafeAccessMutex.lock();
00261 statistics = getAllStatisticsQuery();
00262 _dbSafeAccessMutex.unlock();
00263 return statistics;
00264 }
00265
00266 std::map<int, std::vector<int> > DBDriver::getAllStatisticsWmStates() const
00267 {
00268 std::map<int, std::vector<int> > wmStates;
00269 _dbSafeAccessMutex.lock();
00270 wmStates = getAllStatisticsWmStatesQuery();
00271 _dbSafeAccessMutex.unlock();
00272 return wmStates;
00273 }
00274
00275 std::string DBDriver::getDatabaseVersion() const
00276 {
00277 std::string version = "0.0.0";
00278 _dbSafeAccessMutex.lock();
00279 getDatabaseVersionQuery(version);
00280 _dbSafeAccessMutex.unlock();
00281 return version;
00282 }
00283
00284 void DBDriver::mainLoop()
00285 {
00286 this->emptyTrashes();
00287 this->kill();
00288 }
00289
00290 void DBDriver::beginTransaction() const
00291 {
00292 _transactionMutex.lock();
00293 ULOGGER_DEBUG("");
00294 this->executeNoResultQuery("BEGIN TRANSACTION;");
00295 }
00296
00297 void DBDriver::commit() const
00298 {
00299 ULOGGER_DEBUG("");
00300 this->executeNoResultQuery("COMMIT;");
00301 _transactionMutex.unlock();
00302 }
00303
00304 void DBDriver::executeNoResult(const std::string & sql) const
00305 {
00306 _dbSafeAccessMutex.lock();
00307 this->executeNoResultQuery(sql);
00308 _dbSafeAccessMutex.unlock();
00309 }
00310
00311 void DBDriver::emptyTrashes(bool async)
00312 {
00313 if(async)
00314 {
00315 ULOGGER_DEBUG("Async emptying, start the trash thread");
00316 this->start();
00317 return;
00318 }
00319
00320 UTimer totalTime;
00321 totalTime.start();
00322
00323 std::map<int, Signature*> signatures;
00324 std::map<int, VisualWord*> visualWords;
00325 _trashesMutex.lock();
00326 {
00327 ULOGGER_DEBUG("signatures=%d, visualWords=%d", _trashSignatures.size(), _trashVisualWords.size());
00328 signatures = _trashSignatures;
00329 visualWords = _trashVisualWords;
00330 _trashSignatures.clear();
00331 _trashVisualWords.clear();
00332
00333 _dbSafeAccessMutex.lock();
00334 }
00335 _trashesMutex.unlock();
00336
00337 if(signatures.size() || visualWords.size())
00338 {
00339 this->beginTransaction();
00340 UTimer timer;
00341 timer.start();
00342 if(signatures.size())
00343 {
00344 if(this->isConnected())
00345 {
00346
00347 this->saveOrUpdate(uValues(signatures));
00348 }
00349
00350 for(std::map<int, Signature *>::iterator iter=signatures.begin(); iter!=signatures.end(); ++iter)
00351 {
00352 delete iter->second;
00353 }
00354 signatures.clear();
00355 ULOGGER_DEBUG("Time emptying memory signatures trash = %f...", timer.ticks());
00356 }
00357 if(visualWords.size())
00358 {
00359 if(this->isConnected())
00360 {
00361
00362 this->saveOrUpdate(uValues(visualWords));
00363 }
00364
00365 for(std::map<int, VisualWord *>::iterator iter=visualWords.begin(); iter!=visualWords.end(); ++iter)
00366 {
00367 delete (*iter).second;
00368 }
00369 visualWords.clear();
00370 ULOGGER_DEBUG("Time emptying memory visualWords trash = %f...", timer.ticks());
00371 }
00372
00373 this->commit();
00374 }
00375
00376 _emptyTrashesTime = totalTime.ticks();
00377 ULOGGER_DEBUG("Total time emptying trashes = %fs...", _emptyTrashesTime);
00378
00379 _dbSafeAccessMutex.unlock();
00380 }
00381
00382 void DBDriver::asyncSave(Signature * s)
00383 {
00384 if(s)
00385 {
00386 UDEBUG("s=%d", s->id());
00387 _trashesMutex.lock();
00388 {
00389 _trashSignatures.insert(std::pair<int, Signature*>(s->id(), s));
00390 }
00391 _trashesMutex.unlock();
00392 }
00393 }
00394
00395 void DBDriver::asyncSave(VisualWord * vw)
00396 {
00397 if(vw)
00398 {
00399 _trashesMutex.lock();
00400 {
00401 _trashVisualWords.insert(std::pair<int, VisualWord*>(vw->id(), vw));
00402 }
00403 _trashesMutex.unlock();
00404 }
00405 }
00406
00407 void DBDriver::saveOrUpdate(const std::vector<Signature *> & signatures)
00408 {
00409 ULOGGER_DEBUG("");
00410 std::list<Signature *> toSave;
00411 std::list<Signature *> toUpdate;
00412 if(this->isConnected() && signatures.size())
00413 {
00414 for(std::vector<Signature *>::const_iterator i=signatures.begin(); i!=signatures.end();++i)
00415 {
00416 if((*i)->isSaved())
00417 {
00418 toUpdate.push_back(*i);
00419 }
00420 else
00421 {
00422 toSave.push_back(*i);
00423 }
00424 }
00425
00426 if(toUpdate.size())
00427 {
00428 this->updateQuery(toUpdate, _timestampUpdate);
00429 }
00430 if(toSave.size())
00431 {
00432 this->saveQuery(toSave);
00433 }
00434 }
00435 }
00436
00437 void DBDriver::saveOrUpdate(const std::vector<VisualWord *> & words) const
00438 {
00439 ULOGGER_DEBUG("words.size=%d", (int)words.size());
00440 std::list<VisualWord *> toSave;
00441 std::list<VisualWord *> toUpdate;
00442 if(this->isConnected() && words.size())
00443 {
00444 for(std::vector<VisualWord *>::const_iterator i=words.begin(); i!=words.end();++i)
00445 {
00446 if((*i)->isSaved())
00447 {
00448 toUpdate.push_back(*i);
00449 }
00450 else
00451 {
00452 toSave.push_back(*i);
00453 }
00454 }
00455
00456 if(toUpdate.size())
00457 {
00458 this->updateQuery(toUpdate, _timestampUpdate);
00459 }
00460 if(toSave.size())
00461 {
00462 this->saveQuery(toSave);
00463 }
00464 }
00465 }
00466
00467 void DBDriver::addLink(const Link & link)
00468 {
00469 _dbSafeAccessMutex.lock();
00470 this->addLinkQuery(link);
00471 _dbSafeAccessMutex.unlock();
00472 }
00473 void DBDriver::removeLink(int from, int to)
00474 {
00475 this->executeNoResult(uFormat("DELETE FROM Link WHERE from_id=%d and to_id=%d", from, to).c_str());
00476 }
00477 void DBDriver::updateLink(const Link & link)
00478 {
00479 _dbSafeAccessMutex.lock();
00480 this->updateLinkQuery(link);
00481 _dbSafeAccessMutex.unlock();
00482 }
00483 void DBDriver::updateOccupancyGrid(
00484 int nodeId,
00485 const cv::Mat & ground,
00486 const cv::Mat & obstacles,
00487 const cv::Mat & empty,
00488 float cellSize,
00489 const cv::Point3f & viewpoint)
00490 {
00491 _dbSafeAccessMutex.lock();
00492
00493 SensorData data;
00494 data.setOccupancyGrid(ground, obstacles, empty, cellSize, viewpoint);
00495 this->updateOccupancyGridQuery(
00496 nodeId,
00497 data.gridGroundCellsCompressed(),
00498 data.gridObstacleCellsCompressed(),
00499 data.gridEmptyCellsCompressed(),
00500 cellSize,
00501 viewpoint);
00502 _dbSafeAccessMutex.unlock();
00503 }
00504
00505 void DBDriver::updateDepthImage(int nodeId, const cv::Mat & image)
00506 {
00507 _dbSafeAccessMutex.lock();
00508 this->updateDepthImageQuery(
00509 nodeId,
00510 image);
00511 _dbSafeAccessMutex.unlock();
00512 }
00513
00514 void DBDriver::load(VWDictionary * dictionary, bool lastStateOnly) const
00515 {
00516 _dbSafeAccessMutex.lock();
00517 this->loadQuery(dictionary, lastStateOnly);
00518 _dbSafeAccessMutex.unlock();
00519 }
00520
00521 void DBDriver::loadLastNodes(std::list<Signature *> & signatures) const
00522 {
00523 _dbSafeAccessMutex.lock();
00524 this->loadLastNodesQuery(signatures);
00525 _dbSafeAccessMutex.unlock();
00526 }
00527
00528 void DBDriver::loadSignatures(const std::list<int> & signIds,
00529 std::list<Signature *> & signatures,
00530 std::set<int> * loadedFromTrash)
00531 {
00532 UDEBUG("");
00533
00534 std::list<int> ids = signIds;
00535 bool valueFound = false;
00536 _trashesMutex.lock();
00537 {
00538 for(std::list<int>::iterator iter = ids.begin(); iter != ids.end();)
00539 {
00540 valueFound = false;
00541 for(std::map<int, Signature*>::iterator sIter = _trashSignatures.begin(); sIter!=_trashSignatures.end();)
00542 {
00543 if(sIter->first == *iter)
00544 {
00545 signatures.push_back(sIter->second);
00546 _trashSignatures.erase(sIter++);
00547
00548 valueFound = true;
00549 break;
00550 }
00551 else
00552 {
00553 ++sIter;
00554 }
00555 }
00556 if(valueFound)
00557 {
00558 if(loadedFromTrash)
00559 {
00560 loadedFromTrash->insert(*iter);
00561 }
00562 iter = ids.erase(iter);
00563 }
00564 else
00565 {
00566 ++iter;
00567 }
00568 }
00569 }
00570 _trashesMutex.unlock();
00571 UDEBUG("");
00572 if(ids.size())
00573 {
00574 _dbSafeAccessMutex.lock();
00575 this->loadSignaturesQuery(ids, signatures);
00576 _dbSafeAccessMutex.unlock();
00577 }
00578 }
00579
00580 void DBDriver::loadWords(const std::set<int> & wordIds, std::list<VisualWord *> & vws)
00581 {
00582
00583 std::set<int> ids = wordIds;
00584 std::map<int, VisualWord*>::iterator wIter;
00585 std::list<VisualWord *> puttedBack;
00586 _trashesMutex.lock();
00587 {
00588 if(_trashVisualWords.size())
00589 {
00590 for(std::set<int>::iterator iter = ids.begin(); iter != ids.end();)
00591 {
00592 UASSERT(*iter>0);
00593 wIter = _trashVisualWords.find(*iter);
00594 if(wIter != _trashVisualWords.end())
00595 {
00596 UDEBUG("put back word %d from trash", *iter);
00597 puttedBack.push_back(wIter->second);
00598 _trashVisualWords.erase(wIter);
00599 ids.erase(iter++);
00600 }
00601 else
00602 {
00603 ++iter;
00604 }
00605 }
00606 }
00607 }
00608 _trashesMutex.unlock();
00609 if(ids.size())
00610 {
00611 _dbSafeAccessMutex.lock();
00612 this->loadWordsQuery(ids, vws);
00613 _dbSafeAccessMutex.unlock();
00614 uAppend(vws, puttedBack);
00615 }
00616 else if(puttedBack.size())
00617 {
00618 uAppend(vws, puttedBack);
00619 }
00620 }
00621
00622 void DBDriver::loadNodeData(std::list<Signature *> & signatures, bool images, bool scan, bool userData, bool occupancyGrid) const
00623 {
00624
00625
00626 _trashesMutex.lock();
00627 if(_trashSignatures.size())
00628 {
00629 for(std::list<Signature *>::iterator iter=signatures.begin(); iter!=signatures.end(); ++iter)
00630 {
00631 UASSERT(*iter != 0);
00632 UASSERT_MSG(!uContains(_trashSignatures, (*iter)->id()), uFormat("Signature %d should not be used when transferred to trash!!!!", (*iter)->id()).c_str());
00633 }
00634 }
00635 _trashesMutex.unlock();
00636
00637 _dbSafeAccessMutex.lock();
00638 this->loadNodeDataQuery(signatures, images, scan, userData, occupancyGrid);
00639 _dbSafeAccessMutex.unlock();
00640 }
00641
00642 void DBDriver::getNodeData(
00643 int signatureId,
00644 SensorData & data,
00645 bool images, bool scan, bool userData, bool occupancyGrid) const
00646 {
00647 bool found = false;
00648
00649 _trashesMutex.lock();
00650 if(uContains(_trashSignatures, signatureId))
00651 {
00652 const Signature * s = _trashSignatures.at(signatureId);
00653 if(!s->sensorData().imageCompressed().empty() ||
00654 !s->sensorData().laserScanCompressed().isEmpty() ||
00655 !s->sensorData().userDataCompressed().empty() ||
00656 s->sensorData().gridCellSize() != 0.0f ||
00657 !s->isSaved())
00658 {
00659 data = (SensorData)s->sensorData();
00660 found = true;
00661 }
00662 }
00663 _trashesMutex.unlock();
00664
00665 if(!found)
00666 {
00667 _dbSafeAccessMutex.lock();
00668 std::list<Signature *> signatures;
00669 Signature tmp(signatureId);
00670 signatures.push_back(&tmp);
00671 loadNodeDataQuery(signatures, images, scan, userData, occupancyGrid);
00672 data = signatures.front()->sensorData();
00673 _dbSafeAccessMutex.unlock();
00674 }
00675 }
00676
00677 bool DBDriver::getCalibration(
00678 int signatureId,
00679 std::vector<CameraModel> & models,
00680 StereoCameraModel & stereoModel) const
00681 {
00682 UDEBUG("");
00683 bool found = false;
00684
00685 _trashesMutex.lock();
00686 if(uContains(_trashSignatures, signatureId))
00687 {
00688 models = _trashSignatures.at(signatureId)->sensorData().cameraModels();
00689 stereoModel = _trashSignatures.at(signatureId)->sensorData().stereoCameraModel();
00690 found = true;
00691 }
00692 _trashesMutex.unlock();
00693
00694 if(!found)
00695 {
00696 _dbSafeAccessMutex.lock();
00697 found = this->getCalibrationQuery(signatureId, models, stereoModel);
00698 _dbSafeAccessMutex.unlock();
00699 }
00700 return found;
00701 }
00702
00703 bool DBDriver::getLaserScanInfo(
00704 int signatureId,
00705 LaserScan & info) const
00706 {
00707 UDEBUG("");
00708 bool found = false;
00709
00710 _trashesMutex.lock();
00711 if(uContains(_trashSignatures, signatureId))
00712 {
00713 info = _trashSignatures.at(signatureId)->sensorData().laserScanCompressed();
00714 found = true;
00715 }
00716 _trashesMutex.unlock();
00717
00718 if(!found)
00719 {
00720 _dbSafeAccessMutex.lock();
00721 found = this->getLaserScanInfoQuery(signatureId, info);
00722 _dbSafeAccessMutex.unlock();
00723 }
00724 return found;
00725 }
00726
00727 bool DBDriver::getNodeInfo(
00728 int signatureId,
00729 Transform & pose,
00730 int & mapId,
00731 int & weight,
00732 std::string & label,
00733 double & stamp,
00734 Transform & groundTruthPose,
00735 std::vector<float> & velocity,
00736 GPS & gps) const
00737 {
00738 bool found = false;
00739
00740 _trashesMutex.lock();
00741 if(uContains(_trashSignatures, signatureId))
00742 {
00743 pose = _trashSignatures.at(signatureId)->getPose();
00744 mapId = _trashSignatures.at(signatureId)->mapId();
00745 weight = _trashSignatures.at(signatureId)->getWeight();
00746 label = _trashSignatures.at(signatureId)->getLabel();
00747 stamp = _trashSignatures.at(signatureId)->getStamp();
00748 groundTruthPose = _trashSignatures.at(signatureId)->getGroundTruthPose();
00749 gps = _trashSignatures.at(signatureId)->sensorData().gps();
00750 found = true;
00751 }
00752 _trashesMutex.unlock();
00753
00754 if(!found)
00755 {
00756 _dbSafeAccessMutex.lock();
00757 found = this->getNodeInfoQuery(signatureId, pose, mapId, weight, label, stamp, groundTruthPose, velocity, gps);
00758 _dbSafeAccessMutex.unlock();
00759 }
00760 return found;
00761 }
00762
00763 void DBDriver::loadLinks(int signatureId, std::map<int, Link> & links, Link::Type type) const
00764 {
00765 bool found = false;
00766
00767 _trashesMutex.lock();
00768 if(uContains(_trashSignatures, signatureId))
00769 {
00770 const Signature * s = _trashSignatures.at(signatureId);
00771 UASSERT(s != 0);
00772 for(std::map<int, Link>::const_iterator nIter = s->getLinks().begin();
00773 nIter!=s->getLinks().end();
00774 ++nIter)
00775 {
00776 if(type == Link::kUndef || nIter->second.type() == type)
00777 {
00778 links.insert(*nIter);
00779 }
00780 }
00781 found = true;
00782 }
00783 _trashesMutex.unlock();
00784
00785 if(!found)
00786 {
00787 _dbSafeAccessMutex.lock();
00788 this->loadLinksQuery(signatureId, links, type);
00789 _dbSafeAccessMutex.unlock();
00790 }
00791 }
00792
00793 void DBDriver::getWeight(int signatureId, int & weight) const
00794 {
00795 bool found = false;
00796
00797 _trashesMutex.lock();
00798 if(uContains(_trashSignatures, signatureId))
00799 {
00800 weight = _trashSignatures.at(signatureId)->getWeight();
00801 found = true;
00802 }
00803 _trashesMutex.unlock();
00804
00805 if(!found)
00806 {
00807 _dbSafeAccessMutex.lock();
00808 this->getWeightQuery(signatureId, weight);
00809 _dbSafeAccessMutex.unlock();
00810 }
00811 }
00812
00813 void DBDriver::getAllNodeIds(std::set<int> & ids, bool ignoreChildren, bool ignoreBadSignatures) const
00814 {
00815
00816 _trashesMutex.lock();
00817 if(_trashSignatures.size())
00818 {
00819 for(std::map<int, Signature*>::const_iterator sIter = _trashSignatures.begin(); sIter!=_trashSignatures.end(); ++sIter)
00820 {
00821 bool hasNeighbors = !ignoreChildren;
00822 if(ignoreChildren)
00823 {
00824 for(std::map<int, Link>::const_iterator nIter = sIter->second->getLinks().begin();
00825 nIter!=sIter->second->getLinks().end();
00826 ++nIter)
00827 {
00828 if(nIter->second.type() == Link::kNeighbor ||
00829 nIter->second.type() == Link::kNeighborMerged)
00830 {
00831 hasNeighbors = true;
00832 break;
00833 }
00834 }
00835 }
00836 if(hasNeighbors)
00837 {
00838 ids.insert(sIter->first);
00839 }
00840 }
00841
00842 std::vector<int> keys = uKeys(_trashSignatures);
00843
00844 }
00845 _trashesMutex.unlock();
00846
00847 _dbSafeAccessMutex.lock();
00848 this->getAllNodeIdsQuery(ids, ignoreChildren, ignoreBadSignatures);
00849 _dbSafeAccessMutex.unlock();
00850 }
00851
00852 void DBDriver::getAllLinks(std::multimap<int, Link> & links, bool ignoreNullLinks) const
00853 {
00854 _dbSafeAccessMutex.lock();
00855 this->getAllLinksQuery(links, ignoreNullLinks);
00856 _dbSafeAccessMutex.unlock();
00857
00858
00859 _trashesMutex.lock();
00860 if(_trashSignatures.size())
00861 {
00862 for(std::map<int, Signature*>::const_iterator iter=_trashSignatures.begin(); iter!=_trashSignatures.end(); ++iter)
00863 {
00864 links.erase(iter->first);
00865 for(std::map<int, Link>::const_iterator jter=iter->second->getLinks().begin();
00866 jter!=iter->second->getLinks().end();
00867 ++jter)
00868 {
00869 if(!ignoreNullLinks || jter->second.isValid())
00870 {
00871 links.insert(std::make_pair(iter->first, jter->second));
00872 }
00873 }
00874 }
00875 }
00876 _trashesMutex.unlock();
00877 }
00878
00879 void DBDriver::getLastNodeId(int & id) const
00880 {
00881
00882 _trashesMutex.lock();
00883 if(_trashSignatures.size())
00884 {
00885 id = _trashSignatures.rbegin()->first;
00886 }
00887 _trashesMutex.unlock();
00888
00889 _dbSafeAccessMutex.lock();
00890 this->getLastIdQuery("Node", id);
00891 int statisticsId = 0;
00892 if(uStrNumCmp(this->getDatabaseVersion(), "0.11.11") >= 0)
00893 {
00894 this->getLastIdQuery("Statistics", statisticsId);
00895 if(statisticsId > id)
00896 {
00897 id = statisticsId;
00898 }
00899 }
00900 _dbSafeAccessMutex.unlock();
00901 }
00902
00903 void DBDriver::getLastWordId(int & id) const
00904 {
00905
00906 _trashesMutex.lock();
00907 if(_trashVisualWords.size())
00908 {
00909 id = _trashVisualWords.rbegin()->first;
00910 }
00911 _trashesMutex.unlock();
00912
00913 _dbSafeAccessMutex.lock();
00914 this->getLastIdQuery("Word", id);
00915 _dbSafeAccessMutex.unlock();
00916 }
00917
00918 void DBDriver::getInvertedIndexNi(int signatureId, int & ni) const
00919 {
00920 bool found = false;
00921
00922 _trashesMutex.lock();
00923 if(uContains(_trashSignatures, signatureId))
00924 {
00925 ni = _trashSignatures.at(signatureId)->getWords().size();
00926 found = true;
00927 }
00928 _trashesMutex.unlock();
00929
00930 if(!found)
00931 {
00932 _dbSafeAccessMutex.lock();
00933 this->getInvertedIndexNiQuery(signatureId, ni);
00934 _dbSafeAccessMutex.unlock();
00935 }
00936 }
00937
00938 void DBDriver::getNodeIdByLabel(const std::string & label, int & id) const
00939 {
00940 if(!label.empty())
00941 {
00942 int idFound = 0;
00943
00944 _trashesMutex.lock();
00945 for(std::map<int, Signature*>::const_iterator sIter = _trashSignatures.begin(); sIter!=_trashSignatures.end(); ++sIter)
00946 {
00947 if(sIter->second->getLabel().compare(label) == 0)
00948 {
00949 idFound = sIter->first;
00950 break;
00951 }
00952 }
00953 _trashesMutex.unlock();
00954
00955
00956 if(idFound == 0)
00957 {
00958 _dbSafeAccessMutex.lock();
00959 this->getNodeIdByLabelQuery(label, id);
00960 _dbSafeAccessMutex.unlock();
00961 }
00962 else
00963 {
00964 id = idFound;
00965 }
00966 }
00967 else
00968 {
00969 UWARN("Can't search with an empty label!");
00970 }
00971 }
00972
00973 void DBDriver::getAllLabels(std::map<int, std::string> & labels) const
00974 {
00975
00976 _trashesMutex.lock();
00977 for(std::map<int, Signature*>::const_iterator sIter = _trashSignatures.begin(); sIter!=_trashSignatures.end(); ++sIter)
00978 {
00979 if(!sIter->second->getLabel().empty())
00980 {
00981 labels.insert(std::make_pair(sIter->first, sIter->second->getLabel()));
00982 }
00983 }
00984 _trashesMutex.unlock();
00985
00986
00987 _dbSafeAccessMutex.lock();
00988 this->getAllLabelsQuery(labels);
00989 _dbSafeAccessMutex.unlock();
00990 }
00991
00992 void DBDriver::addInfoAfterRun(
00993 int stMemSize,
00994 int lastSignAdded,
00995 int processMemUsed,
00996 int databaseMemUsed,
00997 int dictionarySize,
00998 const ParametersMap & parameters) const
00999 {
01000 ULOGGER_DEBUG("");
01001 if(this->isConnected())
01002 {
01003 std::stringstream query;
01004 if(uStrNumCmp(this->getDatabaseVersion(), "0.11.8") >= 0)
01005 {
01006 std::string param = Parameters::serialize(parameters);
01007 if(uStrNumCmp(this->getDatabaseVersion(), "0.11.11") >= 0)
01008 {
01009 query << "INSERT INTO Info(STM_size,last_sign_added,process_mem_used,database_mem_used,dictionary_size,parameters) values("
01010 << stMemSize << ","
01011 << lastSignAdded << ","
01012 << processMemUsed << ","
01013 << databaseMemUsed << ","
01014 << dictionarySize << ","
01015 "\"" << param.c_str() << "\");";
01016 }
01017 else
01018 {
01019 query << "INSERT INTO Statistics(STM_size,last_sign_added,process_mem_used,database_mem_used,dictionary_size,parameters) values("
01020 << stMemSize << ","
01021 << lastSignAdded << ","
01022 << processMemUsed << ","
01023 << databaseMemUsed << ","
01024 << dictionarySize << ","
01025 "\"" << param.c_str() << "\");";
01026 }
01027 }
01028 else
01029 {
01030 query << "INSERT INTO Statistics(STM_size,last_sign_added,process_mem_used,database_mem_used,dictionary_size) values("
01031 << stMemSize << ","
01032 << lastSignAdded << ","
01033 << processMemUsed << ","
01034 << databaseMemUsed << ","
01035 << dictionarySize << ");";
01036 }
01037
01038 this->executeNoResultQuery(query.str());
01039 }
01040 }
01041
01042 void DBDriver::addStatistics(const Statistics & statistics) const
01043 {
01044 _dbSafeAccessMutex.lock();
01045 addStatisticsQuery(statistics);
01046 _dbSafeAccessMutex.unlock();
01047 }
01048
01049 void DBDriver::savePreviewImage(const cv::Mat & image) const
01050 {
01051 _dbSafeAccessMutex.lock();
01052 savePreviewImageQuery(image);
01053 _dbSafeAccessMutex.unlock();
01054 }
01055
01056 cv::Mat DBDriver::loadPreviewImage() const
01057 {
01058 _dbSafeAccessMutex.lock();
01059 cv::Mat image = loadPreviewImageQuery();
01060 _dbSafeAccessMutex.unlock();
01061 return image;
01062 }
01063
01064 void DBDriver::saveOptimizedPoses(const std::map<int, Transform> & optimizedPoses, const Transform & lastlocalizationPose) const
01065 {
01066 _dbSafeAccessMutex.lock();
01067 saveOptimizedPosesQuery(optimizedPoses, lastlocalizationPose);
01068 _dbSafeAccessMutex.unlock();
01069 }
01070 std::map<int, Transform> DBDriver::loadOptimizedPoses(Transform * lastlocalizationPose) const
01071 {
01072 _dbSafeAccessMutex.lock();
01073 std::map<int, Transform> poses = loadOptimizedPosesQuery(lastlocalizationPose);
01074 _dbSafeAccessMutex.unlock();
01075 return poses;
01076 }
01077
01078 void DBDriver::save2DMap(const cv::Mat & map, float xMin, float yMin, float cellSize) const
01079 {
01080 _dbSafeAccessMutex.lock();
01081 save2DMapQuery(map, xMin, yMin, cellSize);
01082 _dbSafeAccessMutex.unlock();
01083 }
01084
01085 cv::Mat DBDriver::load2DMap(float & xMin, float & yMin, float & cellSize) const
01086 {
01087 _dbSafeAccessMutex.lock();
01088 cv::Mat map = load2DMapQuery(xMin, yMin, cellSize);
01089 _dbSafeAccessMutex.unlock();
01090 return map;
01091 }
01092
01093 void DBDriver::saveOptimizedMesh(
01094 const cv::Mat & cloud,
01095 const std::vector<std::vector<std::vector<unsigned int> > > & polygons,
01096 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
01097 const std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > & texCoords,
01098 #else
01099 const std::vector<std::vector<Eigen::Vector2f> > & texCoords,
01100 #endif
01101 const cv::Mat & textures) const
01102 {
01103 _dbSafeAccessMutex.lock();
01104 saveOptimizedMeshQuery(cloud, polygons, texCoords, textures);
01105 _dbSafeAccessMutex.unlock();
01106 }
01107
01108 cv::Mat DBDriver::loadOptimizedMesh(
01109 std::vector<std::vector<std::vector<unsigned int> > > * polygons,
01110 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
01111 std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > * texCoords,
01112 #else
01113 std::vector<std::vector<Eigen::Vector2f> > * texCoords,
01114 #endif
01115 cv::Mat * textures) const
01116 {
01117 _dbSafeAccessMutex.lock();
01118 cv::Mat cloud = loadOptimizedMeshQuery(polygons, texCoords, textures);
01119 _dbSafeAccessMutex.unlock();
01120 return cloud;
01121 }
01122
01123 void DBDriver::generateGraph(
01124 const std::string & fileName,
01125 const std::set<int> & idsInput,
01126 const std::map<int, Signature *> & otherSignatures)
01127 {
01128 if(this->isConnected())
01129 {
01130 if(!fileName.empty())
01131 {
01132 FILE* fout = 0;
01133 #ifdef _MSC_VER
01134 fopen_s(&fout, fileName.c_str(), "w");
01135 #else
01136 fout = fopen(fileName.c_str(), "w");
01137 #endif
01138
01139 if (!fout)
01140 {
01141 UERROR("Cannot open file %s!", fileName.c_str());
01142 return;
01143 }
01144
01145 std::set<int> ids;
01146 if(idsInput.size() == 0)
01147 {
01148 this->getAllNodeIds(ids);
01149 UDEBUG("ids.size()=%d", ids.size());
01150 for(std::map<int, Signature*>::const_iterator iter=otherSignatures.begin(); iter!=otherSignatures.end(); ++iter)
01151 {
01152 ids.insert(iter->first);
01153 }
01154 }
01155 else
01156 {
01157 ids = idsInput;
01158 }
01159
01160 const char * colorG = "green";
01161 const char * colorP = "pink";
01162 const char * colorNM = "blue";
01163 UINFO("Generating map with %d locations", ids.size());
01164 fprintf(fout, "digraph G {\n");
01165 for(std::set<int>::iterator i=ids.begin(); i!=ids.end(); ++i)
01166 {
01167 if(otherSignatures.find(*i) == otherSignatures.end())
01168 {
01169 int id = *i;
01170 std::map<int, Link> links;
01171 this->loadLinks(id, links);
01172 int weight = 0;
01173 this->getWeight(id, weight);
01174 for(std::map<int, Link>::iterator iter = links.begin(); iter!=links.end(); ++iter)
01175 {
01176 int weightNeighbor = 0;
01177 if(otherSignatures.find(iter->first) == otherSignatures.end())
01178 {
01179 this->getWeight(iter->first, weightNeighbor);
01180 }
01181 else
01182 {
01183 weightNeighbor = otherSignatures.find(iter->first)->second->getWeight();
01184 }
01185
01186 if(iter->second.type() == Link::kNeighbor)
01187 {
01188 fprintf(fout, " \"%d\\n%d\" -> \"%d\\n%d\"\n",
01189 id,
01190 weight,
01191 iter->first,
01192 weightNeighbor);
01193 }
01194 else if(iter->second.type() == Link::kNeighborMerged)
01195 {
01196
01197 fprintf(fout, " \"%d\\n%d\" -> \"%d\\n%d\" [label=\"M\", fontcolor=%s, fontsize=8];\n",
01198 id,
01199 weight,
01200 iter->first,
01201 weightNeighbor,
01202 colorNM);
01203 }
01204 else if(iter->first > id)
01205 {
01206
01207 fprintf(fout, " \"%d\\n%d\" -> \"%d\\n%d\" [label=\"L\", fontcolor=%s, fontsize=8];\n",
01208 id,
01209 weight,
01210 iter->first,
01211 weightNeighbor,
01212 colorG);
01213 }
01214 else
01215 {
01216
01217 fprintf(fout, " \"%d\\n%d\" -> \"%d\\n%d\" [label=\"C\", fontcolor=%s, fontsize=8];\n",
01218 id,
01219 weight,
01220 iter->first,
01221 weightNeighbor,
01222 colorP);
01223 }
01224 }
01225 }
01226 }
01227 for(std::map<int, Signature*>::const_iterator i=otherSignatures.begin(); i!=otherSignatures.end(); ++i)
01228 {
01229 if(ids.find(i->first) != ids.end())
01230 {
01231 int id = i->second->id();
01232 const std::map<int, Link> & links = i->second->getLinks();
01233 int weight = i->second->getWeight();
01234 for(std::map<int, Link>::const_iterator iter = links.begin(); iter!=links.end(); ++iter)
01235 {
01236 int weightNeighbor = 0;
01237 const Signature * s = uValue(otherSignatures, iter->first, (Signature*)0);
01238 if(s)
01239 {
01240 weightNeighbor = s->getWeight();
01241 }
01242 else
01243 {
01244 this->getWeight(iter->first, weightNeighbor);
01245 }
01246
01247 if(iter->second.type() == Link::kNeighbor)
01248 {
01249 fprintf(fout, " \"%d\\n%d\" -> \"%d\\n%d\"\n",
01250 id,
01251 weight,
01252 iter->first,
01253 weightNeighbor);
01254 }
01255 else if(iter->second.type() == Link::kNeighborMerged)
01256 {
01257 fprintf(fout, " \"%d\\n%d\" -> \"%d\\n%d\" [label=\"M\", fontcolor=%s, fontsize=8];\n",
01258 id,
01259 weight,
01260 iter->first,
01261 weightNeighbor,
01262 colorNM);
01263 }
01264 else if(iter->first > id)
01265 {
01266
01267 fprintf(fout, " \"%d\\n%d\" -> \"%d\\n%d\" [label=\"L\", fontcolor=%s, fontsize=8];\n",
01268 id,
01269 weight,
01270 iter->first,
01271 weightNeighbor,
01272 colorG);
01273 }
01274 else if(iter->first != id)
01275 {
01276
01277 fprintf(fout, " \"%d\\n%d\" -> \"%d\\n%d\" [label=\"C\", fontcolor=%s, fontsize=8];\n",
01278 id,
01279 weight,
01280 iter->first,
01281 weightNeighbor,
01282 colorP);
01283 }
01284 }
01285 }
01286 }
01287 fprintf(fout, "}\n");
01288 fclose(fout);
01289 UINFO("Graph saved to \"%s\" (Tip: $ neato -Tpdf \"%s\" -o out.pdf)", fileName.c_str(), fileName.c_str());
01290 }
01291 }
01292 }
01293
01294 }