Rtabmap.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/Rtabmap.h"
29 #include "rtabmap/core/Version.h"
31 #include "rtabmap/core/Optimizer.h"
32 #include "rtabmap/core/Graph.h"
33 #include "rtabmap/core/Signature.h"
34 
36 
37 #include "rtabmap/core/util3d.h"
41 
42 #include "rtabmap/core/DBDriver.h"
43 #include "rtabmap/core/Memory.h"
49 
51 #include <rtabmap/utilite/UFile.h>
52 #include <rtabmap/utilite/UTimer.h>
54 #include <rtabmap/utilite/UMath.h>
56 
57 #ifdef RTABMAP_PYTHON
59 #endif
60 
61 #ifdef RTABMAP_MRPT
62 // Used for odometry error propagation
63 #include <mrpt/poses/CPose3DPDFGaussian.h>
64 #endif
65 
66 #include <pcl/search/kdtree.h>
67 #include <pcl/filters/crop_box.h>
68 #include <pcl/io/pcd_io.h>
69 #include <pcl/common/common.h>
70 #include <pcl/TextureMesh.h>
71 
72 #include <stdlib.h>
73 #include <set>
74 
75 #define LOG_F "LogF.txt"
76 #define LOG_I "LogI.txt"
77 
78 #define GRAPH_FILE_NAME "Graph.dot"
79 
80 
81 //
82 //
83 //
84 // =======================================================
85 // MAIN LOOP, see method "void Rtabmap::process();" below.
86 // =======================================================
87 //
88 //
89 //
90 
91 namespace rtabmap
92 {
93 
95  _publishStats(Parameters::defaultRtabmapPublishStats()),
96  _publishLastSignatureData(Parameters::defaultRtabmapPublishLastSignature()),
97  _publishPdf(Parameters::defaultRtabmapPublishPdf()),
98  _publishLikelihood(Parameters::defaultRtabmapPublishLikelihood()),
99  _publishRAMUsage(Parameters::defaultRtabmapPublishRAMUsage()),
100  _computeRMSE(Parameters::defaultRtabmapComputeRMSE()),
101  _saveWMState(Parameters::defaultRtabmapSaveWMState()),
102  _maxTimeAllowed(Parameters::defaultRtabmapTimeThr()), // 700 ms
103  _maxMemoryAllowed(Parameters::defaultRtabmapMemoryThr()), // 0=inf
104  _loopThr(Parameters::defaultRtabmapLoopThr()),
105  _loopRatio(Parameters::defaultRtabmapLoopRatio()),
106  _aggressiveLoopThr(Parameters::defaultRGBDAggressiveLoopThr()),
107  _virtualPlaceLikelihoodRatio(Parameters::defaultRtabmapVirtualPlaceLikelihoodRatio()),
108  _maxLoopClosureDistance(Parameters::defaultRGBDMaxLoopClosureDistance()),
109  _verifyLoopClosureHypothesis(Parameters::defaultVhEpEnabled()),
110  _maxRetrieved(Parameters::defaultRtabmapMaxRetrieved()),
111  _maxLocalRetrieved(Parameters::defaultRGBDMaxLocalRetrieved()),
112  _maxRepublished(Parameters::defaultRtabmapMaxRepublished()),
113  _rawDataKept(Parameters::defaultMemImageKept()),
114  _statisticLogsBufferedInRAM(Parameters::defaultRtabmapStatisticLogsBufferedInRAM()),
115  _statisticLogged(Parameters::defaultRtabmapStatisticLogged()),
116  _statisticLoggedHeaders(Parameters::defaultRtabmapStatisticLoggedHeaders()),
117  _rgbdSlamMode(Parameters::defaultRGBDEnabled()),
118  _rgbdLinearUpdate(Parameters::defaultRGBDLinearUpdate()),
119  _rgbdAngularUpdate(Parameters::defaultRGBDAngularUpdate()),
120  _rgbdLinearSpeedUpdate(Parameters::defaultRGBDLinearSpeedUpdate()),
121  _rgbdAngularSpeedUpdate(Parameters::defaultRGBDAngularSpeedUpdate()),
122  _newMapOdomChangeDistance(Parameters::defaultRGBDNewMapOdomChangeDistance()),
123  _neighborLinkRefining(Parameters::defaultRGBDNeighborLinkRefining()),
124  _proximityByTime(Parameters::defaultRGBDProximityByTime()),
125  _proximityBySpace(Parameters::defaultRGBDProximityBySpace()),
126  _scanMatchingIdsSavedInLinks(Parameters::defaultRGBDScanMatchingIdsSavedInLinks()),
127  _loopClosureIdentityGuess(Parameters::defaultRGBDLoopClosureIdentityGuess()),
128  _localRadius(Parameters::defaultRGBDLocalRadius()),
129  _localImmunizationRatio(Parameters::defaultRGBDLocalImmunizationRatio()),
130  _proximityMaxGraphDepth(Parameters::defaultRGBDProximityMaxGraphDepth()),
131  _proximityMaxPaths(Parameters::defaultRGBDProximityMaxPaths()),
132  _proximityMaxNeighbors(Parameters::defaultRGBDProximityPathMaxNeighbors()),
133  _proximityFilteringRadius(Parameters::defaultRGBDProximityPathFilteringRadius()),
134  _proximityRawPosesUsed(Parameters::defaultRGBDProximityPathRawPosesUsed()),
135  _proximityAngle(Parameters::defaultRGBDProximityAngle()*M_PI/180.0f),
136  _proximityOdomGuess(Parameters::defaultRGBDProximityOdomGuess()),
137  _proximityMergedScanCovFactor(Parameters::defaultRGBDProximityMergedScanCovFactor()),
138  _databasePath(""),
139  _optimizeFromGraphEnd(Parameters::defaultRGBDOptimizeFromGraphEnd()),
140  _optimizationMaxError(Parameters::defaultRGBDOptimizeMaxError()),
141  _startNewMapOnLoopClosure(Parameters::defaultRtabmapStartNewMapOnLoopClosure()),
142  _startNewMapOnGoodSignature(Parameters::defaultRtabmapStartNewMapOnGoodSignature()),
143  _goalReachedRadius(Parameters::defaultRGBDGoalReachedRadius()),
144  _goalsSavedInUserData(Parameters::defaultRGBDGoalsSavedInUserData()),
145  _pathStuckIterations(Parameters::defaultRGBDPlanStuckIterations()),
146  _pathLinearVelocity(Parameters::defaultRGBDPlanLinearVelocity()),
147  _pathAngularVelocity(Parameters::defaultRGBDPlanAngularVelocity()),
148  _forceOdom3doF(Parameters::defaultRGBDForceOdom3DoF()),
149  _restartAtOrigin(Parameters::defaultRGBDStartAtOrigin()),
150  _loopCovLimited(Parameters::defaultRGBDLoopCovLimited()),
151  _loopGPS(Parameters::defaultRtabmapLoopGPS()),
152  _maxOdomCacheSize(Parameters::defaultRGBDMaxOdomCacheSize()),
153  _localizationSmoothing(Parameters::defaultRGBDLocalizationSmoothing()),
154  _localizationPriorInf(1.0/(Parameters::defaultRGBDLocalizationPriorError()*Parameters::defaultRGBDLocalizationPriorError())),
155  _createGlobalScanMap(Parameters::defaultRGBDProximityGlobalScanMap()),
156  _markerPriorsLinearVariance(Parameters::defaultMarkerPriorsVarianceLinear()),
157  _markerPriorsAngularVariance(Parameters::defaultMarkerPriorsVarianceAngular()),
158  _loopClosureHypothesis(0,0.0f),
159  _highestHypothesis(0,0.0f),
160  _lastProcessTime(0.0),
161  _someNodesHaveBeenTransferred(false),
162  _distanceTravelled(0.0f),
163  _distanceTravelledSinceLastLocalization(0.0f),
164  _optimizeFromGraphEndChanged(false),
165  _epipolarGeometry(0),
166  _bayesFilter(0),
167  _graphOptimizer(0),
168  _memory(0),
169  _foutFloat(0),
170  _foutInt(0),
171  _wDir(""),
172  _mapCorrection(Transform::getIdentity()),
173  _lastLocalizationNodeId(0),
174  _currentSessionHasGPS(false),
175  _pathStatus(0),
176  _pathCurrentIndex(0),
177  _pathGoalIndex(0),
178  _pathTransformToGoal(Transform::getIdentity()),
179  _pathStuckCount(0),
180  _pathStuckDistance(0.0f)
181 #ifdef RTABMAP_PYTHON
182  ,_python(new PythonInterface())
183 #endif
184 {
185 }
186 
188  UDEBUG("");
189  this->close();
190 }
191 
192 void Rtabmap::setupLogFiles(bool overwrite)
193 {
195  // Log files
196  if(_foutFloat)
197  {
198  fclose(_foutFloat);
199  _foutFloat = 0;
200  }
201  if(_foutInt)
202  {
203  fclose(_foutInt);
204  _foutInt = 0;
205  }
206 
207  if(_statisticLogged && !_wDir.empty())
208  {
209  std::string attributes = "a+"; // append to log files
210  if(overwrite)
211  {
212  // If a file with the same name already exists
213  // its content is erased and the file is treated
214  // as a new empty file.
215  attributes = "w";
216  }
217 
218  bool addLogFHeader = overwrite || !UFile::exists(_wDir+"/"+LOG_F);
219  bool addLogIHeader = overwrite || !UFile::exists(_wDir+"/"+LOG_I);
220 
221  #ifdef _MSC_VER
222  fopen_s(&_foutFloat, (_wDir+"/"+LOG_F).c_str(), attributes.c_str());
223  fopen_s(&_foutInt, (_wDir+"/"+LOG_I).c_str(), attributes.c_str());
224  #else
225  _foutFloat = fopen((_wDir+"/"+LOG_F).c_str(), attributes.c_str());
226  _foutInt = fopen((_wDir+"/"+LOG_I).c_str(), attributes.c_str());
227  #endif
228  // add header (column identification)
229  if(_statisticLoggedHeaders && addLogFHeader && _foutFloat)
230  {
231  fprintf(_foutFloat, "Column headers:\n");
232  fprintf(_foutFloat, " 1-Total iteration time (s)\n");
233  fprintf(_foutFloat, " 2-Memory update time (s)\n");
234  fprintf(_foutFloat, " 3-Retrieval time (s)\n");
235  fprintf(_foutFloat, " 4-Likelihood time (s)\n");
236  fprintf(_foutFloat, " 5-Posterior time (s)\n");
237  fprintf(_foutFloat, " 6-Hypothesis selection time (s)\n");
238  fprintf(_foutFloat, " 7-Hypothesis validation time (s)\n");
239  fprintf(_foutFloat, " 8-Transfer time (s)\n");
240  fprintf(_foutFloat, " 9-Statistics creation time (s)\n");
241  fprintf(_foutFloat, " 10-Loop closure hypothesis value\n");
242  fprintf(_foutFloat, " 11-NAN\n");
243  fprintf(_foutFloat, " 12-NAN\n");
244  fprintf(_foutFloat, " 13-NAN\n");
245  fprintf(_foutFloat, " 14-NAN\n");
246  fprintf(_foutFloat, " 15-NAN\n");
247  fprintf(_foutFloat, " 16-Virtual place hypothesis\n");
248  fprintf(_foutFloat, " 17-Join trash time (s)\n");
249  fprintf(_foutFloat, " 18-Weight Update (rehearsal) similarity\n");
250  fprintf(_foutFloat, " 19-Empty trash time (s)\n");
251  fprintf(_foutFloat, " 20-Retrieval database access time (s)\n");
252  fprintf(_foutFloat, " 21-Add loop closure link time (s)\n");
253  fprintf(_foutFloat, " 22-Memory cleanup time (s)\n");
254  fprintf(_foutFloat, " 23-Scan matching (odometry correction) time (s)\n");
255  fprintf(_foutFloat, " 24-Local time loop closure detection time (s)\n");
256  fprintf(_foutFloat, " 25-Local space loop closure detection time (s)\n");
257  fprintf(_foutFloat, " 26-Map optimization (s)\n");
258  }
259  if(_statisticLoggedHeaders && addLogIHeader && _foutInt)
260  {
261  fprintf(_foutInt, "Column headers:\n");
262  fprintf(_foutInt, " 1-Loop closure ID\n");
263  fprintf(_foutInt, " 2-Highest loop closure hypothesis\n");
264  fprintf(_foutInt, " 3-Locations transferred\n");
265  fprintf(_foutInt, " 4-NAN\n");
266  fprintf(_foutInt, " 5-Words extracted from the last image\n");
267  fprintf(_foutInt, " 6-Vocabulary size\n");
268  fprintf(_foutInt, " 7-Working memory size\n");
269  fprintf(_foutInt, " 8-Is loop closure hypothesis rejected?\n");
270  fprintf(_foutInt, " 9-NAN\n");
271  fprintf(_foutInt, " 10-NAN\n");
272  fprintf(_foutInt, " 11-Locations retrieved\n");
273  fprintf(_foutInt, " 12-Retrieval location ID\n");
274  fprintf(_foutInt, " 13-Unique words extraced from last image\n");
275  fprintf(_foutInt, " 14-Retrieval ID\n");
276  fprintf(_foutInt, " 15-Non-null likelihood values\n");
277  fprintf(_foutInt, " 16-Weight Update ID\n");
278  fprintf(_foutInt, " 17-Is last location merged through Weight Update?\n");
279  fprintf(_foutInt, " 18-Local graph size\n");
280  fprintf(_foutInt, " 19-Sensor data id\n");
281  fprintf(_foutInt, " 20-Indexed words\n");
282  fprintf(_foutInt, " 21-Index memory usage (KB)\n");
283  }
284 
285  ULOGGER_DEBUG("Log file (int)=%s", (_wDir+"/"+LOG_I).c_str());
286  ULOGGER_DEBUG("Log file (float)=%s", (_wDir+"/"+LOG_F).c_str());
287  }
288  else
289  {
290  if(_statisticLogged)
291  {
292  UWARN("Working directory is not set, log disabled!");
293  }
294  UDEBUG("Log disabled!");
295  }
296 }
297 
299 {
300  if(_foutFloat && _bufferedLogsF.size())
301  {
302  UDEBUG("_bufferedLogsF.size=%d", _bufferedLogsF.size());
303  for(std::list<std::string>::iterator iter = _bufferedLogsF.begin(); iter!=_bufferedLogsF.end(); ++iter)
304  {
305  fprintf(_foutFloat, "%s", iter->c_str());
306  }
307  _bufferedLogsF.clear();
308  }
309  if(_foutInt && _bufferedLogsI.size())
310  {
311  UDEBUG("_bufferedLogsI.size=%d", _bufferedLogsI.size());
312  for(std::list<std::string>::iterator iter = _bufferedLogsI.begin(); iter!=_bufferedLogsI.end(); ++iter)
313  {
314  fprintf(_foutInt, "%s", iter->c_str());
315  }
316  _bufferedLogsI.clear();
317  }
318 }
319 
320 void Rtabmap::init(const ParametersMap & parameters, const std::string & databasePath, bool loadDatabaseParameters)
321 {
322  UDEBUG("path=%s", databasePath.c_str());
323  _databasePath = databasePath;
324  if(!_databasePath.empty())
325  {
327  UINFO("Using database \"%s\".", _databasePath.c_str());
328  }
329  else
330  {
331  UWARN("Using empty database. Mapping session will not be saved unless it is closed with an output database path.");
332  }
333 
335 
336  ParametersMap allParameters;
337  if(!newDatabase && loadDatabaseParameters)
338  {
339  DBDriver * driver = DBDriver::create();
340  if(driver->openConnection(_databasePath, false))
341  {
342  allParameters = driver->getLastParameters();
343  // ignore working directory (we may be on a different computer)
344  allParameters.erase(Parameters::kRtabmapWorkingDirectory());
345  }
346  delete driver;
347  }
348 
349  uInsert(allParameters, parameters);
350  ParametersMap::const_iterator iter;
351  if((iter=allParameters.find(Parameters::kRtabmapWorkingDirectory())) != allParameters.end())
352  {
353  this->setWorkingDirectory(iter->second.c_str());
354  }
355 
356  // If doesn't exist, create a memory
357  if(!_memory)
358  {
359  _memory = new Memory(allParameters);
360  _memory->init(_databasePath, false, allParameters, true);
361  }
362 
363  _optimizedPoses.clear();
364  _constraints.clear();
366  _globalScanMapPoses.clear();
367  _odomCachePoses.clear();
368  _odomCacheConstraints.clear();
369  _nodesToRepublish.clear();
370 
371  // Parse all parameters
372  this->parseParameters(allParameters);
373 
374  Transform lastPose;
376  if(!_memory->isIncremental())
377  {
378  if(_optimizedPoses.empty() &&
379  _memory->getWorkingMem().size()>1 &&
380  _memory->getWorkingMem().lower_bound(1)!=_memory->getWorkingMem().end())
381  {
382  cv::Mat cov;
383  this->optimizeCurrentMap(
384  !_optimizeFromGraphEnd?_memory->getWorkingMem().lower_bound(1)->first:_memory->getWorkingMem().rbegin()->first,
385  false, _optimizedPoses, cov, &_constraints);
386  }
387  if(!_optimizedPoses.empty())
388  {
389  if(_restartAtOrigin)
390  {
391  UWARN("last localization pose is ignored (%s=true), assuming we start at the origin of the map.", Parameters::kRGBDStartAtOrigin().c_str());
392  lastPose = _optimizedPoses.begin()->second;
393  }
394  _lastLocalizationPose = lastPose;
395 
396  UINFO("Loaded optimizedPoses=%d firstPose %d=%s lastLocalizationPose=%s",
397  _optimizedPoses.size(),
398  _optimizedPoses.begin()->first,
399  _optimizedPoses.begin()->second.prettyPrint().c_str(),
401 
402  if(_constraints.empty())
403  {
404  std::map<int, Transform> tmp;
405  // Get just the links
407  }
408 
409  // Initialize Bayes' prediction matrix
410  UTimer time;
411  std::map<int, float> likelihood;
412  likelihood.insert(std::make_pair(Memory::kIdVirtual, 1));
413  for(std::map<int, Transform>::iterator iter=_optimizedPoses.begin(); iter!=_optimizedPoses.end(); ++iter)
414  {
415  if(_memory->getSignature(iter->first))
416  {
417  likelihood.insert(std::make_pair(iter->first, 0));
418  }
419  }
420  _bayesFilter->computePosterior(_memory, likelihood);
421  UINFO("Time initializing Bayes' prediction with %ld nodes: %fs", _optimizedPoses.size(), time.ticks());
422 
425  }
426  else
427  {
428  UINFO("Loaded optimizedPoses=0, last localization pose is ignored!");
429  }
430  }
431  else
432  {
433  _lastLocalizationPose = lastPose;
434  if(!_optimizedPoses.empty())
435  {
436  std::map<int, Transform> tmp;
437  // Get just the links
439  }
440  }
441 
442  if(_databasePath.empty())
443  {
444  _statisticLogged = false;
445  }
447 }
448 
449 void Rtabmap::init(const std::string & configFile, const std::string & databasePath, bool loadDatabaseParameters)
450 {
451  // fill ctrl struct with values from the configuration file
452  ParametersMap param;// = Parameters::defaultParameters;
453 
454  if(!configFile.empty())
455  {
456  ULOGGER_DEBUG("Read parameters from = %s", configFile.c_str());
457  Parameters::readINI(configFile, param);
458  }
459 
460  this->init(param, databasePath, loadDatabaseParameters);
461 }
462 
463 void Rtabmap::close(bool databaseSaved, const std::string & ouputDatabasePath)
464 {
465  UINFO("databaseSaved=%d", databaseSaved?1:0);
466  _highestHypothesis = std::make_pair(0,0.0f);
467  _loopClosureHypothesis = std::make_pair(0,0.0f);
468  _lastProcessTime = 0.0;
470  _constraints.clear();
473 
474  _localizationCovariance = cv::Mat();
476  _odomCachePoses.clear();
477  _odomCacheConstraints.clear();
478  _distanceTravelled = 0.0f;
481  this->clearPath(0);
482  _gpsGeocentricCache.clear();
483  _currentSessionHasGPS = false;
484 
486  _globalScanMapPoses.clear();
487 
488  _nodesToRepublish.clear();
489 
491  if(_foutFloat)
492  {
493  fclose(_foutFloat);
494  _foutFloat = 0;
495  }
496  if(_foutInt)
497  {
498  fclose(_foutInt);
499  _foutInt = 0;
500  }
501 
503  {
504  delete _epipolarGeometry;
505  _epipolarGeometry = 0;
506  }
507  if(_memory)
508  {
509  if(databaseSaved)
510  {
512  {
513  // Force reducing graph, then remove filtered nodes from the optimized poses
514  std::map<int, int> reducedIds;
515  _memory->incrementMapId(&reducedIds);
516  for(std::map<int, int>::iterator iter=reducedIds.begin(); iter!=reducedIds.end(); ++iter)
517  {
518  _optimizedPoses.erase(iter->first);
519  }
520  }
522  }
523  _memory->close(databaseSaved, true, ouputDatabasePath);
524  delete _memory;
525  _memory = 0;
526  }
527  _optimizedPoses.clear();
529 
530  if(_bayesFilter)
531  {
532  delete _bayesFilter;
533  _bayesFilter = 0;
534  }
535  if(_graphOptimizer)
536  {
537  delete _graphOptimizer;
538  _graphOptimizer = 0;
539  }
540  _databasePath.clear();
541  parseParameters(Parameters::getDefaultParameters()); // reset to default parameters
542  _parameters.clear();
543 }
544 
545 void Rtabmap::parseParameters(const ParametersMap & parameters)
546 {
547  uInsert(_parameters, parameters);
548 
549  // place this before changing working directory
550  Parameters::parse(parameters, Parameters::kRtabmapStatisticLogsBufferedInRAM(), _statisticLogsBufferedInRAM);
551  Parameters::parse(parameters, Parameters::kRtabmapStatisticLogged(), _statisticLogged);
552  Parameters::parse(parameters, Parameters::kRtabmapStatisticLoggedHeaders(), _statisticLoggedHeaders);
553 
554  ULOGGER_DEBUG("");
555  ParametersMap::const_iterator iter;
556  if((iter=parameters.find(Parameters::kRtabmapWorkingDirectory())) != parameters.end())
557  {
558  this->setWorkingDirectory(iter->second.c_str());
559  }
560 
561  Parameters::parse(parameters, Parameters::kRtabmapPublishStats(), _publishStats);
562  Parameters::parse(parameters, Parameters::kRtabmapPublishLastSignature(), _publishLastSignatureData);
563  Parameters::parse(parameters, Parameters::kRtabmapPublishPdf(), _publishPdf);
564  Parameters::parse(parameters, Parameters::kRtabmapPublishLikelihood(), _publishLikelihood);
565  Parameters::parse(parameters, Parameters::kRtabmapPublishRAMUsage(), _publishRAMUsage);
566  Parameters::parse(parameters, Parameters::kRtabmapComputeRMSE(), _computeRMSE);
567  Parameters::parse(parameters, Parameters::kRtabmapSaveWMState(), _saveWMState);
568  Parameters::parse(parameters, Parameters::kRtabmapTimeThr(), _maxTimeAllowed);
569  Parameters::parse(parameters, Parameters::kRtabmapMemoryThr(), _maxMemoryAllowed);
570  Parameters::parse(parameters, Parameters::kRtabmapLoopThr(), _loopThr);
571  Parameters::parse(parameters, Parameters::kRtabmapLoopRatio(), _loopRatio);
572  Parameters::parse(parameters, Parameters::kRGBDAggressiveLoopThr(), _aggressiveLoopThr);
573  Parameters::parse(parameters, Parameters::kRtabmapVirtualPlaceLikelihoodRatio(), _virtualPlaceLikelihoodRatio);
574 
575  Parameters::parse(parameters, Parameters::kRGBDMaxLoopClosureDistance(), _maxLoopClosureDistance);
576  Parameters::parse(parameters, Parameters::kVhEpEnabled(), _verifyLoopClosureHypothesis);
577  Parameters::parse(parameters, Parameters::kRtabmapMaxRetrieved(), _maxRetrieved);
578  Parameters::parse(parameters, Parameters::kRGBDMaxLocalRetrieved(), _maxLocalRetrieved);
579  Parameters::parse(parameters, Parameters::kRtabmapMaxRepublished(), _maxRepublished);
581  {
582  _nodesToRepublish.clear();
583  }
584  Parameters::parse(parameters, Parameters::kMemImageKept(), _rawDataKept);
585  Parameters::parse(parameters, Parameters::kRGBDEnabled(), _rgbdSlamMode);
586  Parameters::parse(parameters, Parameters::kRGBDLinearUpdate(), _rgbdLinearUpdate);
587  Parameters::parse(parameters, Parameters::kRGBDAngularUpdate(), _rgbdAngularUpdate);
588  Parameters::parse(parameters, Parameters::kRGBDLinearSpeedUpdate(), _rgbdLinearSpeedUpdate);
589  Parameters::parse(parameters, Parameters::kRGBDAngularSpeedUpdate(), _rgbdAngularSpeedUpdate);
590  Parameters::parse(parameters, Parameters::kRGBDNewMapOdomChangeDistance(), _newMapOdomChangeDistance);
591  Parameters::parse(parameters, Parameters::kRGBDNeighborLinkRefining(), _neighborLinkRefining);
592  Parameters::parse(parameters, Parameters::kRGBDProximityByTime(), _proximityByTime);
593  Parameters::parse(parameters, Parameters::kRGBDProximityBySpace(), _proximityBySpace);
594  Parameters::parse(parameters, Parameters::kRGBDScanMatchingIdsSavedInLinks(), _scanMatchingIdsSavedInLinks);
595  Parameters::parse(parameters, Parameters::kRGBDLoopClosureIdentityGuess(), _loopClosureIdentityGuess);
596  Parameters::parse(parameters, Parameters::kRGBDLocalRadius(), _localRadius);
597  Parameters::parse(parameters, Parameters::kRGBDLocalImmunizationRatio(), _localImmunizationRatio);
598  Parameters::parse(parameters, Parameters::kRGBDProximityMaxGraphDepth(), _proximityMaxGraphDepth);
599  Parameters::parse(parameters, Parameters::kRGBDProximityMaxPaths(), _proximityMaxPaths);
600  Parameters::parse(parameters, Parameters::kRGBDProximityPathMaxNeighbors(), _proximityMaxNeighbors);
601  Parameters::parse(parameters, Parameters::kRGBDProximityPathFilteringRadius(), _proximityFilteringRadius);
602  Parameters::parse(parameters, Parameters::kRGBDProximityPathRawPosesUsed(), _proximityRawPosesUsed);
603  if(Parameters::parse(parameters, Parameters::kRGBDProximityAngle(), _proximityAngle))
604  {
605  _proximityAngle *= M_PI/180.0f;
606  }
607  Parameters::parse(parameters, Parameters::kRGBDProximityOdomGuess(), _proximityOdomGuess);
608  Parameters::parse(parameters, Parameters::kRGBDProximityMergedScanCovFactor(), _proximityMergedScanCovFactor);
610 
611  bool optimizeFromGraphEndPrevious = _optimizeFromGraphEnd;
612  Parameters::parse(parameters, Parameters::kRGBDOptimizeFromGraphEnd(), _optimizeFromGraphEnd);
613  if(optimizeFromGraphEndPrevious != _optimizeFromGraphEnd && !_optimizedPoses.empty())
614  {
616  }
617  Parameters::parse(parameters, Parameters::kRGBDOptimizeMaxError(), _optimizationMaxError);
618  Parameters::parse(parameters, Parameters::kRtabmapStartNewMapOnLoopClosure(), _startNewMapOnLoopClosure);
619  Parameters::parse(parameters, Parameters::kRtabmapStartNewMapOnGoodSignature(), _startNewMapOnGoodSignature);
620  Parameters::parse(parameters, Parameters::kRGBDGoalReachedRadius(), _goalReachedRadius);
621  Parameters::parse(parameters, Parameters::kRGBDGoalsSavedInUserData(), _goalsSavedInUserData);
622  Parameters::parse(parameters, Parameters::kRGBDPlanStuckIterations(), _pathStuckIterations);
623  Parameters::parse(parameters, Parameters::kRGBDPlanLinearVelocity(), _pathLinearVelocity);
624  Parameters::parse(parameters, Parameters::kRGBDPlanAngularVelocity(), _pathAngularVelocity);
625  Parameters::parse(parameters, Parameters::kRGBDForceOdom3DoF(), _forceOdom3doF);
626  Parameters::parse(parameters, Parameters::kRGBDStartAtOrigin(), _restartAtOrigin);
627  Parameters::parse(parameters, Parameters::kRGBDLoopCovLimited(), _loopCovLimited);
628  Parameters::parse(parameters, Parameters::kRtabmapLoopGPS(), _loopGPS);
629  Parameters::parse(parameters, Parameters::kRGBDMaxOdomCacheSize(), _maxOdomCacheSize);
630  Parameters::parse(parameters, Parameters::kRGBDLocalizationSmoothing(), _localizationSmoothing);
631  double localizationPriorError = Parameters::defaultRGBDLocalizationPriorError();
632  Parameters::parse(parameters, Parameters::kRGBDLocalizationPriorError(), localizationPriorError);
633  UASSERT(localizationPriorError>0.0);
634  _localizationPriorInf = 1.0/(localizationPriorError*localizationPriorError);
635  Parameters::parse(parameters, Parameters::kRGBDProximityGlobalScanMap(), _createGlobalScanMap);
636 
637  Parameters::parse(parameters, Parameters::kMarkerPriorsVarianceLinear(), _markerPriorsLinearVariance);
639  Parameters::parse(parameters, Parameters::kMarkerPriorsVarianceAngular(), _markerPriorsAngularVariance);
641  std::string markerPriorsStr;
642  if(Parameters::parse(parameters, Parameters::kMarkerPriors(), markerPriorsStr))
643  {
644  _markerPriors.clear();
645  std::list<std::string> strList = uSplit(markerPriorsStr, '|');
646  for(std::list<std::string>::iterator iter=strList.begin(); iter!=strList.end(); ++iter)
647  {
648  std::string markerStr = *iter;
649  while(!markerStr.empty() && !uIsDigit(markerStr[0]))
650  {
651  markerStr.erase(markerStr.begin());
652  }
653  if(!markerStr.empty())
654  {
655  std::string idStr = uSplitNumChar(markerStr).front();
656  int id = uStr2Int(idStr);
657  Transform prior = Transform::fromString(markerStr.substr(idStr.size()));
658  if(!prior.isNull() && id>0)
659  {
660  _markerPriors.insert(std::make_pair(-id, prior));
661  UDEBUG("Added landmark prior %d: %s", id, prior.prettyPrint().c_str());
662  }
663  else
664  {
665  UERROR("Failed to parse element \"%s\" in parameter %s", markerStr.c_str(), Parameters::kMarkerPriors().c_str());
666  }
667  }
668  else if(!iter->empty())
669  {
670  UERROR("Failed to parse parameter %s, value=\"%s\"", Parameters::kMarkerPriors().c_str(), iter->c_str());
671  }
672  }
673  }
674 
675  UASSERT(_rgbdLinearUpdate >= 0.0f);
680 
681  // By default, we create our strategies if they are not already created.
682  // If they already exists, we check the parameters if a change is requested
683 
684  // Graph optimizer
685  Optimizer::Type optimizerType = Optimizer::kTypeUndef;
686  if((iter=parameters.find(Parameters::kOptimizerStrategy())) != parameters.end())
687  {
688  optimizerType = (Optimizer::Type)std::atoi((*iter).second.c_str());
689  }
690  if(optimizerType!=Optimizer::kTypeUndef)
691  {
692  UDEBUG("new detector strategy %d", int(optimizerType));
693  if(_graphOptimizer)
694  {
695  delete _graphOptimizer;
696  _graphOptimizer = 0;
697  }
698 
700  }
701  else if(_graphOptimizer)
702  {
703  _graphOptimizer->parseParameters(parameters);
704  }
705  else
706  {
707  optimizerType = (Optimizer::Type)Parameters::defaultOptimizerStrategy();
708  _graphOptimizer = Optimizer::create(optimizerType, parameters);
709  }
710 
712  {
714  _globalScanMapPoses.clear();
715  }
716 
717  if(_memory)
718  {
719  bool isMemIncremental = _memory->isIncremental();
720  if(Parameters::parse(parameters, Parameters::kMemIncrementalMemory(), isMemIncremental) &&
721  isMemIncremental != _memory->isIncremental())
722  {
723  // Mode has changed from Mapping to Localization, cleanup the local graph
725  {
726  // Force reducing graph, then remove filtered nodes from the optimized poses
727  std::map<int, int> reducedIds;
728  _memory->incrementMapId(&reducedIds);
729  for(std::map<int, int>::iterator iter=reducedIds.begin(); iter!=reducedIds.end(); ++iter)
730  {
731  _optimizedPoses.erase(iter->first);
732  }
733  }
734 
735  // In both cases, we save the latest optimized graph and latest localization pose
737 
738  // Mode changed from Localization to Mapping, clear local graph
739  if(!_memory->isIncremental()) {
740  _optimizedPoses.clear();
744  _localizationCovariance = cv::Mat();
746  }
747  }
748 
749  _memory->parseParameters(parameters);
751  {
752  UWARN("Map is now incremental, clearing global scan map...");
754  _globalScanMapPoses.clear();
755  }
756 
758  {
759  this->createGlobalScanMap();
760  }
761 
762  if(_memory->isIncremental())
763  {
764  _odomCachePoses.clear();
765  _odomCacheConstraints.clear();
766  }
767  }
768 
769  if(!_epipolarGeometry)
770  {
772  }
773  else
774  {
775  _epipolarGeometry->parseParameters(parameters);
776  }
777 
778  // Bayes filter, create one if not exists
779  if(!_bayesFilter)
780  {
782  }
783  else
784  {
785  _bayesFilter->parseParameters(parameters);
786  }
787 }
788 
790 {
791  int id = 0;
792  if(_memory)
793  {
794  id = _memory->getLastSignatureId();
795  }
796  return id;
797 }
798 
799 std::list<int> Rtabmap::getWM() const
800 {
801  std::list<int> mem;
802  if(_memory)
803  {
804  mem = uKeysList(_memory->getWorkingMem());
805  mem.remove(-1);// Ignore the virtual signature (if here)
806  }
807  return mem;
808 }
809 
811 {
812  if(_memory)
813  {
814  return (int)_memory->getWorkingMem().size()-1; // remove virtual place
815  }
816  return 0;
817 }
818 
819 std::map<int, int> Rtabmap::getWeights() const
820 {
821  std::map<int, int> weights;
822  if(_memory)
823  {
824  weights = _memory->getWeights();
825  weights.erase(-1);// Ignore the virtual signature (if here)
826  }
827  return weights;
828 }
829 
830 std::set<int> Rtabmap::getSTM() const
831 {
832  if(_memory)
833  {
834  return _memory->getStMem();
835  }
836  return std::set<int>();
837 }
838 
840 {
841  if(_memory)
842  {
843  return (int)_memory->getStMem().size();
844  }
845  return 0;
846 }
847 
849 {
850  if(_memory)
851  {
853  if(s)
854  {
855  return s->id();
856  }
857  }
858  return 0;
859 }
860 
861 bool Rtabmap::isInSTM(int locationId) const
862 {
863  if(_memory)
864  {
865  return _memory->isInSTM(locationId);
866  }
867  return false;
868 }
869 
871 {
872  if(_memory)
873  {
874  return _memory->isIDsGenerated();
875  }
876  return Parameters::defaultMemGenerateIds();
877 }
878 
880 {
881  return statistics_;
882 }
883 
884 Transform Rtabmap::getPose(int locationId) const
885 {
886  return uValue(_optimizedPoses, locationId, Transform());
887 }
888 
889 void Rtabmap::setInitialPose(const Transform & initialPose)
890 {
891  if(_memory)
892  {
893  if(!_memory->isIncremental())
894  {
895  _lastLocalizationPose = initialPose;
896  _localizationCovariance = cv::Mat();
898  _odomCachePoses.clear();
899  _odomCacheConstraints.clear();
902 
904  _optimizedPoses.empty())
905  {
906  cv::Mat covariance;
908  }
909  }
910  else
911  {
912  UWARN("Initial pose can only be set in localization mode (%s=false), ignoring it...", Parameters::kMemIncrementalMemory().c_str());
913  }
914  }
915 }
916 
918 {
919  int mapId = -1;
920  if(_memory)
921  {
922  _localizationCovariance = cv::Mat();
924  _odomCachePoses.clear();
925  _odomCacheConstraints.clear();
926  _distanceTravelled = 0.0f;
928 
929  if(!_memory->isIncremental())
930  {
932  if(_restartAtOrigin)
933  {
935  }
936  return mapId;
937  }
938  std::map<int, int> reducedIds;
939  mapId = _memory->incrementMapId(&reducedIds);
940  UINFO("New map triggered, new map = %d", mapId);
941  _optimizedPoses.clear();
942  _constraints.clear();
943 
944  if(_bayesFilter)
945  {
946  _bayesFilter->reset();
947  }
948 
949  //Verify if there are nodes that were merged through graph reduction
950  if(reducedIds.size() && _path.size())
951  {
952  for(unsigned int i=0; i<_path.size(); ++i)
953  {
954  std::map<int, int>::const_iterator iter = reducedIds.find(_path[i].first);
955  if(iter!= reducedIds.end())
956  {
957  // change path ID to loop closure ID
958  _path[i].first = iter->second;
959  }
960  }
961  }
962  }
963  return mapId;
964 }
965 
966 bool Rtabmap::labelLocation(int id, const std::string & label)
967 {
968  if(_memory)
969  {
970  if(id > 0)
971  {
972  return _memory->labelSignature(id, label);
973  }
975  {
977  }
979  {
980  std::map<int, Transform> nearestNodes = getNodesInRadius(_lastLocalizationPose, _localRadius, 1);
981  if(!nearestNodes.empty())
982  {
983  return _memory->labelSignature(nearestNodes.begin()->first, label);
984  }
985  else
986  {
987  UERROR("No nodes found inside %s=%fm of the current pose (%s). Cannot set label \"%s\"",
988  Parameters::kRGBDLocalRadius().c_str(),
989  _localRadius,
991  label.c_str());
992  }
993  }
994  else
995  {
996  UERROR("Last signature is null! Cannot set label \"%s\"", label.c_str());
997  }
998  }
999  return false;
1000 }
1001 
1002 bool Rtabmap::setUserData(int id, const cv::Mat & data)
1003 {
1004  if(_memory)
1005  {
1006  if(id > 0)
1007  {
1008  return _memory->setUserData(id, data);
1009  }
1010  else if(_memory->getLastWorkingSignature())
1011  {
1013  }
1014  else
1015  {
1016  UERROR("Last signature is null! Cannot set user data!");
1017  }
1018  }
1019  return false;
1020 }
1021 
1022 void Rtabmap::generateDOTGraph(const std::string & path, int id, int margin)
1023 {
1024  if(_memory)
1025  {
1026  _memory->joinTrashThread(); // make sure the trash is flushed
1027 
1028  if(id > 0)
1029  {
1030  std::map<int, int> ids = _memory->getNeighborsId(id, margin, -1, false);
1031 
1032  if(ids.size() > 0)
1033  {
1034  ids.insert(std::pair<int,int>(id, 0));
1035  std::set<int> idsSet;
1036  for(std::map<int, int>::iterator iter = ids.begin(); iter!=ids.end(); ++iter)
1037  {
1038  idsSet.insert(idsSet.end(), iter->first);
1039  }
1040  _memory->generateGraph(path, idsSet);
1041  }
1042  else
1043  {
1044  UERROR("No neighbors found for signature %d.", id);
1045  }
1046  }
1047  else
1048  {
1050  }
1051  }
1052 }
1053 
1054 void Rtabmap::exportPoses(const std::string & path, bool optimized, bool global, int format)
1055 {
1057  {
1058  std::map<int, Transform> poses;
1059  std::multimap<int, Link> constraints;
1060 
1061  if(optimized)
1062  {
1063  cv::Mat covariance;
1064  this->optimizeCurrentMap(_memory->getLastWorkingSignature()->id(), global, poses, covariance, &constraints);
1065  }
1066  else
1067  {
1068  std::map<int, int> ids = _memory->getNeighborsId(_memory->getLastWorkingSignature()->id(), 0, global?-1:0, true);
1069  _memory->getMetricConstraints(uKeysSet(ids), poses, constraints, global);
1070  }
1071 
1072  std::map<int, double> stamps;
1073  if(format == 1 || format == 10 || format == 11)
1074  {
1075  for(std::map<int, Transform>::iterator iter=poses.begin(); iter!=poses.end(); ++iter)
1076  {
1077  Transform o,g;
1078  int m, w;
1079  std::string l;
1080  double stamp = 0.0;
1081  std::vector<float> v;
1082  GPS gps;
1083  EnvSensors sensors;
1084  _memory->getNodeInfo(iter->first, o, m, w, l, stamp, g, v, gps, sensors, true);
1085  stamps.insert(std::make_pair(iter->first, stamp));
1086  }
1087  }
1088 
1089  graph::exportPoses(path, format, poses, constraints, stamps, _parameters);
1090  }
1091 }
1092 
1094 {
1095  UDEBUG("");
1096  _highestHypothesis = std::make_pair(0,0.0f);
1097  _loopClosureHypothesis = std::make_pair(0,0.0f);
1098  _lastProcessTime = 0.0;
1100  _optimizedPoses.clear();
1101  _constraints.clear();
1105  _localizationCovariance = cv::Mat();
1107  _odomCachePoses.clear();
1108  _odomCacheConstraints.clear();
1109  _distanceTravelled = 0.0f;
1113  _globalScanMapPoses.clear();
1114  _nodesToRepublish.clear();
1115  this->clearPath(0);
1116 
1117  if(_memory)
1118  {
1119  _memory->init(_databasePath, true, _parameters, true);
1121  {
1122  cv::Mat covariance;
1124  }
1125  if(_bayesFilter)
1126  {
1127  _bayesFilter->reset();
1128  }
1129  }
1130  else
1131  {
1132  UERROR("RTAB-Map is not initialized. No memory to reset...");
1133  }
1134 
1135  if(_graphOptimizer)
1136  {
1137  delete _graphOptimizer;
1139  }
1140 
1141  this->setupLogFiles(true);
1142 }
1143 
1145 {
1146 public:
1147  NearestPathKey(float l, int i, float d) :
1148  likelihood(l),
1149  id(i),
1150  distance(d){}
1151  bool operator<(const NearestPathKey & k) const
1152  {
1153  if(likelihood < k.likelihood)
1154  {
1155  return true;
1156  }
1157  else if(likelihood == k.likelihood)
1158  {
1159  if(distance > k.distance)
1160  {
1161  return true;
1162  }
1163  else if(distance == k.distance && id < k.id)
1164  {
1165  return true;
1166  }
1167  }
1168  return false;
1169  }
1170  float likelihood;
1171  int id;
1172  float distance;
1173 };
1174 
1175 //============================================================
1176 // MAIN LOOP
1177 //============================================================
1179  const cv::Mat & image,
1180  int id,
1181  const std::map<std::string, float> & externalStats)
1182 {
1183  return this->process(SensorData(image, id), Transform());
1184 }
1186  const SensorData & data,
1187  Transform odomPose,
1188  float odomLinearVariance,
1189  float odomAngularVariance,
1190  const std::vector<float> & odomVelocity,
1191  const std::map<std::string, float> & externalStats)
1192 {
1193  if(!odomPose.isNull())
1194  {
1195  UASSERT(odomLinearVariance>0.0f);
1196  UASSERT(odomAngularVariance>0.0f);
1197  }
1198  cv::Mat covariance = cv::Mat::eye(6,6,CV_64FC1);
1199  covariance.at<double>(0,0) = odomLinearVariance;
1200  covariance.at<double>(1,1) = odomLinearVariance;
1201  covariance.at<double>(2,2) = odomLinearVariance;
1202  covariance.at<double>(3,3) = odomAngularVariance;
1203  covariance.at<double>(4,4) = odomAngularVariance;
1204  covariance.at<double>(5,5) = odomAngularVariance;
1205  return process(data, odomPose, covariance, odomVelocity, externalStats);
1206 }
1208  const SensorData & data,
1209  Transform odomPose,
1210  const cv::Mat & odomCovariance,
1211  const std::vector<float> & odomVelocity,
1212  const std::map<std::string, float> & externalStats)
1213 {
1214  UDEBUG("");
1215 
1216  //============================================================
1217  // Initialization
1218  //============================================================
1219  UTimer timer;
1220  UTimer timerTotal;
1221  double timeMemoryUpdate = 0;
1222  double timeNeighborLinkRefining = 0;
1223  double timeProximityByTimeDetection = 0;
1224  double timeProximityBySpaceSearch = 0;
1225  double timeProximityBySpaceVisualDetection = 0;
1226  double timeProximityBySpaceDetection = 0;
1227  double timeCleaningNeighbors = 0;
1228  double timeReactivations = 0;
1229  double timeAddLoopClosureLink = 0;
1230  double timeMapOptimization = 0;
1231  double timeRetrievalDbAccess = 0;
1232  double timeLikelihoodCalculation = 0;
1233  double timePosteriorCalculation = 0;
1234  double timeHypothesesCreation = 0;
1235  double timeHypothesesValidation = 0;
1236  double timeRealTimeLimitReachedProcess = 0;
1237  double timeMemoryCleanup = 0;
1238  double timeEmptyingTrash = 0;
1239  double timeFinalizingStatistics = 0;
1240  double timeJoiningTrash = 0;
1241  double timeStatsCreation = 0;
1242 
1243  float hypothesisRatio = 0.0f; // Only used for statistics
1244  bool rejectedLoopClosure = false;
1245 
1246  std::map<int, float> rawLikelihood;
1247  std::map<int, float> adjustedLikelihood;
1248  std::map<int, float> likelihood;
1249  std::map<int, int> weights;
1250  std::map<int, float> posterior;
1251  std::list<std::pair<int, float> > reactivateHypotheses;
1252 
1253  std::map<int, int> childCount;
1254  std::set<int> signaturesRetrieved;
1255  int proximityDetectionsInTimeFound = 0;
1256 
1257  const Signature * signature = 0;
1258  const Signature * sLoop = 0;
1259 
1260  _loopClosureHypothesis = std::make_pair(0,0.0f);
1261  std::pair<int, float> lastHighestHypothesis = _highestHypothesis;
1262  _highestHypothesis = std::make_pair(0,0.0f);
1263 
1264  std::set<int> immunizedLocations;
1265 
1266  statistics_ = Statistics(); // reset
1267  for(std::map<std::string, float>::const_iterator iter=externalStats.begin(); iter!=externalStats.end(); ++iter)
1268  {
1269  statistics_.addStatistic(iter->first, iter->second);
1270  }
1271 
1272  //============================================================
1273  // Wait for an image...
1274  //============================================================
1275  ULOGGER_INFO("getting data...");
1276 
1277  timer.start();
1278  timerTotal.start();
1279 
1280  UASSERT_MSG(_memory, "RTAB-Map is not initialized!");
1281  UASSERT_MSG(_bayesFilter, "RTAB-Map is not initialized!");
1282  UASSERT_MSG(_graphOptimizer, "RTAB-Map is not initialized!");
1283 
1284  //============================================================
1285  // If RGBD SLAM is enabled, a pose must be set.
1286  //============================================================
1287  bool fakeOdom = false;
1288  if(_rgbdSlamMode)
1289  {
1290  if(!odomPose.isNull())
1291  {
1292  // If we are doing 2D mapping, make sure the pose is 3DoF so that landmark logic works.
1293  if(_forceOdom3doF && _graphOptimizer->isSlam2d() && !odomPose.is3DoF())
1294  {
1295  odomPose = odomPose.to3DoF();
1296  }
1297 
1298  // this will make sure that all inverse operations will work!
1299  if(!odomPose.isInvertible())
1300  {
1301  UWARN("Input odometry is not invertible! pose = %s\n"
1302  "[%f %f %f %f;\n"
1303  " %f %f %f %f;\n"
1304  " %f %f %f %f;\n"
1305  " 0 0 0 1]\n"
1306  "Trying to normalize rotation to see if it makes it invertible...",
1307  odomPose.prettyPrint().c_str(),
1308  odomPose.r11(), odomPose.r12(), odomPose.r13(), odomPose.o14(),
1309  odomPose.r21(), odomPose.r22(), odomPose.r23(), odomPose.o24(),
1310  odomPose.r31(), odomPose.r32(), odomPose.r33(), odomPose.o34());
1311  odomPose.normalizeRotation();
1312  UASSERT_MSG(odomPose.isInvertible(), uFormat("Odometry pose is not invertible!\n"
1313  "[%f %f %f %f;\n"
1314  " %f %f %f %f;\n"
1315  " %f %f %f %f;\n"
1316  " 0 0 0 1]", odomPose.prettyPrint().c_str(),
1317  odomPose.r11(), odomPose.r12(), odomPose.r13(), odomPose.o14(),
1318  odomPose.r21(), odomPose.r22(), odomPose.r23(), odomPose.o24(),
1319  odomPose.r31(), odomPose.r32(), odomPose.r33(), odomPose.o34()).c_str());
1320  UWARN("Normalizing rotation succeeded! fixed pose = %s\n"
1321  "[%f %f %f %f;\n"
1322  " %f %f %f %f;\n"
1323  " %f %f %f %f;\n"
1324  " 0 0 0 1]\n"
1325  "If the resulting rotation is very different from original one, try to fix the odometry or TF.",
1326  odomPose.prettyPrint().c_str(),
1327  odomPose.r11(), odomPose.r12(), odomPose.r13(), odomPose.o14(),
1328  odomPose.r21(), odomPose.r22(), odomPose.r23(), odomPose.o24(),
1329  odomPose.r31(), odomPose.r32(), odomPose.r33(), odomPose.o34());
1330  }
1331  }
1332 
1333  UDEBUG("incremental=%d odomPose=%s optimizedPoses=%d mapCorrection=%s lastLocalizationPose=%s lastLocalizationNodeId=%d",
1334  _memory->isIncremental()?1:0,
1335  odomPose.prettyPrint().c_str(),
1336  (int)_optimizedPoses.size(),
1337  _mapCorrection.prettyPrint().c_str(),
1340 
1341  if(!_memory->isIncremental() &&
1342  !odomPose.isNull() &&
1343  _optimizedPoses.size() &&
1347  {
1348  // Localization mode
1350  {
1351  //set map->odom so that odom is moved back to last saved localization
1352  if(_graphOptimizer->isSlam2d())
1353  {
1355  }
1356  else if((!data.imu().empty() || _memory->isOdomGravityUsed()) && _graphOptimizer->gravitySigma()>0.0f)
1357  {
1359  }
1360  else
1361  {
1363  }
1364  std::map<int, Transform> nodesOnly(_optimizedPoses.lower_bound(1), _optimizedPoses.end());
1366  UWARN("Update map correction based on last localization saved in database! correction = %s, nearest id = %d of last pose = %s, odom = %s",
1367  _mapCorrection.prettyPrint().c_str(),
1370  odomPose.prettyPrint().c_str());
1371  }
1372  else
1373  {
1374  //move optimized poses accordingly to last saved localization
1375  Transform mapCorrectionInv;
1376  if(_graphOptimizer->isSlam2d())
1377  {
1378  mapCorrectionInv = odomPose.to3DoF() * _lastLocalizationPose.to3DoF().inverse();
1379  }
1380  else if((!data.imu().empty() || _memory->isOdomGravityUsed()) && _graphOptimizer->gravitySigma()>0.0f)
1381  {
1382  mapCorrectionInv = odomPose.to4DoF() * _lastLocalizationPose.to4DoF().inverse();
1383  }
1384  else
1385  {
1386  mapCorrectionInv = odomPose * _lastLocalizationPose.inverse();
1387  }
1388  for(std::map<int, Transform>::iterator iter=_optimizedPoses.begin(); iter!=_optimizedPoses.end(); ++iter)
1389  {
1390  iter->second = mapCorrectionInv * iter->second;
1391  }
1392 
1393  std::map<int, Transform> nodesOnly(_optimizedPoses.lower_bound(1), _optimizedPoses.end());
1395  UWARN("Transformed map accordingly to last localization pose saved in database (%s=true)! nearest id = %d of last pose = %s",
1396  Parameters::kRGBDOptimizeFromGraphEnd().c_str(),
1399  }
1400  }
1401 
1402  if(odomPose.isNull())
1403  {
1404  if(_memory->isIncremental())
1405  {
1406  UERROR("RGB-D SLAM mode is enabled, memory is incremental but no odometry is provided. "
1407  "Image %d is ignored!", data.id());
1408  return false;
1409  }
1410  else // fake localization
1411  {
1413  {
1416  }
1418  {
1420  }
1421  fakeOdom = true;
1423  UDEBUG("Map correction = %s", _mapCorrection.prettyPrint().c_str());
1424  UDEBUG("Last localization pose: %s", _lastLocalizationPose.prettyPrint().c_str());
1425  UDEBUG("Fake odom: %s", odomPose.prettyPrint().c_str());
1426  }
1427  }
1428  else if(_memory->isIncremental()) // only in mapping mode
1429  {
1430  // Detect if the odometry is reset. If yes, trigger a new map.
1432  {
1433  const Transform & lastPose = _memory->getLastWorkingSignature()->getPose(); // use raw odometry
1434 
1435  // look for identity
1436  if(!lastPose.isIdentity() && odomPose.isIdentity())
1437  {
1438  int mapId = triggerNewMap();
1439  UWARN("Odometry is reset (identity pose detected). Increment map id to %d!", mapId);
1440  }
1441  else if(_newMapOdomChangeDistance > 0.0)
1442  {
1443  // look for large change
1444  Transform lastPoseToNewPose = lastPose.inverse() * odomPose;
1445  float x,y,z, roll,pitch,yaw;
1446  lastPoseToNewPose.getTranslationAndEulerAngles(x,y,z, roll,pitch,yaw);
1448  {
1449  int mapId = triggerNewMap();
1450  UWARN("Odometry is reset (large odometry change detected > %f). A new map (%d) is created! Last pose = %s, new pose = %s",
1452  mapId,
1453  lastPose.prettyPrint().c_str(),
1454  odomPose.prettyPrint().c_str());
1455  }
1456  }
1457  }
1458  }
1459  }
1460 
1461  //============================================================
1462  // Memory Update : Location creation + Add to STM + Weight Update (Rehearsal)
1463  //============================================================
1464  ULOGGER_INFO("Updating memory...");
1465  if(_rgbdSlamMode)
1466  {
1467  if(!_memory->update(data, odomPose, odomCovariance, odomVelocity, &statistics_))
1468  {
1469  return false;
1470  }
1471  }
1472  else
1473  {
1474  if(!_memory->update(data, Transform(), cv::Mat(), std::vector<float>(), &statistics_))
1475  {
1476  return false;
1477  }
1478  }
1479 
1480  signature = _memory->getLastWorkingSignature();
1481  _currentSessionHasGPS = _currentSessionHasGPS || signature->sensorData().gps().stamp() > 0.0;
1482  if(!signature)
1483  {
1484  UFATAL("Not supposed to be here...last signature is null?!?");
1485  }
1486 
1487  ULOGGER_INFO("Processing signature %d w=%d map=%d", signature->id(), signature->getWeight(), signature->mapId());
1488  timeMemoryUpdate = timer.ticks();
1489  ULOGGER_INFO("timeMemoryUpdate=%fs", timeMemoryUpdate);
1490 
1491  //============================================================
1492  // Metric
1493  //============================================================
1494  bool smallDisplacement = false;
1495  bool tooFastMovement = false;
1496  std::list<int> signaturesRemoved;
1497  bool neighborLinkRefined = false;
1498  bool addedNewLandmark = false;
1499  float distanceToClosestNodeInTheGraph = 0;
1500  float angleToClosestNodeInTheGraph = 0;
1501  if(_rgbdSlamMode)
1502  {
1503  double linVar = odomCovariance.empty()?1.0f:uMax3(odomCovariance.at<double>(0,0), odomCovariance.at<double>(1,1)>=9999?0:odomCovariance.at<double>(1,1), odomCovariance.at<double>(2,2)>=9999?0:odomCovariance.at<double>(2,2));
1504  double angVar = odomCovariance.empty()?1.0f:uMax3(odomCovariance.at<double>(3,3)>=9999?0:odomCovariance.at<double>(3,3), odomCovariance.at<double>(4,4)>=9999?0:odomCovariance.at<double>(4,4), odomCovariance.at<double>(5,5));
1505  statistics_.addStatistic(Statistics::kMemoryOdometry_variance_lin(), (float)linVar);
1506  statistics_.addStatistic(Statistics::kMemoryOdometry_variance_ang(), (float)angVar);
1507 
1508  //Verify if there was a rehearsal
1509  int rehearsedId = (int)uValue(statistics_.data(), Statistics::kMemoryRehearsal_merged(), 0.0f);
1510  if(rehearsedId > 0)
1511  {
1512  _optimizedPoses.erase(rehearsedId);
1513  }
1514  else
1515  {
1516  if(_rgbdLinearUpdate > 0.0f || _rgbdAngularUpdate > 0.0f)
1517  {
1518  //============================================================
1519  // Minimum displacement required to add to Memory
1520  //============================================================
1521  Transform t;
1522 
1523  if(_memory->isIncremental())
1524  {
1525  const std::multimap<int, Link> & links = signature->getLinks();
1526  if(links.size() && links.begin()->second.type() == Link::kNeighbor)
1527  {
1528  const Signature * s = _memory->getSignature(links.begin()->second.to());
1529  UASSERT(s!=0);
1530  // don't filter if the new node is not intermediate but previous one is
1531  if(signature->getWeight() < 0 || s->getWeight() >= 0)
1532  {
1533  t = links.begin()->second.transform();
1534  }
1535  }
1536  }
1537  else if(!_odomCachePoses.empty())
1538  {
1539  t = _odomCachePoses.rbegin()->second.inverse() * signature->getPose();
1540  }
1541  if(!t.isNull())
1542  {
1543  float x,y,z, roll,pitch,yaw;
1544  t.getTranslationAndEulerAngles(x,y,z, roll,pitch,yaw);
1545  bool isMoving = fabs(x) > _rgbdLinearUpdate ||
1546  fabs(y) > _rgbdLinearUpdate ||
1547  fabs(z) > _rgbdLinearUpdate ||
1548  (_rgbdAngularUpdate>0.0f && (
1552  if(!isMoving)
1553  {
1554  // This will disable global loop closure detection, only retrieval will be done.
1555  // The location will also be deleted at the end.
1556  smallDisplacement = true;
1557  UDEBUG("smallDisplacement: %f %f %f %f %f %f", x,y,z, roll,pitch,yaw);
1558  }
1559  }
1560  }
1561  if(odomVelocity.size() == 6)
1562  {
1563  // This will disable global loop closure detection, only retrieval will be done.
1564  // The location will also be deleted at the end.
1565  tooFastMovement =
1566  (_rgbdLinearSpeedUpdate>0.0f && uMax3(fabs(odomVelocity[0]), fabs(odomVelocity[1]), fabs(odomVelocity[2])) > _rgbdLinearSpeedUpdate) ||
1567  (_rgbdAngularSpeedUpdate>0.0f && uMax3(fabs(odomVelocity[3]), fabs(odomVelocity[4]), fabs(odomVelocity[5])) > _rgbdAngularSpeedUpdate);
1568  }
1569  }
1570 
1571  // Update optimizedPoses with the newly added node
1572  Transform newPose;
1573  bool intermediateNodeRefining = false;
1574  if(_neighborLinkRefining &&
1575  signature->getLinks().size() &&
1576  signature->getLinks().begin()->second.type() == Link::kNeighbor &&
1577  _memory->isIncremental() && // ignore pose matching in localization mode
1578  rehearsedId == 0 && // don't do it if rehearsal happened
1579  !tooFastMovement) // ignore if too fast movement has been detected
1580  {
1581  int oldId = signature->getLinks().begin()->first;
1582  const Signature * oldS = _memory->getSignature(oldId);
1583  UASSERT(oldS != 0);
1584 
1585  if(signature->getWeight() >= 0 && oldS->getWeight()>=0) // ignore intermediate nodes
1586  {
1587  Transform guess = signature->getLinks().begin()->second.transform().inverse();
1588 
1589  if(smallDisplacement)
1590  {
1591  if(signature->getLinks().begin()->second.transVariance() == 1)
1592  {
1593  // set small variance
1594  UDEBUG("Set small variance. The robot is not moving.");
1595  _memory->updateLink(Link(oldId, signature->id(), signature->getLinks().begin()->second.type(), guess, cv::Mat::eye(6,6,CV_64FC1)*1000));
1596  }
1597  }
1598  else
1599  {
1600  //============================================================
1601  // Refine neighbor links
1602  //============================================================
1603  UINFO("Odometry refining: guess = %s", guess.prettyPrint().c_str());
1605  Transform t = _memory->computeTransform(oldId, signature->id(), guess, &info);
1606  if(!t.isNull())
1607  {
1608  UINFO("Odometry refining: update neighbor link (%d->%d, variance:lin=%f, ang=%f) from %s to %s",
1609  oldId,
1610  signature->id(),
1611  info.covariance.at<double>(0,0),
1612  info.covariance.at<double>(5,5),
1613  guess.prettyPrint().c_str(),
1614  t.prettyPrint().c_str());
1615  UASSERT(info.covariance.at<double>(0,0) > 0.0 && info.covariance.at<double>(5,5) > 0.0);
1616  _memory->updateLink(Link(oldId, signature->id(), signature->getLinks().begin()->second.type(), t, info.covariance.inv()));
1617 
1619  {
1620  // update all previous nodes
1621  // Normally _mapCorrection should be identity, but if _optimizeFromGraphEnd
1622  // parameters just changed state, we should put back all poses without map correction.
1623  Transform u = guess * t.inverse();
1624  std::map<int, Transform>::iterator jter = _optimizedPoses.find(oldId);
1625  UASSERT(jter!=_optimizedPoses.end());
1626  Transform up = jter->second * u * jter->second.inverse();
1627  Transform mapCorrectionInv = _mapCorrection.inverse();
1628  for(std::map<int, Transform>::iterator iter=_optimizedPoses.begin(); iter!=_optimizedPoses.end(); ++iter)
1629  {
1630  iter->second = mapCorrectionInv * up * iter->second;
1631  }
1632  }
1633  }
1634  else
1635  {
1636  UINFO("Odometry refining rejected: %s", info.rejectedMsg.c_str());
1637  if(!info.covariance.empty() && info.covariance.at<double>(0,0) > 0.0 && info.covariance.at<double>(0,0) != 1.0 && info.covariance.at<double>(5,5) > 0.0 && info.covariance.at<double>(5,5) != 1.0)
1638  {
1640  {
1641  std::cout << info.covariance << std::endl;
1642  }
1643  _memory->updateLink(Link(oldId, signature->id(), signature->getLinks().begin()->second.type(), guess, (info.covariance*100.0).inv()));
1644  }
1645  }
1646  neighborLinkRefined = !t.isNull();
1647  statistics_.addStatistic(Statistics::kNeighborLinkRefiningAccepted(),neighborLinkRefined?1.0f:0);
1648  statistics_.addStatistic(Statistics::kNeighborLinkRefiningInliers(), info.inliers);
1649  statistics_.addStatistic(Statistics::kNeighborLinkRefiningICP_inliers_ratio(), info.icpInliersRatio);
1650  statistics_.addStatistic(Statistics::kNeighborLinkRefiningICP_rotation(), info.icpRotation);
1651  statistics_.addStatistic(Statistics::kNeighborLinkRefiningICP_translation(), info.icpTranslation);
1652  statistics_.addStatistic(Statistics::kNeighborLinkRefiningICP_complexity(), info.icpStructuralComplexity);
1653  statistics_.addStatistic(Statistics::kNeighborLinkRefiningPts(), signature->sensorData().laserScanRaw().size());
1654  }
1655  timeNeighborLinkRefining = timer.ticks();
1656  ULOGGER_INFO("timeOdometryRefining=%fs", timeNeighborLinkRefining);
1657 
1658  UASSERT(oldS->hasLink(signature->id()));
1660 
1661  statistics_.addStatistic(Statistics::kNeighborLinkRefiningVariance(), oldS->getLinks().find(signature->id())->second.transVariance());
1662 
1663  newPose = _optimizedPoses.at(oldId) * oldS->getLinks().find(signature->id())->second.transform();
1664  _mapCorrection = newPose * signature->getPose().inverse();
1666  {
1667  UERROR("Map correction should be identity when optimizing from the last node. T=%s NewPose=%s OldPose=%s",
1668  _mapCorrection.prettyPrint().c_str(),
1669  newPose.prettyPrint().c_str(),
1670  signature->getPose().prettyPrint().c_str());
1671  }
1672  }
1673  else
1674  {
1675  newPose = _mapCorrection * signature->getPose();
1676  intermediateNodeRefining = true;
1677  }
1678  }
1679  else
1680  {
1681  newPose = _mapCorrection * signature->getPose();
1682  }
1683 
1684  // Get statistics about the closest node in the graph
1685  if(!_memory->isIncremental())
1686  {
1687  int closestNode = 0;
1688  float sqrdDistance = 0.0f;
1689  if(_optimizedPoses.begin()->first < 0)
1690  {
1691  std::map<int, Transform> poses(_optimizedPoses.lower_bound(1), _optimizedPoses.end());
1692  closestNode = graph::findNearestNode(poses, newPose, &sqrdDistance);
1693  }
1694  else
1695  {
1696  closestNode = graph::findNearestNode(_optimizedPoses, newPose, &sqrdDistance);
1697  }
1698  if(closestNode>0 && sqrdDistance>0.0f)
1699  {
1700  distanceToClosestNodeInTheGraph = sqrt(sqrdDistance);
1701  UDEBUG("Last localization pose = %s, closest node=%d (%f m)", newPose.prettyPrint().c_str(), closestNode, distanceToClosestNodeInTheGraph);
1702  angleToClosestNodeInTheGraph = (newPose.inverse() * _optimizedPoses.at(closestNode)).getAngle();
1703  }
1704  }
1705 
1706  UDEBUG("Added pose %s (odom=%s)", newPose.prettyPrint().c_str(), signature->getPose().prettyPrint().c_str());
1707  // Update Poses and Constraints
1708  _optimizedPoses.insert(std::make_pair(signature->id(), newPose));
1709  if(_memory->isIncremental() && signature->getWeight() >= 0)
1710  {
1711  for(std::map<int, Link>::const_iterator iter = signature->getLandmarks().begin(); iter!=signature->getLandmarks().end(); ++iter)
1712  {
1713  if(_optimizedPoses.find(iter->first) == _optimizedPoses.end())
1714  {
1715  _optimizedPoses.insert(std::make_pair(iter->first, newPose*iter->second.transform()));
1716  UDEBUG("Added landmark %d : %s", iter->first, (newPose*iter->second.transform()).prettyPrint().c_str());
1717  addedNewLandmark = true;
1718  }
1719  _constraints.insert(std::make_pair(iter->first, iter->second.inverse()));
1720  }
1721  }
1722 
1723  float distanceTravelledOld = _distanceTravelled;
1724 
1725  // only in mapping mode we add a neighbor link
1726  if(signature->getLinks().size() &&
1727  signature->getLinks().begin()->second.type() == Link::kNeighbor)
1728  {
1729  // link should be old to new
1730  UASSERT_MSG(signature->id() > signature->getLinks().begin()->second.to(),
1731  "Only forward links should be added.");
1732 
1733  Link tmp = signature->getLinks().begin()->second.inverse();
1734 
1735  if(!smallDisplacement)
1736  {
1738  }
1739 
1740  // if the previous node is an intermediate node, remove it from the local graph
1741  if(_constraints.size() &&
1742  _constraints.rbegin()->second.to() == signature->getLinks().begin()->second.to())
1743  {
1744  const Signature * s = _memory->getSignature(signature->getLinks().begin()->second.to());
1745  UASSERT(s!=0);
1746  if(s->getWeight() == -1)
1747  {
1748  tmp = _constraints.rbegin()->second.merge(tmp, tmp.type());
1749  _optimizedPoses.erase(s->id());
1750  _constraints.erase(--_constraints.end());
1751  }
1752  }
1753 
1754  _constraints.insert(std::make_pair(tmp.from(), tmp));
1755  }
1756  // Localization mode stuff
1757  if( signature->getWeight() >= 0 &&
1758  !smallDisplacement &&
1759  odomCovariance.cols == 6 &&
1760  odomCovariance.rows == 6 &&
1761  odomCovariance.type() == CV_64FC1 &&
1762  odomCovariance.at<double>(0,0) < 1)
1763  {
1764  if( _memory->isIncremental() && _localizationCovariance.empty())
1765  {
1766  _localizationCovariance = cv::Mat::zeros(6,6,CV_64FC1);
1767  }
1768  if(_localizationCovariance.total() == 36)
1769  {
1770 #ifdef RTABMAP_MRPT
1771  // Transform odometry covariance (which in base frame) into global frame
1772  // "odometry error propagation law"
1774  mrpt::poses::CPose3D pose = mrpt::poses::CPose3D::FromQuaternion(mrpt::math::CQuaternionDouble(rotation.w(), rotation.x(), rotation.y(), rotation.z()));
1775  mrpt::math::CMatrixDouble66 gaussian;
1776  gaussian.loadFromRawPointer((const double*)odomCovariance.data);
1777  mrpt::poses::CPose3DPDFGaussian gaussianTransformed(mrpt::poses::CPose3D(), gaussian);
1778  gaussianTransformed.changeCoordinatesReference(pose);
1779  _localizationCovariance += cv::Mat(6,6,CV_64FC1, gaussianTransformed.cov.data());
1780 #else
1781  // Assuming diagonal uniform covariance matrix!
1782  // If variance is different for each axis,
1783  // build rtabmap with MRPT to use approach above.
1784  _localizationCovariance += odomCovariance;
1785 #endif
1786  }
1787  }
1788  _lastLocalizationPose = newPose; // keep in cache the latest corrected pose
1789  if(!_memory->isIncremental() && signature->getWeight() >= 0)
1790  {
1791  UDEBUG("Update odometry localization cache (size=%d/%d)", (int)_odomCachePoses.size(), _maxOdomCacheSize);
1792  if(!_odomCachePoses.empty())
1793  {
1794  float odomDistance = (_odomCachePoses.rbegin()->second.inverse() * signature->getPose()).getNorm();
1795  if(!smallDisplacement)
1796  {
1797  _distanceTravelled += odomDistance;
1798  }
1799 
1800  while(!_odomCachePoses.empty() && (int)_odomCachePoses.size() > _maxOdomCacheSize)
1801  {
1802  _odomCacheConstraints.erase(_odomCachePoses.begin()->first);
1803  _odomCachePoses.erase(_odomCachePoses.begin());
1804  }
1805  if(!_odomCachePoses.empty())
1806  {
1807  Link odomLink(_odomCachePoses.rbegin()->first,
1808  signature->id(),
1810  _odomCachePoses.rbegin()->second.inverse() * signature->getPose(),
1811  odomCovariance.inv());
1812  _odomCacheConstraints.insert(std::make_pair(_odomCachePoses.rbegin()->first, odomLink));
1813  UDEBUG("Added odom cov = %f %f", odomLink.transVariance(), odomLink.rotVariance());
1814  }
1815  }
1816 
1817  _odomCachePoses.insert(std::make_pair(signature->id(), signature->getPose()));
1818  }
1820 
1821  //============================================================
1822  // Reduced graph
1823  //============================================================
1824  //Verify if there are nodes that were merged through graph reduction
1825  if(statistics_.reducedIds().size())
1826  {
1827  for(unsigned int i=0; i<_path.size(); ++i)
1828  {
1829  std::map<int, int>::const_iterator iter = statistics_.reducedIds().find(_path[i].first);
1830  if(iter!= statistics_.reducedIds().end())
1831  {
1832  // change path ID to loop closure ID
1833  _path[i].first = iter->second;
1834  }
1835  }
1836 
1837  for(std::map<int, int>::const_iterator iter=statistics_.reducedIds().begin();
1838  iter!=statistics_.reducedIds().end();
1839  ++iter)
1840  {
1841  int erased = (int)_optimizedPoses.erase(iter->first);
1842  if(erased)
1843  {
1844  for(std::multimap<int, Link>::iterator jter = _constraints.begin(); jter!=_constraints.end();)
1845  {
1846  if(jter->second.from() == iter->first || jter->second.to() == iter->first)
1847  {
1848  _constraints.erase(jter++);
1849  }
1850  else
1851  {
1852  ++jter;
1853  }
1854  }
1855  }
1856  }
1857  }
1858 
1859  //============================================================
1860  // Local loop closure in TIME
1861  //============================================================
1862  if((_proximityByTime || intermediateNodeRefining) &&
1863  rehearsedId == 0 && // don't do it if rehearsal happened
1864  _memory->isIncremental() && // don't do it in localization mode
1865  signature->getWeight()>=0)
1866  {
1867  const std::set<int> & stm = _memory->getStMem();
1868  for(std::set<int>::const_reverse_iterator iter = stm.rbegin(); iter!=stm.rend(); ++iter)
1869  {
1870  if(*iter != signature->id() &&
1871  signature->getLinks().find(*iter) == signature->getLinks().end() &&
1872  _memory->getSignature(*iter)->mapId() == signature->mapId() &&
1873  _memory->getSignature(*iter)->getWeight()>=0)
1874  {
1875  std::string rejectedMsg;
1876  UDEBUG("Check local transform between %d and %d", signature->id(), *iter);
1878  Transform guess;
1879  if(_optimizedPoses.find(*iter) != _optimizedPoses.end())
1880  {
1881  guess = _optimizedPoses.at(*iter).inverse() * newPose;
1882  }
1883 
1884  // For proximity by time, correspondences should be already enough precise, so don't recompute them
1885  Transform transform = _memory->computeTransform(*iter, signature->id(), guess, &info, true);
1886 
1887  if(!transform.isNull())
1888  {
1889  transform = transform.inverse();
1890  UDEBUG("Add local loop closure in TIME (%d->%d) %s",
1891  signature->id(),
1892  *iter,
1893  transform.prettyPrint().c_str());
1894  // Add a loop constraint
1895  UASSERT(info.covariance.at<double>(0,0) > 0.0 && info.covariance.at<double>(5,5) > 0.0);
1896  if(_memory->addLink(Link(signature->id(), *iter, Link::kLocalTimeClosure, transform, getInformation(info.covariance))))
1897  {
1898  ++proximityDetectionsInTimeFound;
1899  UINFO("Local loop closure found between %d and %d with t=%s",
1900  *iter, signature->id(), transform.prettyPrint().c_str());
1901  }
1902  else
1903  {
1904  UWARN("Cannot add local loop closure between %d and %d ?!?",
1905  *iter, signature->id());
1906  }
1907  }
1908  else
1909  {
1910  UINFO("Local loop closure (time) between %d and %d rejected: %s",
1911  *iter, signature->id(), rejectedMsg.c_str());
1912  }
1913 
1914  if(!_proximityByTime && intermediateNodeRefining)
1915  {
1916  // Do it only with the latest non-intermediate node
1917  break;
1918  }
1919  }
1920  }
1921  }
1922  }
1923 
1924  timeProximityByTimeDetection = timer.ticks();
1925  UINFO("timeProximityByTimeDetection=%fs", timeProximityByTimeDetection);
1926 
1927  //============================================================
1928  // Bayes filter update
1929  //============================================================
1930  bool localizationOnPreviousUpdate = false;
1931  if(_memory->isIncremental())
1932  {
1933  localizationOnPreviousUpdate =
1934  signature->getLinks().size() &&
1935  signature->getLinks().begin()->first!=signature->id() &&
1936  _memory->getLoopClosureLinks(signature->getLinks().begin()->first, false).size() != 0;
1937  }
1938  else
1939  {
1940  // localization mode
1941 
1942  // Count how many localization links are in the constraints
1943  int localizationLinks = 0;
1944  int previousIdWithLocalizationLink = 0;
1945  for(std::multimap<int, Link>::iterator iter=_odomCacheConstraints.begin();
1946  iter!=_odomCacheConstraints.end(); ++iter)
1947  {
1948  if(previousIdWithLocalizationLink == iter->first)
1949  {
1950  // ignore links with node already counted
1951  continue;
1952  }
1953  if(iter->second.type() == Link::kGlobalClosure ||
1954  iter->second.type() == Link::kLocalSpaceClosure ||
1955  iter->second.type() == Link::kLocalTimeClosure ||
1956  iter->second.type() == Link::kUserClosure ||
1957  iter->second.type() == Link::kNeighborMerged ||
1958  iter->second.type() == Link::kLandmark)
1959  {
1960  ++localizationLinks;
1961  previousIdWithLocalizationLink = iter->first;
1962  }
1963  }
1964 
1965  localizationOnPreviousUpdate = localizationLinks > 1; // need two links in case we have delayed localization
1966  }
1967 
1968  // Not a bad signature, not an intermediate node, not a small displacement unless the previous signature didn't have a loop closure, not too fast movement
1969  if(!signature->isBadSignature() && signature->getWeight()>=0 && (!smallDisplacement || !localizationOnPreviousUpdate) && !tooFastMovement)
1970  {
1971  // If the working memory is empty, don't do the detection. It happens when it
1972  // is the first time the detector is started (there needs some images to
1973  // fill the short-time memory before a signature is added to the working memory).
1974  if(_memory->getWorkingMem().size())
1975  {
1976  //============================================================
1977  // Likelihood computation
1978  // Get the likelihood of the new signature
1979  // with all images contained in the working memory + reactivated.
1980  //============================================================
1981  ULOGGER_INFO("computing likelihood...");
1982 
1983  std::list<int> signaturesToCompare;
1984  GPS originGPS;
1985  Transform originOffsetENU = Transform::getIdentity();
1986  if(_loopGPS)
1987  {
1988  originGPS = signature->sensorData().gps();
1989  if(originGPS.stamp() == 0.0 && _currentSessionHasGPS)
1990  {
1991  UTimer tmpT;
1992  if(_optimizedPoses.size() && _memory->isIncremental())
1993  {
1994  //Search for latest node having GPS linked to current signature not too far.
1995  std::map<int, float> nearestIds = graph::findNearestNodes(signature->id(), _optimizedPoses, _localRadius);
1996  for(std::map<int, float>::reverse_iterator iter=nearestIds.rbegin(); iter!=nearestIds.rend() && iter->first>0; ++iter)
1997  {
1998  const Signature * s = _memory->getSignature(iter->first);
1999  UASSERT(s!=0);
2000  if(s->sensorData().gps().stamp() > 0.0)
2001  {
2002  originGPS = s->sensorData().gps();
2003  const Transform & sPose = _optimizedPoses.at(s->id());
2004  Transform localToENU(0,0,(float)((-(originGPS.bearing()-90))*M_PI/180.0) - sPose.theta());
2005  originOffsetENU = localToENU * (sPose.rotation()*(sPose.inverse()*_optimizedPoses.at(signature->id())));
2006  break;
2007  }
2008  }
2009  }
2010  //else if(!_memory->isIncremental()) // TODO, how can we estimate current GPS position in localization?
2011  //{
2012  //}
2013  }
2014  if(originGPS.stamp() > 0.0)
2015  {
2016  // no need to save it if it is in localization mode
2017  _gpsGeocentricCache.insert(std::make_pair(signature->id(), std::make_pair(originGPS.toGeodeticCoords().toGeocentric_WGS84(), originOffsetENU)));
2018  }
2019  }
2020 
2021  for(std::map<int, double>::const_iterator iter=_memory->getWorkingMem().begin();
2022  iter!=_memory->getWorkingMem().end();
2023  ++iter)
2024  {
2025  if(iter->first > 0)
2026  {
2027  const Signature * s = _memory->getSignature(iter->first);
2028  UASSERT(s!=0);
2029  if(s->getWeight() != -1) // ignore intermediate nodes
2030  {
2031  bool accept = true;
2032  if(originGPS.stamp()>0.0)
2033  {
2034  std::map<int, std::pair<cv::Point3d, Transform> >::iterator cacheIter = _gpsGeocentricCache.find(s->id());
2035  if(cacheIter == _gpsGeocentricCache.end())
2036  {
2037  GPS gps = s->sensorData().gps();
2038  Transform offsetENU = Transform::getIdentity();
2039  if(gps.stamp()==0.0)
2040  {
2041  _memory->getGPS(s->id(), gps, offsetENU, false);
2042  }
2043  if(gps.stamp() > 0.0)
2044  {
2045  cacheIter = _gpsGeocentricCache.insert(
2046  std::make_pair(s->id(),
2047  std::make_pair(gps.toGeodeticCoords().toGeocentric_WGS84(), offsetENU))).first;
2048  }
2049  }
2050 
2051 
2052  if(cacheIter != _gpsGeocentricCache.end())
2053  {
2054  std::map<int, std::pair<cv::Point3d, Transform> >::iterator originIter = _gpsGeocentricCache.find(signature->id());
2055  UASSERT(originIter != _gpsGeocentricCache.end());
2056  cv::Point3d relativePose = GeodeticCoords::Geocentric_WGS84ToENU_WGS84(cacheIter->second.first, originIter->second.first, originGPS.toGeodeticCoords());
2057  const double & error = originGPS.error();
2058  const Transform & offsetENU = cacheIter->second.second;
2059  relativePose.x += offsetENU.x() - originOffsetENU.x();
2060  relativePose.y += offsetENU.y() - originOffsetENU.y();
2061  relativePose.z += offsetENU.z() - originOffsetENU.z();
2062  // ignore altitude if difference is under GPS error
2063  if(relativePose.z>error)
2064  {
2065  relativePose.z -= error;
2066  }
2067  else if(relativePose.z < -error)
2068  {
2069  relativePose.z += error;
2070  }
2071  else
2072  {
2073  relativePose.z = 0;
2074  }
2075  accept = uNormSquared(relativePose.x, relativePose.y, relativePose.z) < _localRadius*_localRadius;
2076  }
2077  }
2078 
2079  if(accept)
2080  {
2081  signaturesToCompare.push_back(iter->first);
2082  }
2083  }
2084  }
2085  else
2086  {
2087  // virtual signature should be added
2088  signaturesToCompare.push_back(iter->first);
2089  }
2090  }
2091 
2092  rawLikelihood = _memory->computeLikelihood(signature, signaturesToCompare);
2093 
2094  // Adjust the likelihood (with mean and std dev)
2095  likelihood = rawLikelihood;
2096  this->adjustLikelihood(likelihood);
2097 
2098  timeLikelihoodCalculation = timer.ticks();
2099  ULOGGER_INFO("timeLikelihoodCalculation=%fs",timeLikelihoodCalculation);
2100 
2101  //============================================================
2102  // Apply the Bayes filter
2103  // Posterior = Likelihood x Prior
2104  //============================================================
2105  ULOGGER_INFO("getting posterior...");
2106 
2107  // Compute the posterior
2108  posterior = _bayesFilter->computePosterior(_memory, likelihood);
2109  timePosteriorCalculation = timer.ticks();
2110  ULOGGER_INFO("timePosteriorCalculation=%fs",timePosteriorCalculation);
2111 
2112  // For statistics, copy weights
2114  {
2115  weights = _memory->getWeights();
2116  }
2117 
2118  //============================================================
2119  // Select the highest hypothesis
2120  //============================================================
2121  ULOGGER_INFO("creating hypotheses...");
2122  if(posterior.size())
2123  {
2124  for(std::map<int, float>::const_reverse_iterator iter = posterior.rbegin(); iter != posterior.rend(); ++iter)
2125  {
2126  if(iter->first > 0 && iter->second > _highestHypothesis.second)
2127  {
2129  }
2130  }
2131  // With the virtual place, use sum of LC probabilities (1 - virtual place hypothesis).
2132  _highestHypothesis.second = 1-posterior.begin()->second;
2133  }
2134  timeHypothesesCreation = timer.ticks();
2135  ULOGGER_INFO("Highest hypothesis=%d, value=%f, timeHypothesesCreation=%fs", _highestHypothesis.first, _highestHypothesis.second, timeHypothesesCreation);
2136 
2137  if(_highestHypothesis.first > 0)
2138  {
2139  float loopThr = _loopThr;
2140  bool hasLoopClosureConstraints = false;
2141  for(std::multimap<int, Link>::iterator iter=_odomCacheConstraints.begin(); iter!=_odomCacheConstraints.end() && !hasLoopClosureConstraints; ++iter)
2142  {
2143  hasLoopClosureConstraints =
2144  iter->second.type() == Link::kGlobalClosure ||
2145  iter->second.type() == Link::kLocalSpaceClosure ||
2146  iter->second.type() == Link::kLandmark;
2147  }
2148  if( (( _memory->isIncremental() && !uContains(_optimizedPoses, _highestHypothesis.first)) || // not linked to previous map of that hypothesis
2149  (!_memory->isIncremental() && !hasLoopClosureConstraints)) && // not yet localized to any previous sessions
2150  _memory->getWorkingMem().size()>1 && // should have an old map (beside virtual signature)
2151  _rgbdSlamMode &&
2152  loopThr > _aggressiveLoopThr)
2153  {
2154  // use the best hypothesis directly.
2155  UDEBUG("Using %s=%f", Parameters::kRGBDAggressiveLoopThr().c_str(), _aggressiveLoopThr);
2156  loopThr = _aggressiveLoopThr;
2157  }
2158 
2159  // Loop closure Threshold
2160  if(_highestHypothesis.second >= loopThr)
2161  {
2162  rejectedLoopClosure = true;
2163  if(posterior.size() <= 2 && loopThr>0.0f)
2164  {
2165  // Ignore loop closure if there is only one loop closure hypothesis
2166  UDEBUG("rejected hypothesis: single hypothesis");
2167  }
2169  {
2170  UWARN("rejected hypothesis: by epipolar geometry");
2171  }
2172  else if(_loopRatio > 0.0f && lastHighestHypothesis.second && _highestHypothesis.second < _loopRatio*lastHighestHypothesis.second)
2173  {
2174  UWARN("rejected hypothesis: not satisfying hypothesis ratio (%f < %f * %f)",
2175  _highestHypothesis.second, _loopRatio, lastHighestHypothesis.second);
2176  }
2177  else if(_loopRatio > 0.0f && lastHighestHypothesis.second == 0)
2178  {
2179  UWARN("rejected hypothesis: last closure hypothesis is null (loop ratio is on)");
2180  }
2181  else
2182  {
2184  rejectedLoopClosure = false;
2185  }
2186 
2187  timeHypothesesValidation = timer.ticks();
2188  ULOGGER_INFO("timeHypothesesValidation=%fs",timeHypothesesValidation);
2189  }
2190  else if(_highestHypothesis.second < _loopRatio*lastHighestHypothesis.second)
2191  {
2192  // Used for Precision-Recall computation.
2193  // When analyzing logs, it's convenient to know
2194  // if the hypothesis would be rejected if T_loop would be lower.
2195  rejectedLoopClosure = true;
2196  UDEBUG("rejected hypothesis: under loop ratio %f < %f", _highestHypothesis.second, _loopRatio*lastHighestHypothesis.second);
2197  }
2198 
2199  //for statistic...
2200  hypothesisRatio = _loopClosureHypothesis.second>0?_highestHypothesis.second/_loopClosureHypothesis.second:0;
2201  }
2202  } // if(_memory->getWorkingMemSize())
2203  }// !isBadSignature
2204  else if(!signature->isBadSignature() && (smallDisplacement || tooFastMovement))
2205  {
2206  _highestHypothesis = lastHighestHypothesis;
2207  UDEBUG("smallDisplacement=%d tooFastMovement=%d", smallDisplacement?1:0, tooFastMovement?1:0);
2208  }
2209  else
2210  {
2211  UDEBUG("Ignoring likelihood and loop closure hypotheses as current signature doesn't have enough visual features.");
2212  }
2213 
2214  //============================================================
2215  // Before retrieval, make sure the trash has finished
2216  //============================================================
2218  timeEmptyingTrash = _memory->getDbSavingTime();
2219  timeJoiningTrash = timer.ticks();
2220  ULOGGER_INFO("Time emptying memory trash = %fs, joining (actual overhead) = %fs", timeEmptyingTrash, timeJoiningTrash);
2221 
2222  //============================================================
2223  // RETRIEVAL 1/3 : Loop closure neighbors reactivation
2224  //============================================================
2225  int retrievalId = _highestHypothesis.first;
2226  std::list<int> reactivatedIds;
2227  double timeGetNeighborsTimeDb = 0.0;
2228  double timeGetNeighborsSpaceDb = 0.0;
2229  int immunizedGlobally = 0;
2230  int immunizedLocally = 0;
2231  int maxLocalLocationsImmunized = 0;
2232  if(_maxTimeAllowed != 0 || _maxMemoryAllowed != 0)
2233  {
2234  // with memory management, we have to immunize some nodes
2235  maxLocalLocationsImmunized = _localImmunizationRatio * float(_memory->getWorkingMem().size());
2236  }
2237  // no need to do retrieval or immunization of locations if memory management
2238  // is disabled and all nodes are in WM
2239  if(!(_memory->allNodesInWM() && maxLocalLocationsImmunized == 0))
2240  {
2241  if(retrievalId > 0)
2242  {
2243  //Load neighbors
2244  ULOGGER_INFO("Retrieving locations... around id=%d", retrievalId);
2245  int neighborhoodSize = (int)_bayesFilter->getPredictionLC().size()-1;
2246  UASSERT(neighborhoodSize >= 0);
2247  ULOGGER_DEBUG("margin=%d maxRetieved=%d", neighborhoodSize, _maxRetrieved);
2248 
2249  UTimer timeGetN;
2250  unsigned int nbLoadedFromDb = 0;
2251  std::set<int> reactivatedIdsSet;
2252  std::map<int, int> neighbors;
2253  int nbDirectNeighborsInDb = 0;
2254 
2255  // priority in time
2256  // Direct neighbors TIME
2257  ULOGGER_DEBUG("In TIME");
2258  neighbors = _memory->getNeighborsId(retrievalId,
2259  neighborhoodSize,
2260  _maxRetrieved,
2261  true,
2262  true,
2263  false,
2264  true,
2265  std::set<int>(),
2266  &timeGetNeighborsTimeDb);
2267  ULOGGER_DEBUG("neighbors of %d in time = %d", retrievalId, (int)neighbors.size());
2268  //Priority to locations near in time (direct neighbor) then by space (loop closure)
2269  bool firstPassDone = false; // just to avoid checking to STM after the first pass
2270  int m = 0;
2271  while(m < neighborhoodSize)
2272  {
2273  std::set<int> idsSorted;
2274  for(std::map<int, int>::iterator iter=neighbors.begin(); iter!=neighbors.end();)
2275  {
2276  if(!firstPassDone && _memory->isInSTM(iter->first))
2277  {
2278  neighbors.erase(iter++);
2279  }
2280  else if(iter->second == m)
2281  {
2282  if(reactivatedIdsSet.find(iter->first) == reactivatedIdsSet.end())
2283  {
2284  idsSorted.insert(iter->first);
2285  reactivatedIdsSet.insert(iter->first);
2286 
2287  if(m == 1 && _memory->getSignature(iter->first) == 0)
2288  {
2289  ++nbDirectNeighborsInDb;
2290  }
2291 
2292  //immunized locations in the neighborhood from being transferred
2293  if(immunizedLocations.insert(iter->first).second)
2294  {
2295  ++immunizedGlobally;
2296  }
2297 
2298  //UDEBUG("nt=%d m=%d immunized=1", iter->first, iter->second);
2299  }
2300  neighbors.erase(iter++);
2301  }
2302  else
2303  {
2304  ++iter;
2305  }
2306  }
2307  firstPassDone = true;
2308  reactivatedIds.insert(reactivatedIds.end(), idsSorted.rbegin(), idsSorted.rend());
2309  ++m;
2310  }
2311 
2312  // neighbors SPACE, already added direct neighbors will be ignored
2313  ULOGGER_DEBUG("In SPACE");
2314  neighbors = _memory->getNeighborsId(retrievalId,
2315  neighborhoodSize,
2316  _maxRetrieved,
2317  true,
2318  false,
2319  false,
2320  false,
2321  std::set<int>(),
2322  &timeGetNeighborsSpaceDb);
2323  ULOGGER_DEBUG("neighbors of %d in space = %d", retrievalId, (int)neighbors.size());
2324  firstPassDone = false;
2325  m = 0;
2326  while(m < neighborhoodSize)
2327  {
2328  std::set<int> idsSorted;
2329  for(std::map<int, int>::iterator iter=neighbors.begin(); iter!=neighbors.end();)
2330  {
2331  if(!firstPassDone && _memory->isInSTM(iter->first))
2332  {
2333  neighbors.erase(iter++);
2334  }
2335  else if(iter->second == m)
2336  {
2337  if(reactivatedIdsSet.find(iter->first) == reactivatedIdsSet.end())
2338  {
2339  idsSorted.insert(iter->first);
2340  reactivatedIdsSet.insert(iter->first);
2341 
2342  if(m == 1 && _memory->getSignature(iter->first) == 0)
2343  {
2344  ++nbDirectNeighborsInDb;
2345  }
2346  //UDEBUG("nt=%d m=%d", iter->first, iter->second);
2347  }
2348  neighbors.erase(iter++);
2349  }
2350  else
2351  {
2352  ++iter;
2353  }
2354  }
2355  firstPassDone = true;
2356  reactivatedIds.insert(reactivatedIds.end(), idsSorted.rbegin(), idsSorted.rend());
2357  ++m;
2358  }
2359  ULOGGER_INFO("neighborhoodSize=%d, "
2360  "reactivatedIds.size=%d, "
2361  "nbLoadedFromDb=%d, "
2362  "nbDirectNeighborsInDb=%d, "
2363  "time=%fs (%fs %fs)",
2364  neighborhoodSize,
2365  reactivatedIds.size(),
2366  (int)nbLoadedFromDb,
2367  nbDirectNeighborsInDb,
2368  timeGetN.ticks(),
2369  timeGetNeighborsTimeDb,
2370  timeGetNeighborsSpaceDb);
2371 
2372  }
2373  }
2374 
2375  //============================================================
2376  // RETRIEVAL 2/3 : Update planned path and get next nodes to retrieve
2377  //============================================================
2378  std::list<int> retrievalLocalIds;
2379  if(_rgbdSlamMode)
2380  {
2381  // Priority on locations on the planned path
2382  if(_path.size())
2383  {
2384  updateGoalIndex();
2385 
2386  float distanceSoFar = 0.0f;
2387  // immunize all nodes after current node and
2388  // retrieve nodes after current node in the maximum radius from the current node
2389  for(unsigned int i=_pathCurrentIndex; i<_path.size(); ++i)
2390  {
2391  if(_localRadius > 0.0f && i != _pathCurrentIndex)
2392  {
2393  distanceSoFar += _path[i-1].second.getDistance(_path[i].second);
2394  }
2395 
2396  if(distanceSoFar <= _localRadius)
2397  {
2398  if(_memory->getSignature(_path[i].first) != 0)
2399  {
2400  if(immunizedLocations.insert(_path[i].first).second)
2401  {
2402  ++immunizedLocally;
2403  }
2404  UDEBUG("Path immunization: node %d (dist=%fm)", _path[i].first, distanceSoFar);
2405  }
2406  else if(retrievalLocalIds.size() < _maxLocalRetrieved)
2407  {
2408  UINFO("retrieval of node %d on path (dist=%fm)", _path[i].first, distanceSoFar);
2409  retrievalLocalIds.push_back(_path[i].first);
2410  // retrieved locations are automatically immunized
2411  }
2412  }
2413  else
2414  {
2415  UDEBUG("Stop on node %d (dist=%fm > %fm)",
2416  _path[i].first, distanceSoFar, _localRadius);
2417  break;
2418  }
2419  }
2420  }
2421 
2422  if(!(_memory->allNodesInWM() && maxLocalLocationsImmunized == 0))
2423  {
2424  // immunize the path from the nearest local location to the current location
2425  if(immunizedLocally < maxLocalLocationsImmunized &&
2426  _memory->isIncremental()) // Can only work in mapping mode
2427  {
2428  std::map<int ,Transform> poses;
2429  // remove poses from STM
2430  for(std::map<int, Transform>::iterator iter=_optimizedPoses.begin(); iter!=_optimizedPoses.end(); ++iter)
2431  {
2432  if(iter->first > 0 && !_memory->isInSTM(iter->first))
2433  {
2434  poses.insert(*iter);
2435  }
2436  }
2437  int nearestId = graph::findNearestNode(poses, _optimizedPoses.at(signature->id()));
2438 
2439  if(nearestId > 0 &&
2440  (_localRadius==0 ||
2441  _optimizedPoses.at(signature->id()).getDistance(_optimizedPoses.at(nearestId)) < _localRadius))
2442  {
2443  std::multimap<int, int> links;
2444  for(std::multimap<int, Link>::iterator iter=_constraints.begin(); iter!=_constraints.end(); ++iter)
2445  {
2446  if(uContains(_optimizedPoses, iter->second.from()) && uContains(_optimizedPoses, iter->second.to()))
2447  {
2448  links.insert(std::make_pair(iter->second.from(), iter->second.to()));
2449  links.insert(std::make_pair(iter->second.to(), iter->second.from())); // <->
2450  }
2451  }
2452 
2453  std::list<std::pair<int, Transform> > path = graph::computePath(_optimizedPoses, links, nearestId, signature->id());
2454  if(path.size() == 0)
2455  {
2456  UWARN("Could not compute a path between %d and %d", nearestId, signature->id());
2457  }
2458  else
2459  {
2460  for(std::list<std::pair<int, Transform> >::iterator iter=path.begin();
2461  iter!=path.end();
2462  ++iter)
2463  {
2464  if(iter->first>0)
2465  {
2466  if(immunizedLocally >= maxLocalLocationsImmunized)
2467  {
2468  // set 20 to avoid this warning when starting mapping
2469  if(maxLocalLocationsImmunized > 20 && _someNodesHaveBeenTransferred)
2470  {
2471  UWARN("Could not immunize the whole local path (%d) between "
2472  "%d and %d (max location immunized=%d). You may want "
2473  "to increase RGBD/LocalImmunizationRatio (current=%f (%d of WM=%d)) "
2474  "to be able to immunize longer paths.",
2475  (int)path.size(),
2476  nearestId,
2477  signature->id(),
2478  maxLocalLocationsImmunized,
2480  maxLocalLocationsImmunized,
2481  (int)_memory->getWorkingMem().size());
2482  }
2483  break;
2484  }
2485  else if(!_memory->isInSTM(iter->first))
2486  {
2487  if(immunizedLocations.insert(iter->first).second)
2488  {
2489  ++immunizedLocally;
2490  }
2491  //UDEBUG("local node %d on path immunized=1", iter->first);
2492  }
2493  }
2494  }
2495  }
2496  }
2497  }
2498 
2499  // retrieval based on the nodes close the the nearest pose in WM
2500  // immunize closest nodes
2501  std::map<int, float> nearNodes = graph::findNearestNodes(signature->id(), _optimizedPoses, _localRadius);
2502  // sort by distance
2503  std::multimap<float, int> nearNodesByDist;
2504  for(std::map<int, float>::iterator iter=nearNodes.lower_bound(1); iter!=nearNodes.end(); ++iter)
2505  {
2506  nearNodesByDist.insert(std::make_pair(iter->second, iter->first));
2507  }
2508  UINFO("near nodes=%d, max local immunized=%d, ratio=%f WM=%d",
2509  (int)nearNodesByDist.size(),
2510  maxLocalLocationsImmunized,
2512  (int)_memory->getWorkingMem().size());
2513  for(std::multimap<float, int>::iterator iter=nearNodesByDist.begin();
2514  iter!=nearNodesByDist.end() && (retrievalLocalIds.size() < _maxLocalRetrieved || immunizedLocally < maxLocalLocationsImmunized);
2515  ++iter)
2516  {
2517  const Signature * s = _memory->getSignature(iter->second);
2518  if(s!=0)
2519  {
2520  // If there is a change of direction, better to be retrieving
2521  // ALL nearest signatures than only newest neighbors
2522  const std::multimap<int, Link> & links = s->getLinks();
2523  for(std::multimap<int, Link>::const_reverse_iterator jter=links.rbegin();
2524  jter!=links.rend() && retrievalLocalIds.size() < _maxLocalRetrieved;
2525  ++jter)
2526  {
2527  if(_memory->getSignature(jter->first) == 0)
2528  {
2529  UINFO("retrieval of node %d on local map", jter->first);
2530  retrievalLocalIds.push_back(jter->first);
2531  }
2532  }
2533  if(!_memory->isInSTM(s->id()) && immunizedLocally < maxLocalLocationsImmunized)
2534  {
2535  if(immunizedLocations.insert(s->id()).second)
2536  {
2537  ++immunizedLocally;
2538  }
2539  //UDEBUG("local node %d (%f m) immunized=1", iter->second, iter->first);
2540  }
2541  }
2542  }
2543  // well, if the maximum retrieved is not reached, look for neighbors in database
2544  if(retrievalLocalIds.size() < _maxLocalRetrieved)
2545  {
2546  std::set<int> retrievalLocalIdsSet(retrievalLocalIds.begin(), retrievalLocalIds.end());
2547  for(std::list<int>::iterator iter=retrievalLocalIds.begin();
2548  iter!=retrievalLocalIds.end() && retrievalLocalIds.size() < _maxLocalRetrieved;
2549  ++iter)
2550  {
2551  std::map<int, int> ids = _memory->getNeighborsId(*iter, 2, _maxLocalRetrieved - (unsigned int)retrievalLocalIds.size() + 1, true, false);
2552  for(std::map<int, int>::reverse_iterator jter=ids.rbegin();
2553  jter!=ids.rend() && retrievalLocalIds.size() < _maxLocalRetrieved;
2554  ++jter)
2555  {
2556  if(_memory->getSignature(jter->first) == 0 &&
2557  retrievalLocalIdsSet.find(jter->first) == retrievalLocalIdsSet.end())
2558  {
2559  UINFO("retrieval of node %d on local map", jter->first);
2560  retrievalLocalIds.push_back(jter->first);
2561  retrievalLocalIdsSet.insert(jter->first);
2562  }
2563  }
2564  }
2565  }
2566 
2567  // update Age of the close signatures (oldest the farthest)
2568  for(std::multimap<float, int>::reverse_iterator iter=nearNodesByDist.rbegin(); iter!=nearNodesByDist.rend(); ++iter)
2569  {
2570  _memory->updateAge(iter->second);
2571  }
2572 
2573  // insert them first to make sure they are loaded.
2574  reactivatedIds.insert(reactivatedIds.begin(), retrievalLocalIds.begin(), retrievalLocalIds.end());
2575  }
2576  }
2577 
2578  //============================================================
2579  // RETRIEVAL 3/3 : Load signatures from the database
2580  //============================================================
2581  if(reactivatedIds.size())
2582  {
2583  // Not important if the loop closure hypothesis don't have all its neighbors loaded,
2584  // only a loop closure link is added...
2585  signaturesRetrieved = _memory->reactivateSignatures(
2586  reactivatedIds,
2587  _maxRetrieved+(unsigned int)retrievalLocalIds.size(), // add path retrieved
2588  timeRetrievalDbAccess);
2589 
2590  ULOGGER_INFO("retrieval of %d (db time = %fs)", (int)signaturesRetrieved.size(), timeRetrievalDbAccess);
2591 
2592  timeRetrievalDbAccess += timeGetNeighborsTimeDb + timeGetNeighborsSpaceDb;
2593  UINFO("total timeRetrievalDbAccess=%fs", timeRetrievalDbAccess);
2594 
2595  // Immunize just retrieved signatures
2596  immunizedLocations.insert(signaturesRetrieved.begin(), signaturesRetrieved.end());
2597 
2598  if(!signaturesRetrieved.empty() && !_globalScanMap.empty())
2599  {
2600  UWARN("Some signatures have been retrieved from memory management, clearing global scan map...");
2602  _globalScanMapPoses.clear();
2603  }
2604  }
2605  timeReactivations = timer.ticks();
2606  ULOGGER_INFO("timeReactivations=%fs", timeReactivations);
2607 
2608  //============================================================
2609  // Proximity detections
2610  //============================================================
2611  std::list<std::pair<int, int> > loopClosureLinksAdded;
2612  int loopClosureVisualInliers = 0; // for statistics
2613  float loopClosureVisualInliersRatio = 0.0f;
2614  int loopClosureVisualMatches = 0;
2615  float loopClosureLinearVariance = 0.0f;
2616  float loopClosureAngularVariance = 0.0f;
2617  float loopClosureVisualInliersMeanDist = 0;
2618  float loopClosureVisualInliersDistribution = 0;
2619 
2620  int proximityDetectionsAddedVisually = 0;
2621  int proximityDetectionsAddedByICPMulti = 0;
2622  int proximityDetectionsAddedByICPGlobal = 0;
2623  int lastProximitySpaceClosureId = 0;
2624  int proximitySpacePaths = 0;
2625  int localVisualPathsChecked = 0;
2626  int localScanPathsChecked = 0;
2627  int loopIdSuppressedByProximity = 0;
2628 
2629  if(_proximityBySpace &&
2630  _localRadius > 0 &&
2631  _rgbdSlamMode &&
2632  signature->getWeight() >= 0) // not an intermediate node
2633  {
2635  _memory->getWorkingMem().size()>=2 && // must have an old map (+1 virtual place)
2636  _localizationCovariance.empty() && // if we didn't localize yet
2637  graph::filterLinks(signature->getLinks(), Link::kSelfRefLink).size() == 0) // alone in new session
2638  {
2639  UINFO("Proximity detection by space disabled as if we force to have a global loop "
2640  "closure with previous map before doing proximity detections (%s=true).",
2641  Parameters::kRtabmapStartNewMapOnLoopClosure().c_str());
2642  }
2643  else if(_graphOptimizer->iterations() == 0)
2644  {
2645  UWARN("Cannot do local loop closure detection in space if graph optimization is disabled!");
2646  }
2647  else
2648  {
2649  // In localization mode, no need to check local loop
2650  // closures if we are already localized by a landmark.
2651 
2652  // don't do it if it is a small displacement unless the previous signature didn't have a loop closure
2653  // don't do it if there is a too fast movement
2654  if((!smallDisplacement || !localizationOnPreviousUpdate) && !tooFastMovement)
2655  {
2656 
2657  //============================================================
2658  // LOCAL LOOP CLOSURE SPACE
2659  //============================================================
2660 
2661  //
2662  // 1) compare visually with nearest locations
2663  //
2664  UDEBUG("Proximity detection (local loop closure in SPACE using matching images, local radius=%fm)", _localRadius);
2665  std::map<int, float> nearestIds = graph::findNearestNodes(signature->id(), _optimizedPoses, _localRadius);
2666  UDEBUG("nearestIds=%d/%d", (int)nearestIds.size(), (int)_optimizedPoses.size());
2667  std::map<int, Transform> nearestPoses;
2668  std::multimap<int, int> links;
2670  {
2671  // get bidirectional links
2672  for(std::multimap<int, Link>::iterator iter=_constraints.begin(); iter!=_constraints.end(); ++iter)
2673  {
2674  if(uContains(_optimizedPoses, iter->second.from()) && uContains(_optimizedPoses, iter->second.to()))
2675  {
2676  links.insert(std::make_pair(iter->second.from(), iter->second.to()));
2677  links.insert(std::make_pair(iter->second.to(), iter->second.from())); // <->
2678  }
2679  }
2680  }
2681  for(std::map<int, float>::iterator iter=nearestIds.lower_bound(1); iter!=nearestIds.end(); ++iter)
2682  {
2683  if(_memory->getStMem().find(iter->first) == _memory->getStMem().end())
2684  {
2686  {
2687  std::list<std::pair<int, Transform> > path = graph::computePath(_optimizedPoses, links, signature->id(), iter->first);
2688  UDEBUG("Graph depth to %d = %ld", iter->first, path.size());
2689  if(!path.empty() && (int)path.size() <= _proximityMaxGraphDepth)
2690  {
2691  nearestPoses.insert(std::make_pair(iter->first, _optimizedPoses.at(iter->first)));
2692  }
2693  }
2694  else
2695  {
2696  nearestPoses.insert(std::make_pair(iter->first, _optimizedPoses.at(iter->first)));
2697  }
2698  }
2699  }
2700  UDEBUG("nearestPoses=%d", (int)nearestPoses.size());
2701 
2702  // segment poses by paths, only one detection per path, landmarks are ignored
2703  std::map<int, std::map<int, Transform> > nearestPathsNotSorted = getPaths(nearestPoses, _optimizedPoses.at(signature->id()), _proximityMaxGraphDepth);
2704  UDEBUG("got %d paths", (int)nearestPathsNotSorted.size());
2705  // sort nearest paths by highest likelihood (if two have same likelihood, sort by id)
2706  std::map<NearestPathKey, std::map<int, Transform> > nearestPaths;
2707  Transform currentPoseInv = _optimizedPoses.at(signature->id()).inverse();
2708  for(std::map<int, std::map<int, Transform> >::const_iterator iter=nearestPathsNotSorted.begin();iter!=nearestPathsNotSorted.end(); ++iter)
2709  {
2710  const std::map<int, Transform> & path = iter->second;
2711  float highestLikelihood = 0.0f;
2712  int highestLikelihoodId = iter->first;
2713  float smallestDistanceSqr = -1;
2714  for(std::map<int, Transform>::const_iterator jter=path.begin(); jter!=path.end(); ++jter)
2715  {
2716  float v = uValue(likelihood, jter->first, 0.0f);
2717  float distance = (currentPoseInv * jter->second).getNormSquared();
2718  if(v > highestLikelihood || (v == highestLikelihood && (smallestDistanceSqr < 0 || distance < smallestDistanceSqr)))
2719  {
2720  highestLikelihood = v;
2721  highestLikelihoodId = jter->first;
2722  smallestDistanceSqr = distance;
2723  }
2724  }
2725  nearestPaths.insert(std::make_pair(NearestPathKey(highestLikelihood, highestLikelihoodId, smallestDistanceSqr), path));
2726  }
2727  UDEBUG("nearestPaths=%d proximityMaxPaths=%d", (int)nearestPaths.size(), _proximityMaxPaths);
2728 
2729  timeProximityBySpaceSearch = timer.ticks();
2730  ULOGGER_INFO("timeProximityBySpaceSearch=%fs", timeProximityBySpaceSearch);
2731 
2732  float proximityFilteringRadius = _proximityFilteringRadius;
2733  if(_maxLoopClosureDistance>0.0f && (proximityFilteringRadius <= 0.0f || _maxLoopClosureDistance<proximityFilteringRadius))
2734  {
2735  proximityFilteringRadius = _maxLoopClosureDistance;
2736  }
2737  for(std::map<NearestPathKey, std::map<int, Transform> >::const_reverse_iterator iter=nearestPaths.rbegin();
2738  iter!=nearestPaths.rend() &&
2739  (_proximityMaxPaths <= 0 || localVisualPathsChecked < _proximityMaxPaths);
2740  ++iter)
2741  {
2742  std::map<int, Transform> path = iter->second;
2743  UASSERT(path.size());
2744 
2745  //find the nearest pose on the path looking in the same direction
2746  path.insert(std::make_pair(signature->id(), _optimizedPoses.at(signature->id())));
2748  //take the one with highest likelihood if not null
2749  int nearestId = 0;
2750  if(iter->first.likelihood > 0.0f &&
2751  path.find(iter->first.id)!=path.end())
2752  {
2753  nearestId = iter->first.id;
2754  }
2755  else
2756  {
2757  nearestId = rtabmap::graph::findNearestNode(path, _optimizedPoses.at(signature->id()));
2758  }
2759 
2760  if(nearestId > 0)
2761  {
2762  // nearest pose must not be linked to current location and enough close
2763  if(!signature->hasLink(nearestId) &&
2764  (proximityFilteringRadius <= 0.0f ||
2765  _optimizedPoses.at(signature->id()).getDistanceSquared(_optimizedPoses.at(nearestId)) < proximityFilteringRadius*proximityFilteringRadius))
2766  {
2767  ++localVisualPathsChecked;
2769  Transform guess;
2771  {
2772  // Use odometry as guess so that correspondences can be computed by projection
2773  guess = _optimizedPoses.at(nearestId).inverse()*_optimizedPoses.at(signature->id());
2774  } //else: guess is null to make sure visual correspondences are globally computed
2775  Transform transform = _memory->computeTransform(nearestId, signature->id(), guess, &info);
2776  if(!transform.isNull())
2777  {
2778  transform = transform.inverse();
2779  if(proximityFilteringRadius <= 0 || transform.getNormSquared() <= proximityFilteringRadius*proximityFilteringRadius)
2780  {
2781  UINFO("[Visual] Add local loop closure in SPACE (%d->%d) %s",
2782  signature->id(),
2783  nearestId,
2784  transform.prettyPrint().c_str());
2785  UASSERT(info.covariance.at<double>(0,0) > 0.0 && info.covariance.at<double>(5,5) > 0.0);
2786 
2787  //for statistics
2788  loopClosureVisualInliersMeanDist = info.inliersMeanDistance;
2789  loopClosureVisualInliersDistribution = info.inliersDistribution;
2790 
2791  ++proximityDetectionsAddedVisually;
2792  lastProximitySpaceClosureId = nearestId;
2793 
2794  loopClosureVisualInliers = info.inliers;
2795  loopClosureVisualInliersRatio = info.inliersRatio;
2796  loopClosureVisualMatches = info.matches;
2797 
2798  cv::Mat information = getInformation(info.covariance);
2799  loopClosureLinearVariance = 1.0/information.at<double>(0,0);
2800  loopClosureAngularVariance = 1.0/information.at<double>(5,5);
2801 
2803  if(_loopClosureHypothesis.first>0 &&
2804  nearestIds.find(_loopClosureHypothesis.first)!=nearestIds.end())
2805  {
2806  // Avoid transform computation on the global loop closure if a visual proximity
2807  // one has been detected close (inside proximity radius) to that hypothesis.
2808  UDEBUG("Proximity detection on %d is close to loop closure %d, ignoring loop closure transform estimation...",
2809  nearestId, _loopClosureHypothesis.first);
2810 
2811  if(nearestId == _loopClosureHypothesis.first)
2812  {
2814  loopIdSuppressedByProximity = nearestId;
2815  }
2816  else if(loopIdSuppressedByProximity == 0)
2817  {
2818  loopIdSuppressedByProximity = nearestId;
2819  }
2820  }
2821 
2822  _memory->addLink(Link(signature->id(), nearestId, type, transform, information));
2823  loopClosureLinksAdded.push_back(std::make_pair(signature->id(), nearestId));
2824  }
2825  else
2826  {
2827  UWARN("Ignoring local loop closure with %d because resulting "
2828  "transform is too large!? (%fm > %fm)",
2829  nearestId, transform.getNorm(), proximityFilteringRadius);
2830  }
2831  }
2832  }
2833  else if(!signature->hasLink(nearestId) && proximityFilteringRadius>0.0f)
2834  {
2835  UDEBUG("Skipping path %d as most likely ID %d is too far %f > %f (%s)",
2836  iter->first.id,
2837  nearestId,
2838  _optimizedPoses.at(signature->id()).getDistance(_optimizedPoses.at(nearestId)),
2839  proximityFilteringRadius,
2840  Parameters::kRGBDProximityPathFilteringRadius().c_str());
2841  }
2842  }
2843  }
2844 
2845  timeProximityBySpaceVisualDetection = timer.ticks();
2846  ULOGGER_INFO("timeProximityBySpaceVisualDetection=%fs", timeProximityBySpaceVisualDetection);
2847 
2848  //
2849  // 2) compare locally with nearest locations by scan matching
2850  //
2851  UDEBUG("Proximity detection (local loop closure in SPACE with scan matching)");
2852  if( _proximityMaxNeighbors <= 0)
2853  {
2854  UDEBUG("Proximity by scan matching is disabled (%s=%d).", Parameters::kRGBDProximityPathMaxNeighbors().c_str(), _proximityMaxNeighbors);
2855  }
2856  else if(!signature->sensorData().laserScanCompressed().isEmpty())
2857  {
2858  proximitySpacePaths = (int)nearestPaths.size();
2859  for(std::map<NearestPathKey, std::map<int, Transform> >::const_reverse_iterator iter=nearestPaths.rbegin();
2860  iter!=nearestPaths.rend() &&
2861  (_proximityMaxPaths <= 0 || localScanPathsChecked < _proximityMaxPaths);
2862  ++iter)
2863  {
2864  std::map<int, Transform> path = iter->second; // should contain only nodes (no landmarks)
2865  UASSERT(path.size());
2866  UASSERT(path.begin()->first > 0);
2867 
2868  //find the nearest pose on the path
2869  int nearestId = rtabmap::graph::findNearestNode(path, _optimizedPoses.at(signature->id()));
2870  UASSERT(nearestId > 0);
2871  //UDEBUG("Path %d (size=%d) distance=%fm", nearestId, (int)path.size(), _optimizedPoses.at(signature->id()).getDistance(_optimizedPoses.at(nearestId)));
2872 
2873  // nearest pose must be close and not linked to current location
2874  if(!signature->hasLink(nearestId))
2875  {
2877  {
2878  std::map<int, Transform> filteredPath;
2879  int i=0;
2880  std::map<int, Transform>::iterator nearestIdIter = path.find(nearestId);
2881  // "_proximityMaxNeighbors-1" means that if _proximityMaxNeighbors=1,
2882  // only nearest node on the path is taken (no scan merging). Useful to find
2883  // proximity detection between only 2 nodes with 360x360 lidar scans.
2884  for(std::map<int, Transform>::iterator iter=nearestIdIter; iter!=path.end() && i<=_proximityMaxNeighbors-1; ++iter, ++i)
2885  {
2886  filteredPath.insert(*iter);
2887  }
2888  i=1;
2889  for(std::map<int, Transform>::reverse_iterator iter(nearestIdIter); iter!=path.rend() && i<=_proximityMaxNeighbors-1; ++iter, ++i)
2890  {
2891  filteredPath.insert(*iter);
2892  }
2893  path = filteredPath;
2894  }
2895 
2896  // Assemble scans in the path and do ICP only
2897  std::map<int, Transform> optimizedLocalPath;
2899  {
2900  //optimize the path's poses locally
2901  cv::Mat covariance;
2902  path = optimizeGraph(nearestId, uKeysSet(path), std::map<int, Transform>(), false, covariance);
2903  // transform local poses in optimized graph referential
2904  if(!uContains(path, nearestId))
2905  {
2906  UERROR("Proximity path not containing nearest ID ?! Skipping this path.");
2907  continue;
2908  }
2909  Transform t = _optimizedPoses.at(nearestId) * path.at(nearestId).inverse();
2910 
2911  for(std::map<int, Transform>::iterator jter=path.lower_bound(1); jter!=path.end(); ++jter)
2912  {
2913  optimizedLocalPath.insert(std::make_pair(jter->first, t * jter->second));
2914  }
2915  }
2916  else
2917  {
2918  optimizedLocalPath = path;
2919  }
2920 
2921  std::map<int, Transform> filteredPath;
2922  if(_globalScanMap.empty() && optimizedLocalPath.size() > 2 && proximityFilteringRadius > 0.0f)
2923  {
2924  // path filtering
2925  filteredPath = graph::radiusPosesFiltering(optimizedLocalPath, proximityFilteringRadius, 0, true);
2926  // make sure the current pose is still here
2927  filteredPath.insert(*optimizedLocalPath.find(nearestId));
2928  }
2929  else
2930  {
2931  filteredPath = optimizedLocalPath;
2932  }
2933 
2934  if(filteredPath.size() > 0)
2935  {
2936  // add current node to poses
2937  filteredPath.insert(std::make_pair(signature->id(), _optimizedPoses.at(signature->id())));
2938  //The nearest will be the reference for a loop closure transform
2939  if(signature->getLinks().find(nearestId) == signature->getLinks().end())
2940  {
2941  ++localScanPathsChecked;
2944  bool icpMulti = true;
2945  if(_globalScanMap.empty())
2946  {
2947  transform = _memory->computeIcpTransformMulti(signature->id(), nearestId, filteredPath, &info);
2948  }
2949  else
2950  {
2951  UASSERT_MSG(_globalScanMapPoses.find(nearestId) != _globalScanMapPoses.end(), uFormat("Pose of %d not found in global scan poses", nearestId).c_str());
2952  icpMulti = false;
2953  // use pre-assembled scan map
2954  SensorData assembledData;
2955  assembledData.setId(nearestId);
2956  assembledData.setLaserScan(
2958  signature->sensorData().laserScanCompressed().maxPoints(),
2959  signature->sensorData().laserScanCompressed().rangeMax(),
2960  _globalScanMapPoses.at(nearestId).inverse() * (signature->sensorData().laserScanCompressed().is2d()?Transform(0,0,signature->sensorData().laserScanCompressed().localTransform().z(),0,0,0):Transform::getIdentity())));
2961  Signature nearestNode(assembledData);
2962  Transform guess = filteredPath.at(nearestId).inverse() * filteredPath.at(signature->id());
2963  transform = _memory->computeIcpTransform(nearestNode, *signature, guess, &info);
2964  if(!transform.isNull())
2965  {
2966  transform = transform.inverse();
2967  }
2968  }
2969 
2970  if(!transform.isNull())
2971  {
2972  UINFO("[Scan matching] Add local loop closure in SPACE (%d->%d) %s",
2973  signature->id(),
2974  nearestId,
2975  transform.prettyPrint().c_str());
2976 
2977  cv::Mat scanMatchingIds;
2979  {
2980  std::stringstream stream;
2981  stream << "SCANS:";
2982  for(std::map<int, Transform>::iterator iter=optimizedLocalPath.begin(); iter!=optimizedLocalPath.end(); ++iter)
2983  {
2984  if(iter != optimizedLocalPath.begin())
2985  {
2986  stream << ";";
2987  }
2988  stream << uNumber2Str(iter->first);
2989  }
2990  std::string scansStr = stream.str();
2991  scanMatchingIds = cv::Mat(1, int(scansStr.size()+1), CV_8SC1, (void *)scansStr.c_str());
2992  scanMatchingIds = compressData2(scanMatchingIds); // compressed
2993  }
2994 
2995  // set Identify covariance for laser scan matching only
2996  UASSERT(info.covariance.at<double>(0,0) > 0.0 && info.covariance.at<double>(5,5) > 0.0);
2997  _memory->addLink(Link(signature->id(), nearestId, Link::kLocalSpaceClosure, transform, getInformation(info.covariance)/_proximityMergedScanCovFactor, scanMatchingIds));
2998  loopClosureLinksAdded.push_back(std::make_pair(signature->id(), nearestId));
2999 
3000  if(icpMulti)
3001  {
3002  ++proximityDetectionsAddedByICPMulti;
3003  }
3004  else
3005  {
3006  ++proximityDetectionsAddedByICPGlobal;
3007  }
3008 
3009  // no local loop closure added visually
3010  if(proximityDetectionsAddedVisually == 0)
3011  {
3012  lastProximitySpaceClosureId = nearestId;
3013  }
3014  }
3015  else
3016  {
3017  UINFO("Local scan matching rejected: %s", info.rejectedMsg.c_str());
3018  }
3019  if(!_globalScanMap.empty())
3020  {
3021  break;
3022  }
3023  }
3024  }
3025  }
3026  else
3027  {
3028  //UDEBUG("Path %d ignored", nearestId);
3029  }
3030  }
3031  }
3032  }
3033  }
3034  }
3035  timeProximityBySpaceDetection = timer.ticks();
3036  ULOGGER_INFO("timeProximityBySpaceDetection=%fs", timeProximityBySpaceDetection);
3037 
3038  //=============================================================
3039  // Global loop closure detection
3040  // (updated: place this after retrieval to be sure that neighbors of the loop closure are in RAM)
3041  //=============================================================
3042  if(_loopClosureHypothesis.first>0)
3043  {
3044  if(loopIdSuppressedByProximity==0)
3045  {
3046  //Compute transform if metric data are present
3049  info.covariance = cv::Mat::eye(6,6,CV_64FC1);
3050  if(_rgbdSlamMode)
3051  {
3053  _loopClosureHypothesis.first,
3054  signature->id(),
3056  &info);
3057 
3058  loopClosureVisualInliersMeanDist = info.inliersMeanDistance;
3059  loopClosureVisualInliersDistribution = info.inliersDistribution;
3060 
3061  loopClosureVisualInliers = info.inliers;
3062  loopClosureVisualInliersRatio = info.inliersRatio;
3063  loopClosureVisualMatches = info.matches;
3064  rejectedLoopClosure = transform.isNull();
3065  if(rejectedLoopClosure)
3066  {
3067  UWARN("Rejected loop closure %d -> %d: %s",
3068  _loopClosureHypothesis.first, signature->id(), info.rejectedMsg.c_str());
3069  }
3070  else if(_maxLoopClosureDistance>0.0f && transform.getNorm() > _maxLoopClosureDistance)
3071  {
3072  rejectedLoopClosure = true;
3073  UWARN("Rejected localization %d -> %d because distance to map (%fm) is over %s=%fm.",
3074  _loopClosureHypothesis.first, signature->id(), transform.getNorm(), Parameters::kRGBDMaxLoopClosureDistance().c_str(), _maxLoopClosureDistance);
3075  }
3076  else
3077  {
3078  transform = transform.inverse();
3079  }
3080  }
3081  if(!rejectedLoopClosure)
3082  {
3083  // Make the new one the parent of the old one
3084  UASSERT(info.covariance.at<double>(0,0) > 0.0 && info.covariance.at<double>(5,5) > 0.0);
3085 
3086  loopClosureLinearVariance = uMax3(info.covariance.at<double>(0,0), info.covariance.at<double>(1,1)>=9999?0:info.covariance.at<double>(1,1), info.covariance.at<double>(2,2)>=9999?0:info.covariance.at<double>(2,2));
3087  loopClosureAngularVariance = uMax3(info.covariance.at<double>(3,3)>=9999?0:info.covariance.at<double>(3,3), info.covariance.at<double>(4,4)>=9999?0:info.covariance.at<double>(4,4), info.covariance.at<double>(5,5));
3088  cv::Mat information = getInformation(info.covariance);
3089  rejectedLoopClosure = !_memory->addLink(Link(signature->id(), _loopClosureHypothesis.first, Link::kGlobalClosure, transform, information));
3090  if(!rejectedLoopClosure)
3091  {
3092  loopClosureLinksAdded.push_back(std::make_pair(signature->id(), _loopClosureHypothesis.first));
3093  }
3094  }
3095 
3096  if(rejectedLoopClosure)
3097  {
3098  _loopClosureHypothesis.first = 0;
3099  }
3100  }
3101  else if(loopIdSuppressedByProximity != _loopClosureHypothesis.first)
3102  {
3103  _loopClosureHypothesis.first = 0;
3104  }
3105  }
3106 
3107  timeAddLoopClosureLink = timer.ticks();
3108  ULOGGER_INFO("timeAddLoopClosureLink=%fs", timeAddLoopClosureLink);
3109 
3110  //============================================================
3111  // Landmark
3112  //============================================================
3113  std::map<int, std::set<int> > landmarksDetected; // <Landmark ID, list of nodes that saw this landmark>
3114  if(!signature->getLandmarks().empty() && !_graphOptimizer->landmarksIgnored())
3115  {
3116  bool hasGlobalLoopClosuresInOdomCache = !graph::filterLinks(_odomCacheConstraints, Link::kGlobalClosure, true).empty() || _loopClosureHypothesis.first != 0;
3117  UDEBUG("hasGlobalLoopClosuresInOdomCache=%d", hasGlobalLoopClosuresInOdomCache?1:0);
3118  for(std::map<int, Link>::const_iterator iter=signature->getLandmarks().begin(); iter!=signature->getLandmarks().end(); ++iter)
3119  {
3120  if(uContains(_memory->getLandmarksIndex(), iter->first) &&
3121  _memory->getLandmarksIndex().find(iter->first)->second.size()>1)
3122  {
3123  if(!_memory->isIncremental() && // In localization mode
3124  !hasGlobalLoopClosuresInOdomCache && // If there are global loop closures in odom cache, we can keep far landmarks
3125  _localRadius>0.0 &&
3126  iter->second.transform().getNormSquared() > _localRadius*_localRadius)
3127  {
3128  // Ignore landmark detections over local radius
3129  UWARN("Ignoring landmark %d for localization as it is too far (%fm > %s=%f) "
3130  "and odom cache doesn't contain global loop closure(s).",
3131  iter->first,
3132  iter->second.transform().getNorm(),
3133  Parameters::kRGBDLocalRadius().c_str(),
3134  _localRadius);
3135  }
3136  else
3137  {
3138  UINFO("Landmark %d observed again! Seen the first time by node %d.", -iter->first, *_memory->getLandmarksIndex().find(iter->first)->second.begin());
3139  landmarksDetected.insert(std::make_pair(iter->first, _memory->getLandmarksIndex().find(iter->first)->second));
3140  rejectedLoopClosure = false; // If it was true, it will be set back to false if landmarks are rejected on graph optimization
3141  loopClosureLinksAdded.push_back(std::make_pair(signature->id(), iter->first));
3142  }
3143  }
3144  }
3145  }
3146 
3147  //============================================================
3148  // Add virtual links if a path is activated
3149  //============================================================
3150  if(_path.size())
3151  {
3152  // Add a virtual loop closure link to keep the path linked to local map
3153  if( signature->id() != _path[_pathCurrentIndex].first &&
3154  !signature->hasLink(_path[_pathCurrentIndex].first))
3155  {
3156  UASSERT(uContains(_optimizedPoses, signature->id()));
3158  Transform virtualLoop = _optimizedPoses.at(signature->id()).inverse() * _optimizedPoses.at(_path[_pathCurrentIndex].first);
3159 
3160  if(_localRadius == 0.0f || virtualLoop.getNorm() < _localRadius)
3161  {
3162  _memory->addLink(Link(signature->id(), _path[_pathCurrentIndex].first, Link::kVirtualClosure, virtualLoop, cv::Mat::eye(6,6,CV_64FC1)*0.01)); // set high variance
3163  }
3164  else
3165  {
3166  UERROR("Virtual link larger than local radius (%fm > %fm). Aborting the plan!",
3167  virtualLoop.getNorm(), _localRadius);
3168  this->clearPath(-1);
3169  }
3170  }
3171  }
3172 
3173  //============================================================
3174  // Optimize map graph
3175  //============================================================
3176  float maxLinearError = 0.0f;
3177  float maxLinearErrorRatio = 0.0f;
3178  float maxAngularError = 0.0f;
3179  float maxAngularErrorRatio = 0.0f;
3180  double optimizationError = 0.0;
3181  int optimizationIterations = 0;
3182  Transform previousMapCorrection;
3183  bool delayedLocalization = false;
3184  UDEBUG("RGB-D SLAM mode: %d", _rgbdSlamMode?1:0);
3185  UDEBUG("Incremental: %d", _memory->isIncremental());
3186  UDEBUG("Loop hyp: %d", _loopClosureHypothesis.first);
3187  UDEBUG("Last prox: %d", lastProximitySpaceClosureId);
3188  UDEBUG("Reduced ids: %d", (int)statistics_.reducedIds().size());
3189  UDEBUG("Has prior: %d (prior ignored=%d)", signature->hasLink(signature->id(), Link::kPosePrior)?1:0, _graphOptimizer->priorsIgnored()?1:0);
3190  UDEBUG("Has gravity: %d (sigma=%f, odomGravity=%d, refined=%d)", signature->hasLink(signature->id(), Link::kGravity)?1:0, _graphOptimizer->gravitySigma(), _memory->isOdomGravityUsed()?1:0, neighborLinkRefined?1:0);
3191  UDEBUG("Has virtual link: %d", (int)graph::filterLinks(signature->getLinks(), Link::kVirtualClosure, true).size());
3192  UDEBUG("Prox Time: %d", proximityDetectionsInTimeFound);
3193  UDEBUG("Landmarks: %d", (int)landmarksDetected.size());
3194  UDEBUG("Retrieved: %d", (int)signaturesRetrieved.size());
3195  UDEBUG("Not self ref links: %d", (int)graph::filterLinks(signature->getLinks(), Link::kSelfRefLink).size());
3196 
3197  if(_rgbdSlamMode
3198  &&
3199  (_loopClosureHypothesis.first>0 ||
3200  lastProximitySpaceClosureId>0 || // can be different map of the current one
3201  statistics_.reducedIds().size() ||
3202  (signature->hasLink(signature->id(), Link::kPosePrior) && !_graphOptimizer->priorsIgnored()) || // prior edge
3203  (signature->hasLink(signature->id(), Link::kGravity) && _graphOptimizer->gravitySigma()>0.0f && (!_memory->isOdomGravityUsed() || neighborLinkRefined)) || // gravity edge
3204  proximityDetectionsInTimeFound>0 ||
3205  !landmarksDetected.empty() ||
3206  signaturesRetrieved.size()) // can be different map of the current one
3207  &&
3208  (_memory->isIncremental() ||
3209  // In localization mode, the new node should be linked to another node or a landmark already in the working memory
3211  !landmarksDetected.empty()))
3212  {
3213  UASSERT(uContains(_optimizedPoses, signature->id()));
3214 
3215  //used in localization mode: filter virtual links
3216  std::multimap<int, Link> localizationLinks = graph::filterLinks(signature->getLinks(), Link::kVirtualClosure);
3217  localizationLinks = graph::filterLinks(localizationLinks, Link::kSelfRefLink);
3218  if(!landmarksDetected.empty() && !_memory->isIncremental())
3219  {
3220  for(std::map<int, std::set<int> >::iterator iter=landmarksDetected.begin(); iter!=landmarksDetected.end(); ++iter)
3221  {
3222  if(_optimizedPoses.find(iter->first)!=_optimizedPoses.end())
3223  {
3224  UASSERT(uContains(signature->getLandmarks(), iter->first));
3225  localizationLinks.insert(std::make_pair(iter->first, signature->getLandmarks().at(iter->first)));
3226  }
3227  }
3228  }
3229 
3230  bool allLocalizationLinksInGraph = !localizationLinks.empty();
3231  for(std::multimap<int, Link>::iterator iter=localizationLinks.begin(); iter!=localizationLinks.end(); ++iter)
3232  {
3233  if(!uContains(_optimizedPoses, iter->first))
3234  {
3235  allLocalizationLinksInGraph = false;
3236  break;
3237  }
3238  }
3239 
3240  // Note that in localization mode, we don't re-optimize the graph
3241  // if:
3242  // 1- there are no signatures retrieved,
3243  // 2- we are relocalizing on a node already in the optimized graph
3244  if(!_memory->isIncremental() &&
3245  signaturesRetrieved.empty() &&
3246  !localizationLinks.empty() &&
3247  allLocalizationLinksInGraph)
3248  {
3249  bool rejectLocalization = _odomCachePoses.empty();
3250  if(!_odomCachePoses.empty())
3251  {
3252  // Verify if the new localization is valid by checking if there is
3253  // not too much deformation using current odometry poses
3254  // This will also refine localization links
3255 
3256  std::map<int, Transform> poses = _odomCachePoses;
3257  std::multimap<int, Link> constraints = _odomCacheConstraints;
3258  // add self referring links (e.g., gravity)
3259  std::multimap<int, Link> selfLinks = graph::filterLinks(signature->getLinks(), Link::kSelfRefLink, true);
3261  {
3262  selfLinks = graph::filterLinks(selfLinks, Link::kPosePrior);
3263  }
3264  constraints.insert(selfLinks.begin(), selfLinks.end());
3265  for(std::multimap<int, Link>::iterator iter=localizationLinks.begin(); iter!=localizationLinks.end(); ++iter)
3266  {
3267  constraints.insert(std::make_pair(iter->second.from(), iter->second));
3268  }
3269  cv::Mat priorInfMat = cv::Mat::eye(6,6, CV_64FC1)*_localizationPriorInf;
3270  for(std::multimap<int, Link>::iterator iter=constraints.begin(); iter!=constraints.end(); ++iter)
3271  {
3272  std::map<int, Transform>::iterator iterPose = _optimizedPoses.find(iter->second.to());
3273  if(iterPose != _optimizedPoses.end() && poses.find(iterPose->first) == poses.end())
3274  {
3275  poses.insert(*iterPose);
3276  // make the poses in the map fixed
3277  constraints.insert(std::make_pair(iterPose->first, Link(iterPose->first, iterPose->first, Link::kPosePrior, iterPose->second, priorInfMat)));
3278  UDEBUG("Constraint %d->%d: %s (type=%s, var=%f)", iterPose->first, iterPose->first, iterPose->second.prettyPrint().c_str(), Link::typeName(Link::kPosePrior).c_str(), 1./_localizationPriorInf);
3279  }
3280  UDEBUG("Constraint %d->%d: %s (type=%s, var = %f %f)", iter->second.from(), iter->second.to(), iter->second.transform().prettyPrint().c_str(), iter->second.typeName().c_str(), iter->second.transVariance(), iter->second.rotVariance());
3281  }
3282 
3283  std::map<int, Transform> posesOut;
3284  std::multimap<int, Link> edgeConstraintsOut;
3285  bool priorsIgnored = _graphOptimizer->priorsIgnored();
3286  UDEBUG("priorsIgnored was %s", priorsIgnored?"true":"false");
3287  _graphOptimizer->setPriorsIgnored(false); //temporary set false to use priors above to fix nodes of the map
3288  // If slam2d: get connected graph while keeping original roll,pitch,z values.
3289  _graphOptimizer->getConnectedGraph(signature->id(), poses, constraints, posesOut, edgeConstraintsOut);
3291  {
3292  for(std::map<int, Transform>::iterator iter=posesOut.begin(); iter!=posesOut.end(); ++iter)
3293  {
3294  UDEBUG("Pose %d %s", iter->first, iter->second.prettyPrint().c_str());
3295  }
3296  }
3297  cv::Mat locOptCovariance;
3298  std::map<int, Transform> optPoses;
3299  if(!posesOut.empty() &&
3300  posesOut.begin()->first < _odomCachePoses.begin()->first)
3301  {
3302  optPoses = _graphOptimizer->optimize(posesOut.begin()->first, posesOut, edgeConstraintsOut, locOptCovariance);
3303  }
3304  else
3305  {
3306  UERROR("Invalid localization constraints");
3307  }
3308  _graphOptimizer->setPriorsIgnored(priorsIgnored); // set back
3309  for(std::map<int, Transform>::iterator iter=optPoses.begin(); iter!=optPoses.end(); ++iter)
3310  {
3311  UDEBUG("Opt %d %s", iter->first, iter->second.prettyPrint().c_str());
3312  }
3313 
3314  if(optPoses.empty())
3315  {
3316  UWARN("Optimization failed, rejecting localization!");
3317  rejectLocalization = true;
3318  }
3319  else
3320  {
3321  UINFO("Compute max graph errors...");
3322  const Link * maxLinearLink = 0;
3323  const Link * maxAngularLink = 0;
3325  optPoses,
3326  edgeConstraintsOut,
3327  maxLinearErrorRatio,
3328  maxAngularErrorRatio,
3329  maxLinearError,
3330  maxAngularError,
3331  &maxLinearLink,
3332  &maxAngularLink,
3334  if(maxLinearLink == 0 && maxAngularLink==0)
3335  {
3336  UWARN("Could not compute graph errors! Rejecting localization!");
3337  rejectLocalization = true;
3338  }
3339 
3340  if(maxLinearLink)
3341  {
3342  UINFO("Max optimization linear error = %f m (link %d->%d, var=%f, ratio error/std=%f, thr=%f)",
3343  maxLinearError,
3344  maxLinearLink->from(),
3345  maxLinearLink->to(),
3346  maxLinearLink->transVariance(),
3347  maxLinearError/sqrt(maxLinearLink->transVariance()),
3349  if(_optimizationMaxError > 0.0f && maxLinearErrorRatio > _optimizationMaxError)
3350  {
3351  UWARN("Rejecting localization (%d <-> %d) in this "
3352  "iteration because a wrong loop closure has been "
3353  "detected after graph optimization, resulting in "
3354  "a maximum graph error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). The "
3355  "maximum error ratio parameter \"%s\" is %f of std deviation.",
3356  localizationLinks.rbegin()->second.from(),
3357  localizationLinks.rbegin()->second.to(),
3358  maxLinearErrorRatio,
3359  maxLinearLink->from(),
3360  maxLinearLink->to(),
3361  maxLinearLink->type(),
3362  maxLinearError,
3363  sqrt(maxLinearLink->transVariance()),
3364  Parameters::kRGBDOptimizeMaxError().c_str(),
3366  rejectLocalization = true;
3367  }
3368  else if(_optimizationMaxError == 0.0f && maxLinearErrorRatio>100 && !_graphOptimizer->isRobust())
3369  {
3370  UERROR("Huge optimization error detected!"
3371  "Linear error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). You may consider "
3372  "enabling \"%s\" to reject those bad optimizations by setting it to a non null value!",
3373  maxLinearErrorRatio,
3374  maxLinearLink->from(),
3375  maxLinearLink->to(),
3376  maxLinearLink->type(),
3377  maxLinearError,
3378  sqrt(maxLinearLink->transVariance()),
3379  Parameters::kRGBDOptimizeMaxError().c_str());
3380  }
3381  }
3382  if(maxAngularLink)
3383  {
3384  UINFO("Max optimization angular error = %f deg (link %d->%d, var=%f, ratio error/std=%f, thr=%f)",
3385  maxAngularError*180.0f/CV_PI,
3386  maxAngularLink->from(),
3387  maxAngularLink->to(),
3388  maxAngularLink->rotVariance(),
3389  maxAngularError/sqrt(maxAngularLink->rotVariance()),
3391  if(_optimizationMaxError > 0.0f && maxAngularErrorRatio > _optimizationMaxError)
3392  {
3393  UWARN("Rejecting localization (%d <-> %d) in this "
3394  "iteration because a wrong loop closure has been "
3395  "detected after graph optimization, resulting in "
3396  "a maximum graph error ratio of %f (edge %d->%d, type=%d, abs error=%f deg, stddev=%f). The "
3397  "maximum error ratio parameter \"%s\" is %f of std deviation.",
3398  localizationLinks.rbegin()->second.from(),
3399  localizationLinks.rbegin()->second.to(),
3400  maxAngularErrorRatio,
3401  maxAngularLink->from(),
3402  maxAngularLink->to(),
3403  maxAngularLink->type(),
3404  maxAngularError*180.0f/CV_PI,
3405  sqrt(maxAngularLink->rotVariance()),
3406  Parameters::kRGBDOptimizeMaxError().c_str(),
3408  rejectLocalization = true;
3409  }
3410  else if(_optimizationMaxError == 0.0f && maxAngularErrorRatio>100 && !_graphOptimizer->isRobust())
3411  {
3412  UERROR("Huge optimization error detected!"
3413  "Angular error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). You may consider "
3414  "enabling \"%s\" to reject those bad optimizations by setting it to a non null value!",
3415  maxAngularErrorRatio,
3416  maxAngularLink->from(),
3417  maxAngularLink->to(),
3418  maxAngularLink->type(),
3419  maxAngularError*180.0f/CV_PI,
3420  sqrt(maxAngularLink->rotVariance()),
3421  Parameters::kRGBDOptimizeMaxError().c_str());
3422  }
3423  }
3424  }
3425 
3426  bool hasGlobalLoopClosuresOrLandmarks = false;
3427  if(rejectLocalization && !graph::filterLinks(constraints, Link::kLocalSpaceClosure, true).empty())
3428  {
3429  // Let's try again without local loop closures
3430  localizationLinks = graph::filterLinks(localizationLinks, Link::kLocalSpaceClosure);
3431  constraints = graph::filterLinks(constraints, Link::kLocalSpaceClosure);
3432  for(std::multimap<int, Link>::iterator iter=constraints.begin(); iter!=constraints.end() && !hasGlobalLoopClosuresOrLandmarks; ++iter)
3433  {
3434  hasGlobalLoopClosuresOrLandmarks =
3435  iter->second.type() == Link::kGlobalClosure ||
3436  iter->second.type() == Link::kLandmark;
3437  }
3438  if(hasGlobalLoopClosuresOrLandmarks && !localizationLinks.empty())
3439  {
3440  rejectLocalization = false;
3441  UWARN("Global and loop closures seem not tallying together, try again to optimize without local loop closures...");
3442  priorsIgnored = _graphOptimizer->priorsIgnored();
3443  UDEBUG("priorsIgnored was %s", priorsIgnored?"true":"false");
3444  _graphOptimizer->setPriorsIgnored(false); //temporary set false to use priors above to fix nodes of the map
3445  // If slam2d: get connected graph while keeping original roll,pitch,z values.
3446  _graphOptimizer->getConnectedGraph(signature->id(), poses, constraints, posesOut, edgeConstraintsOut);
3447  optPoses.clear();
3448  if(!posesOut.empty() &&
3449  posesOut.begin()->first < _odomCachePoses.begin()->first)
3450  {
3451  optPoses = _graphOptimizer->optimize(posesOut.begin()->first, posesOut, edgeConstraintsOut, locOptCovariance);
3452  }
3453  else
3454  {
3455  UERROR("Invalid localization constraints");
3456  }
3457  _graphOptimizer->setPriorsIgnored(priorsIgnored); // set back
3458  for(std::map<int, Transform>::iterator iter=optPoses.begin(); iter!=optPoses.end(); ++iter)
3459  {
3460  UDEBUG("Opt2 %d %s", iter->first, iter->second.prettyPrint().c_str());
3461  }
3462 
3463  if(optPoses.empty())
3464  {
3465  UWARN("Optimization failed, rejecting localization!");
3466  rejectLocalization = true;
3467  }
3468  else
3469  {
3470  UINFO("Compute max graph errors...");
3471  const Link * maxLinearLink = 0;
3472  const Link * maxAngularLink = 0;
3474  optPoses,
3475  edgeConstraintsOut,
3476  maxLinearErrorRatio,
3477  maxAngularErrorRatio,
3478  maxLinearError,
3479  maxAngularError,
3480  &maxLinearLink,
3481  &maxAngularLink,
3483  if(maxLinearLink == 0 && maxAngularLink==0)
3484  {
3485  UWARN("Could not compute graph errors! Rejecting localization!");
3486  rejectLocalization = true;
3487  }
3488 
3489  if(maxLinearLink)
3490  {
3491  UINFO("Max optimization linear error = %f m (link %d->%d, var=%f, ratio error/std=%f, thr=%f)",
3492  maxLinearError,
3493  maxLinearLink->from(),
3494  maxLinearLink->to(),
3495  maxLinearLink->transVariance(),
3496  maxLinearError/sqrt(maxLinearLink->transVariance()),
3498  if(_optimizationMaxError > 0.0f && maxLinearErrorRatio > _optimizationMaxError)
3499  {
3500  UWARN("Rejecting localization (%d <-> %d) in this "
3501  "iteration because a wrong loop closure has been "
3502  "detected after graph optimization, resulting in "
3503  "a maximum graph error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). The "
3504  "maximum error ratio parameter \"%s\" is %f of std deviation.",
3505  localizationLinks.rbegin()->second.from(),
3506  localizationLinks.rbegin()->second.to(),
3507  maxLinearErrorRatio,
3508  maxLinearLink->from(),
3509  maxLinearLink->to(),
3510  maxLinearLink->type(),
3511  maxLinearError,
3512  sqrt(maxLinearLink->transVariance()),
3513  Parameters::kRGBDOptimizeMaxError().c_str(),
3515  rejectLocalization = true;
3516  }
3517  else if(_optimizationMaxError == 0.0f && maxLinearErrorRatio>100 && !_graphOptimizer->isRobust())
3518  {
3519  UERROR("Huge optimization error detected!"
3520  "Linear error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). You may consider "
3521  "enabling \"%s\" to reject those bad optimizations by setting it to a non null value!",
3522  maxLinearErrorRatio,
3523  maxLinearLink->from(),
3524  maxLinearLink->to(),
3525  maxLinearLink->type(),
3526  maxLinearError,
3527  sqrt(maxLinearLink->transVariance()),
3528  Parameters::kRGBDOptimizeMaxError().c_str());
3529  }
3530  }
3531  if(maxAngularLink)
3532  {
3533  UINFO("Max optimization angular error = %f deg (link %d->%d, var=%f, ratio error/std=%f, thr=%f)",
3534  maxAngularError*180.0f/CV_PI,
3535  maxAngularLink->from(),
3536  maxAngularLink->to(),
3537  maxAngularLink->rotVariance(),
3538  maxAngularError/sqrt(maxAngularLink->rotVariance()),
3540  if(_optimizationMaxError > 0.0f && maxAngularErrorRatio > _optimizationMaxError)
3541  {
3542  UWARN("Rejecting localization (%d <-> %d) in this "
3543  "iteration because a wrong loop closure has been "
3544  "detected after graph optimization, resulting in "
3545  "a maximum graph error ratio of %f (edge %d->%d, type=%d, abs error=%f deg, stddev=%f). The "
3546  "maximum error ratio parameter \"%s\" is %f of std deviation.",
3547  localizationLinks.rbegin()->second.from(),
3548  localizationLinks.rbegin()->second.to(),
3549  maxAngularErrorRatio,
3550  maxAngularLink->from(),
3551  maxAngularLink->to(),
3552  maxAngularLink->type(),
3553  maxAngularError*180.0f/CV_PI,
3554  sqrt(maxAngularLink->rotVariance()),
3555  Parameters::kRGBDOptimizeMaxError().c_str(),
3557  rejectLocalization = true;
3558  }
3559  else if(_optimizationMaxError == 0.0f && maxAngularErrorRatio>100 && !_graphOptimizer->isRobust())
3560  {
3561  UERROR("Huge optimization error detected!"
3562  "Angular error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). You may consider "
3563  "enabling \"%s\" to reject those bad optimizations by setting it to a non null value!",
3564  maxAngularErrorRatio,
3565  maxAngularLink->from(),
3566  maxAngularLink->to(),
3567  maxAngularLink->type(),
3568  maxAngularError*180.0f/CV_PI,
3569  sqrt(maxAngularLink->rotVariance()),
3570  Parameters::kRGBDOptimizeMaxError().c_str());
3571  }
3572  }
3573  }
3574  }
3575  }
3576 
3577  if(!rejectLocalization)
3578  {
3579  if(hasGlobalLoopClosuresOrLandmarks)
3580  {
3581  // We successfully optimize the graph without local loop closures,
3582  // clear them as some of them may be wrong.
3583  size_t before = _odomCacheConstraints.size();
3585  if(before != _odomCacheConstraints.size())
3586  {
3587  UWARN("Successfully optimized without local loop closures! Clear them from local odometry cache. %ld/%ld have been removed.",
3588  before - _odomCacheConstraints.size(), before);
3589  }
3590  else
3591  {
3592  UWARN("Successfully optimized without local loop closures!");
3593  }
3594  }
3595 
3596  // Count how many localization links are in the constraints
3597  bool hadAlreadyLocalizationLinks = false;
3598  for(std::multimap<int, Link>::iterator iter=_odomCacheConstraints.begin();
3599  iter!=_odomCacheConstraints.end(); ++iter)
3600  {
3601  if(iter->second.type() == Link::kGlobalClosure ||
3602  iter->second.type() == Link::kLocalSpaceClosure ||
3603  iter->second.type() == Link::kLocalTimeClosure ||
3604  iter->second.type() == Link::kUserClosure ||
3605  iter->second.type() == Link::kNeighborMerged ||
3606  iter->second.type() == Link::kLandmark)
3607  {
3608  hadAlreadyLocalizationLinks = true;
3609  break;
3610  }
3611  }
3612 
3613  // update localization links
3614  UASSERT(uContains(optPoses, signature->id()));
3615  Transform newOptPoseInv = optPoses.at(signature->id()).inverse();
3616  for(std::multimap<int, Link>::iterator iter=localizationLinks.begin(); iter!=localizationLinks.end(); ++iter)
3617  {
3619  {
3620  // Add original link without optimization
3621  UDEBUG("Adding new odom cache constraint %d->%d (%s)",
3622  iter->second.from(), iter->second.to(), iter->second.transform().prettyPrint().c_str());
3623  }
3624  else
3625  {
3626  // Adjust with optimized poses, this will smooth the localization
3627  UASSERT(uContains(optPoses, iter->first));
3628  Transform newT = newOptPoseInv * optPoses.at(iter->first);
3629  UDEBUG("Adjusted localization link %d->%d after optimization", iter->second.from(), iter->second.to());
3630  UDEBUG("from %s", iter->second.transform().prettyPrint().c_str());
3631  UDEBUG(" to %s", newT.prettyPrint().c_str());
3632  iter->second.setTransform(newT);
3633 
3634  // Update link in the referred signatures
3635  if(iter->first > 0)
3636  _memory->updateLink(iter->second, false);
3637  }
3638 
3639  _odomCacheConstraints.insert(std::make_pair(signature->id(), iter->second));
3640  }
3641 
3642  _odomCacheConstraints.insert(selfLinks.begin(), selfLinks.end());
3643 
3644  // At least 2 localizations at 2 different time required
3645  if(hadAlreadyLocalizationLinks || _maxOdomCacheSize == 0)
3646  {
3647  UINFO("Update localization");
3649  {
3650  // update all previous nodes
3651  // Normally _mapCorrection should be identity, but if _optimizeFromGraphEnd
3652  // parameters just changed state, we should put back all poses without map correction.
3653  Transform oldPose = _optimizedPoses.at(localizationLinks.rbegin()->first);
3654  Transform mapCorrectionInv = _mapCorrection.inverse();
3655  Transform u = signature->getPose() * localizationLinks.rbegin()->second.transform();
3656  if(_graphOptimizer->gravitySigma() > 0)
3657  {
3658  // Adjust transform with gravity
3659  Transform transform = localizationLinks.rbegin()->second.transform();
3660  int loopId = localizationLinks.rbegin()->first;
3661  int landmarkId = 0;
3662  if(loopId<0)
3663  {
3664  //For landmarks, use transform against other node looking the landmark
3665  // (because we don't assume that landmarks are aligned with gravity)
3666  landmarkId = loopId;
3667  UASSERT(landmarksDetected.find(landmarkId) != landmarksDetected.end() &&
3668  !landmarksDetected.at(landmarkId).empty());
3669  loopId = *landmarksDetected.at(landmarkId).begin();
3670  }
3671 
3672  const Signature * loopS = _memory->getSignature(loopId);
3673  UASSERT(loopS !=0);
3674  std::multimap<int, Link>::const_iterator iterGravityLoop = graph::findLink(loopS->getLinks(), loopS->id(), loopS->id(), false, Link::kGravity);
3675  std::multimap<int, Link>::const_iterator iterGravitySign = graph::findLink(signature->getLinks(), signature->id(), signature->id(), false, Link::kGravity);
3676  if(iterGravityLoop!=loopS->getLinks().end() &&
3677  iterGravitySign!=signature->getLinks().end())
3678  {
3679  float roll,pitch,yaw;
3680  if(landmarkId < 0)
3681  {
3682  iterGravityLoop->second.transform().getEulerAngles(roll, pitch, yaw);
3683  Transform gravityCorr = Transform(_optimizedPoses.at(loopS->id()).x(),
3684  _optimizedPoses.at(loopS->id()).y(),
3685  _optimizedPoses.at(loopS->id()).z(),
3686  roll, pitch, _optimizedPoses.at(loopS->id()).theta()) * _optimizedPoses.at(loopS->id()).inverse();
3687  (gravityCorr * _optimizedPoses.at(landmarkId)).getEulerAngles(roll,pitch,yaw);
3688  }
3689  else
3690  {
3691  iterGravityLoop->second.transform().getEulerAngles(roll, pitch, yaw);
3692  }
3693  Transform targetRotation = iterGravitySign->second.transform().rotation()*transform.rotation();
3694  targetRotation = Transform(0,0,0,roll,pitch,targetRotation.theta());
3695  Transform error = transform.rotation().inverse() * iterGravitySign->second.transform().rotation().inverse() * targetRotation;
3696  transform *= error;
3697  u = signature->getPose() * transform;
3698  }
3699  else if(iterGravityLoop!=loopS->getLinks().end() ||
3700  iterGravitySign!=signature->getLinks().end())
3701  {
3702  UWARN("Gravity link not found for %d or %d, localization won't be corrected with gravity.", loopId, signature->id());
3703  }
3704  }
3705  Transform up = u * oldPose.inverse();
3706  if(_graphOptimizer->isSlam2d())
3707  {
3708  // in case of 3d landmarks, transform constraint to 2D
3709  up.to3DoF();
3710  }
3711  for(std::map<int, Transform>::iterator iter=_optimizedPoses.begin(); iter!=_optimizedPoses.end(); ++iter)
3712  {
3713  iter->second = mapCorrectionInv * up * iter->second;
3714  }
3715  _optimizedPoses.at(signature->id()) = signature->getPose();
3716  }
3717  else
3718  {
3719  Transform newPose = _optimizedPoses.at(localizationLinks.rbegin()->first) * localizationLinks.rbegin()->second.transform().inverse();
3720  UDEBUG("newPose=%s", newPose.prettyPrint().c_str());
3721  if(_graphOptimizer->isSlam2d() && signature->getPose().is3DoF())
3722  {
3723  // in case of 3d landmarks, transform constraint to 2D
3724  newPose = newPose.to3DoF();
3725  UDEBUG("newPose 2D=%s", newPose.prettyPrint().c_str());
3726  }
3727  else if(_graphOptimizer->gravitySigma() > 0)
3728  {
3729  // Adjust transform with gravity
3730  std::multimap<int, Link>::const_iterator iterGravitySign = graph::findLink(signature->getLinks(), signature->id(), signature->id(), false, Link::kGravity);
3731  if(iterGravitySign!=signature->getLinks().end())
3732  {
3733  Transform transform = localizationLinks.rbegin()->second.transform();
3734  float roll,pitch,yaw;
3735  float tmp1,tmp2;
3736  UDEBUG("Gravity link = %s", iterGravitySign->second.transform().prettyPrint().c_str());
3737  _optimizedPoses.at(localizationLinks.rbegin()->first).getEulerAngles(roll, pitch, yaw);
3738  Transform targetRotation = iterGravitySign->second.transform().rotation()*transform.rotation();
3739  targetRotation = Transform(0,0,0,roll,pitch,targetRotation.theta());
3740  Transform error = transform.rotation().inverse() * iterGravitySign->second.transform().rotation().inverse() * targetRotation;
3741  transform *= error;
3742  newPose = _optimizedPoses.at(localizationLinks.rbegin()->first) * transform.inverse();
3743  iterGravitySign->second.transform().getEulerAngles(roll, pitch, tmp1);
3744  newPose.getEulerAngles(tmp1, tmp2, yaw);
3745  newPose = Transform(newPose.x(), newPose.y(), newPose.z(), roll, pitch, yaw);
3746  UDEBUG("newPose gravity=%s", newPose.prettyPrint().c_str());
3747  }
3748  else if(iterGravitySign!=signature->getLinks().end())
3749  {
3750  UWARN("Gravity link not found for %d, localization won't be corrected with gravity.", signature->id());
3751  }
3752  }
3753  _optimizedPoses.at(signature->id()) = newPose;
3754  }
3755  _localizationCovariance = locOptCovariance.empty()?localizationLinks.rbegin()->second.infMatrix().inv():locOptCovariance;
3756  }
3757  else //delayed localization (wait for more than 1 link)
3758  {
3759  UWARN("Localization was good, but waiting for another one to be more accurate (%s>0)", Parameters::kRGBDMaxOdomCacheSize().c_str());
3760  delayedLocalization = true;
3761  rejectLocalization = true;
3762  }
3763  }
3764  }
3765 
3766  if(rejectLocalization)
3767  {
3768  _loopClosureHypothesis.first = 0;
3769  lastProximitySpaceClosureId = 0;
3770  rejectedLoopClosure = true;
3771  }
3772  }
3773  else
3774  {
3775  UINFO("Update map correction");
3776  std::map<int, Transform> poses = _optimizedPoses;
3777 
3778  // if _optimizeFromGraphEnd parameter just changed state, don't use optimized poses as guess
3780  {
3781  UWARN("Optimization: clearing guess poses as %s has changed state, now %s",
3782  Parameters::kRGBDOptimizeFromGraphEnd().c_str(), _optimizeFromGraphEnd?"true":"false");
3783  poses.clear();
3785  }
3786 
3787  std::multimap<int, Link> constraints;
3788  cv::Mat covariance;
3789  optimizeCurrentMap(signature->id(), false, poses, covariance, &constraints, &optimizationError, &optimizationIterations);
3790 
3791  // Check added loop closures have broken the graph
3792  // (in case of wrong loop closures).
3793  bool updateConstraints = true;
3794  if(poses.empty())
3795  {
3796  UWARN("Graph optimization failed! Rejecting last loop closures added.");
3797  for(std::list<std::pair<int, int> >::iterator iter=loopClosureLinksAdded.begin(); iter!=loopClosureLinksAdded.end(); ++iter)
3798  {
3799  _memory->removeLink(iter->first, iter->second);
3800  UWARN("Loop closure %d->%d rejected!", iter->first, iter->second);
3801  }
3802  updateConstraints = false;
3803  _loopClosureHypothesis.first = 0;
3804  lastProximitySpaceClosureId = 0;
3805  rejectedLoopClosure = true;
3806  }
3807  else if(_memory->isIncremental() &&
3808  loopClosureLinksAdded.size() &&
3809  optimizationIterations > 0 &&
3810  constraints.size())
3811  {
3812  UINFO("Compute max graph errors...");
3813  const Link * maxLinearLink = 0;
3814  const Link * maxAngularLink = 0;
3816  poses,
3817  constraints,
3818  maxLinearErrorRatio,
3819  maxAngularErrorRatio,
3820  maxLinearError,
3821  maxAngularError,
3822  &maxLinearLink,
3823  &maxAngularLink);
3824  if(maxLinearLink == 0 && maxAngularLink==0)
3825  {
3826  UWARN("Could not compute graph errors! Wrong loop closures could be accepted!");
3827  }
3828 
3829  bool reject = false;
3830  if(maxLinearLink)
3831  {
3832  UINFO("Max optimization linear error = %f m (link %d->%d, var=%f, ratio error/std=%f)", maxLinearError, maxLinearLink->from(), maxLinearLink->to(), maxLinearLink->transVariance(), maxLinearError/sqrt(maxLinearLink->transVariance()));
3833  if(_optimizationMaxError > 0.0f && maxLinearErrorRatio > _optimizationMaxError)
3834  {
3835  UWARN("Rejecting all added loop closures (%d, first is %d <-> %d) in this "
3836  "iteration because a wrong loop closure has been "
3837  "detected after graph optimization, resulting in "
3838  "a maximum graph error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). The "
3839  "maximum error ratio parameter \"%s\" is %f of std deviation.",
3840  (int)loopClosureLinksAdded.size(),
3841  loopClosureLinksAdded.front().first,
3842  loopClosureLinksAdded.front().second,
3843  maxLinearErrorRatio,
3844  maxLinearLink->from(),
3845  maxLinearLink->to(),
3846  maxLinearLink->type(),
3847  maxLinearError,
3848  sqrt(maxLinearLink->transVariance()),
3849  Parameters::kRGBDOptimizeMaxError().c_str(),
3851  reject = true;
3852  }
3853  else if(_optimizationMaxError == 0.0f && maxLinearErrorRatio>100 && !_graphOptimizer->isRobust())
3854  {
3855  UERROR("Huge optimization error detected!"
3856  "Linear error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). You may consider "
3857  "enabling \"%s\" to reject those bad optimizations by setting it to a non null value!",
3858  maxLinearErrorRatio,
3859  maxLinearLink->from(),
3860  maxLinearLink->to(),
3861  maxLinearLink->type(),
3862  maxLinearError,
3863  sqrt(maxLinearLink->transVariance()),
3864  Parameters::kRGBDOptimizeMaxError().c_str());
3865  }
3866  }
3867  if(maxAngularLink)
3868  {
3869  UINFO("Max optimization angular error = %f deg (link %d->%d, var=%f, ratio error/std=%f)", maxAngularError*180.0f/CV_PI, maxAngularLink->from(), maxAngularLink->to(), maxAngularLink->rotVariance(), maxAngularError/sqrt(maxAngularLink->rotVariance()));
3870  if(_optimizationMaxError > 0.0f && maxAngularErrorRatio > _optimizationMaxError)
3871  {
3872  UWARN("Rejecting all added loop closures (%d, first is %d <-> %d) in this "
3873  "iteration because a wrong loop closure has been "
3874  "detected after graph optimization, resulting in "
3875  "a maximum graph error ratio of %f (edge %d->%d, type=%d, abs error=%f deg, stddev=%f). The "
3876  "maximum error ratio parameter \"%s\" is %f of std deviation.",
3877  (int)loopClosureLinksAdded.size(),
3878  loopClosureLinksAdded.front().first,
3879  loopClosureLinksAdded.front().second,
3880  maxAngularErrorRatio,
3881  maxAngularLink->from(),
3882  maxAngularLink->to(),
3883  maxAngularLink->type(),
3884  maxAngularError*180.0f/CV_PI,
3885  sqrt(maxAngularLink->rotVariance()),
3886  Parameters::kRGBDOptimizeMaxError().c_str(),
3888  reject = true;
3889  }
3890  else if(_optimizationMaxError == 0.0f && maxAngularErrorRatio>100 && !_graphOptimizer->isRobust())
3891  {
3892  UERROR("Huge optimization error detected!"
3893  "Angular error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). You may consider "
3894  "enabling \"%s\" to reject those bad optimizations by setting it to a non null value!",
3895  maxAngularErrorRatio,
3896  maxAngularLink->from(),
3897  maxAngularLink->to(),
3898  maxAngularLink->type(),
3899  maxAngularError*180.0f/CV_PI,
3900  sqrt(maxAngularLink->rotVariance()),
3901  Parameters::kRGBDOptimizeMaxError().c_str());
3902  }
3903  }
3904 
3905  if(reject)
3906  {
3907  for(std::list<std::pair<int, int> >::iterator iter=loopClosureLinksAdded.begin(); iter!=loopClosureLinksAdded.end(); ++iter)
3908  {
3909  _memory->removeLink(iter->first, iter->second);
3910  UWARN("Loop closure %d->%d rejected!", iter->first, iter->second);
3911  }
3912  updateConstraints = false;
3913  _loopClosureHypothesis.first = 0;
3914  lastProximitySpaceClosureId = 0;
3915  rejectedLoopClosure = true;
3916  }
3917  }
3918 
3919  if(updateConstraints)
3920  {
3921  UINFO("Updated local map (old size=%d, new size=%d)", (int)_optimizedPoses.size(), (int)poses.size());
3922  _optimizedPoses = poses;
3923  _constraints = constraints;
3924  _localizationCovariance = covariance;
3925  }
3926  }
3927 
3928  // Update map correction, it should be identify when optimizing from the last node
3929  UASSERT(_optimizedPoses.find(signature->id()) != _optimizedPoses.end());
3930  if(fakeOdom && _mapCorrectionBackup.isNull())
3931  {
3933  }
3934  previousMapCorrection = _mapCorrection;
3935  _mapCorrection = _optimizedPoses.at(signature->id()) * signature->getPose().inverse();
3936  // Update statistics about the closest node in the graph using the actual loop closure
3938  {
3939  int closestNode = _loopClosureHypothesis.first>0?_loopClosureHypothesis.first:lastProximitySpaceClosureId;
3940  if(closestNode>0)
3941  {
3942  distanceToClosestNodeInTheGraph = _lastLocalizationPose.getDistance(_optimizedPoses.at(closestNode));
3943  UDEBUG("Last localization pose = %s, updated closest node=%d (%f m)", _lastLocalizationPose.prettyPrint().c_str(), closestNode, distanceToClosestNodeInTheGraph);
3944  angleToClosestNodeInTheGraph = (_lastLocalizationPose.inverse() * _optimizedPoses.at(closestNode)).getAngle();
3945  }
3946  }
3947  _lastLocalizationPose = _optimizedPoses.at(signature->id()); // update
3949  {
3950  bool hasPrior = signature->hasLink(signature->id());
3952  {
3953  for(std::multimap<int, Link>::reverse_iterator iter=_constraints.rbegin(); !hasPrior && iter!=_constraints.rend(); ++iter)
3954  {
3955  if(iter->second.type() == Link::kPosePrior)
3956  {
3957  hasPrior = true;
3958  }
3959  }
3960  }
3961  if((!hasPrior || _graphOptimizer->priorsIgnored()) && _graphOptimizer->gravitySigma()==0.0f)
3962  {
3963  UERROR("Map correction should be identity when optimizing from the last node. T=%s", _mapCorrection.prettyPrint().c_str());
3964  }
3965  }
3966  }
3967  int newLocId = _loopClosureHypothesis.first>0?_loopClosureHypothesis.first:lastProximitySpaceClosureId>0?lastProximitySpaceClosureId:0;
3968  _lastLocalizationNodeId = newLocId!=0?newLocId:_lastLocalizationNodeId;
3969  if(newLocId==0 && !landmarksDetected.empty())
3970  {
3971  std::map<int, std::set<int> >::const_iterator iter = _memory->getLandmarksIndex().find(landmarksDetected.begin()->first);
3972  if(iter!=_memory->getLandmarksIndex().end())
3973  {
3974  if(iter->second.size() && *iter->second.begin()!=signature->id())
3975  {
3976  _lastLocalizationNodeId = *iter->second.begin();
3977  }
3978  }
3979  }
3980 
3981  timeMapOptimization = timer.ticks();
3982  ULOGGER_INFO("timeMapOptimization=%fs", timeMapOptimization);
3983 
3984  //============================================================
3985  // Prepare statistics
3986  //============================================================
3987  // Data used for the statistics event and for the log files
3988  int dictionarySize = 0;
3989  int refWordsCount = 0;
3990  int refUniqueWordsCount = 0;
3991  int lcHypothesisReactivated = 0;
3992  float rehearsalValue = uValue(statistics_.data(), Statistics::kMemoryRehearsal_sim(), 0.0f);
3993  int rehearsalMaxId = (int)uValue(statistics_.data(), Statistics::kMemoryRehearsal_merged(), 0.0f);
3994  sLoop = _memory->getSignature(_loopClosureHypothesis.first?_loopClosureHypothesis.first:lastProximitySpaceClosureId?lastProximitySpaceClosureId:_highestHypothesis.first);
3995  if(sLoop)
3996  {
3997  lcHypothesisReactivated = sLoop->isSaved()?1.0f:0.0f;
3998  }
3999  dictionarySize = (int)_memory->getVWDictionary()->getVisualWords().size();
4000  refWordsCount = (int)signature->getWords().size();
4001  refUniqueWordsCount = (int)uUniqueKeys(signature->getWords()).size();
4002 
4003  if(_graphOptimizer->isSlam2d() && _localizationCovariance.total() == 36)
4004  {
4005  // set very small
4009  }
4010 
4011  // Posterior is empty if a bad signature is detected
4012  float vpHypothesis = posterior.size()?posterior.at(Memory::kIdVirtual):0.0f;
4013  int loopId = _loopClosureHypothesis.first>0?_loopClosureHypothesis.first:lastProximitySpaceClosureId;
4014 
4015  // prepare statistics
4017  {
4018  ULOGGER_INFO("sending stats...");
4019  statistics_.setRefImageId(_memory->getLastSignatureId()); // Use last id from Memory (in case of rehearsal)
4020  statistics_.setRefImageMapId(signature->mapId());
4021  statistics_.setStamp(data.stamp());
4023  {
4026  ULOGGER_INFO("Loop closure detected! With id=%d", _loopClosureHypothesis.first);
4027  }
4028 
4029  if(_publishStats)
4030  {
4031  ULOGGER_INFO("send all stats...");
4033 
4034  statistics_.addStatistic(Statistics::kLoopAccepted_hypothesis_id(), _loopClosureHypothesis.first);
4035  statistics_.addStatistic(Statistics::kLoopSuppressed_hypothesis_id(), loopIdSuppressedByProximity);
4036  statistics_.addStatistic(Statistics::kLoopHighest_hypothesis_id(), _highestHypothesis.first);
4037  statistics_.addStatistic(Statistics::kLoopHighest_hypothesis_value(), _highestHypothesis.second);
4038  statistics_.addStatistic(Statistics::kLoopHypothesis_reactivated(), lcHypothesisReactivated);
4039  statistics_.addStatistic(Statistics::kLoopVp_hypothesis(), vpHypothesis);
4040  statistics_.addStatistic(Statistics::kLoopReactivate_id(), retrievalId);
4041  statistics_.addStatistic(Statistics::kLoopHypothesis_ratio(), hypothesisRatio);
4042  statistics_.addStatistic(Statistics::kLoopVisual_inliers(), loopClosureVisualInliers);
4043  statistics_.addStatistic(Statistics::kLoopVisual_inliers_ratio(), loopClosureVisualInliersRatio);
4044  statistics_.addStatistic(Statistics::kLoopVisual_matches(), loopClosureVisualMatches);
4045  statistics_.addStatistic(Statistics::kLoopLinear_variance(), loopClosureLinearVariance);
4046  statistics_.addStatistic(Statistics::kLoopAngular_variance(), loopClosureAngularVariance);
4047  statistics_.addStatistic(Statistics::kLoopLast_id(), _memory->getLastGlobalLoopClosureId());
4048  statistics_.addStatistic(Statistics::kLoopOptimization_max_error(), maxLinearError);
4049  statistics_.addStatistic(Statistics::kLoopOptimization_max_error_ratio(), maxLinearErrorRatio);
4050  statistics_.addStatistic(Statistics::kLoopOptimization_max_ang_error(), maxAngularError*180.0f/M_PI);
4051  statistics_.addStatistic(Statistics::kLoopOptimization_max_ang_error_ratio(), maxAngularErrorRatio);
4052  statistics_.addStatistic(Statistics::kLoopOptimization_error(), optimizationError);
4053  statistics_.addStatistic(Statistics::kLoopOptimization_iterations(), optimizationIterations);
4054  statistics_.addStatistic(Statistics::kLoopLandmark_detected(), landmarksDetected.empty()?0:-landmarksDetected.begin()->first);
4055  statistics_.addStatistic(Statistics::kLoopLandmark_detected_node_ref(), landmarksDetected.empty() || landmarksDetected.begin()->second.empty()?0:*landmarksDetected.begin()->second.begin());
4056  statistics_.addStatistic(Statistics::kLoopVisual_inliers_mean_dist(), loopClosureVisualInliersMeanDist);
4057  statistics_.addStatistic(Statistics::kLoopVisual_inliers_distribution(), loopClosureVisualInliersDistribution);
4058 
4059  statistics_.addStatistic(Statistics::kProximityTime_detections(), proximityDetectionsInTimeFound);
4060  statistics_.addStatistic(Statistics::kProximitySpace_detections_added_visually(), proximityDetectionsAddedVisually);
4061  statistics_.addStatistic(Statistics::kProximitySpace_detections_added_icp_multi(), proximityDetectionsAddedByICPMulti);
4062  statistics_.addStatistic(Statistics::kProximitySpace_detections_added_icp_global(), proximityDetectionsAddedByICPGlobal);
4063  statistics_.addStatistic(Statistics::kProximitySpace_paths(), proximitySpacePaths);
4064  statistics_.addStatistic(Statistics::kProximitySpace_visual_paths_checked(), localVisualPathsChecked);
4065  statistics_.addStatistic(Statistics::kProximitySpace_scan_paths_checked(), localScanPathsChecked);
4066  statistics_.addStatistic(Statistics::kProximitySpace_last_detection_id(), lastProximitySpaceClosureId);
4067  statistics_.setProximityDetectionId(lastProximitySpaceClosureId);
4068  statistics_.setProximityDetectionMapId(_memory->getMapId(lastProximitySpaceClosureId));
4069 
4070  statistics_.addStatistic(Statistics::kLoopId(), loopId);
4071  statistics_.addStatistic(Statistics::kLoopMap_id(), (loopId>0 && sLoop)?sLoop->mapId():-1);
4072 
4073  statistics_.addStatistic(Statistics::kLoopDistance_since_last_loc(), _distanceTravelledSinceLastLocalization);
4074 
4075  float x,y,z,roll,pitch,yaw;
4076  if(_loopClosureHypothesis.first || lastProximitySpaceClosureId || (!rejectedLoopClosure && !landmarksDetected.empty()))
4077  {
4078  if(_loopClosureHypothesis.first || lastProximitySpaceClosureId)
4079  {
4080  // Loop closure transform
4081  UASSERT(sLoop);
4082  std::multimap<int, Link>::const_iterator loopIter = sLoop->getLinks().find(signature->id());
4083  UASSERT(loopIter!=sLoop->getLinks().end());
4084  UINFO("Set loop closure transform = %s", loopIter->second.transform().prettyPrint().c_str());
4085  statistics_.setLoopClosureTransform(loopIter->second.transform());
4086 
4087  statistics_.addStatistic(Statistics::kLoopVisual_words(), sLoop->getWords().size());
4088 
4089  // if ground truth exists, compute localization error
4090  if(!sLoop->getGroundTruthPose().isNull() && !signature->getGroundTruthPose().isNull())
4091  {
4092  Transform transformGT = sLoop->getGroundTruthPose().inverse() * signature->getGroundTruthPose();
4093  Transform error = loopIter->second.transform().inverse() * transformGT;
4094  statistics_.addStatistic(Statistics::kGtLocalization_linear_error(), error.getNorm());
4095  statistics_.addStatistic(Statistics::kGtLocalization_angular_error(), error.getAngle(1,0,0)*180/M_PI);
4096  }
4097  }
4098 
4100 
4101  statistics_.addStatistic(Statistics::kLoopMapToOdom_norm(), _mapCorrection.getNorm());
4102  statistics_.addStatistic(Statistics::kLoopMapToOdom_angle(), _mapCorrection.getAngle()*180.0f/M_PI);
4104  statistics_.addStatistic(Statistics::kLoopMapToOdom_x(), x);
4105  statistics_.addStatistic(Statistics::kLoopMapToOdom_y(), y);
4106  statistics_.addStatistic(Statistics::kLoopMapToOdom_z(), z);
4107  statistics_.addStatistic(Statistics::kLoopMapToOdom_roll(), roll*180.0f/M_PI);
4108  statistics_.addStatistic(Statistics::kLoopMapToOdom_pitch(), pitch*180.0f/M_PI);
4109  statistics_.addStatistic(Statistics::kLoopMapToOdom_yaw(), yaw*180.0f/M_PI);
4110 
4111  // Odom correction (actual odometry pose change), ignore correction from first localization
4112  if(!odomPose.isNull() && !previousMapCorrection.isNull() && !previousMapCorrection.isIdentity())
4113  {
4114  Transform odomCorrection = (previousMapCorrection*odomPose).inverse()*_mapCorrection*odomPose;
4115  statistics_.addStatistic(Statistics::kLoopOdom_correction_norm(), odomCorrection.getNorm());
4116  statistics_.addStatistic(Statistics::kLoopOdom_correction_angle(), odomCorrection.getAngle()*180.0f/M_PI);
4117  odomCorrection.getTranslationAndEulerAngles(x, y, z, roll, pitch, yaw);
4118  statistics_.addStatistic(Statistics::kLoopOdom_correction_x(), x);
4119  statistics_.addStatistic(Statistics::kLoopOdom_correction_y(), y);
4120  statistics_.addStatistic(Statistics::kLoopOdom_correction_z(), z);
4121  statistics_.addStatistic(Statistics::kLoopOdom_correction_roll(), roll*180.0f/M_PI);
4122  statistics_.addStatistic(Statistics::kLoopOdom_correction_pitch(), pitch*180.0f/M_PI);
4123  statistics_.addStatistic(Statistics::kLoopOdom_correction_yaw(), yaw*180.0f/M_PI);
4124  }
4125  }
4127  {
4129  statistics_.addStatistic(Statistics::kLoopMapToBase_x(), x);
4130  statistics_.addStatistic(Statistics::kLoopMapToBase_y(), y);
4131  statistics_.addStatistic(Statistics::kLoopMapToBase_z(), z);
4132  statistics_.addStatistic(Statistics::kLoopMapToBase_roll(), roll*180.0f/M_PI);
4133  statistics_.addStatistic(Statistics::kLoopMapToBase_pitch(), pitch*180.0f/M_PI);
4134  statistics_.addStatistic(Statistics::kLoopMapToBase_yaw(), yaw*180.0f/M_PI);
4135  UINFO("Localization pose = %s", _lastLocalizationPose.prettyPrint().c_str());
4136 
4137  if(_localizationCovariance.total()==36)
4138  {
4139  double varLin = _graphOptimizer->isSlam2d()?
4140  std::max(_localizationCovariance.at<double>(0,0), _localizationCovariance.at<double>(1,1)):
4141  uMax3(_localizationCovariance.at<double>(0,0), _localizationCovariance.at<double>(1,1), _localizationCovariance.at<double>(2,2));
4142 
4143  statistics_.addStatistic(Statistics::kLoopMapToBase_lin_std(), sqrt(varLin));
4144  statistics_.addStatistic(Statistics::kLoopMapToBase_lin_var(), varLin);
4145  }
4146  }
4147 
4149  UINFO("Set map correction = %s", _mapCorrection.prettyPrint().c_str());
4151 
4152  // timings...
4153  statistics_.addStatistic(Statistics::kTimingMemory_update(), timeMemoryUpdate*1000);
4154  statistics_.addStatistic(Statistics::kTimingNeighbor_link_refining(), timeNeighborLinkRefining*1000);
4155  statistics_.addStatistic(Statistics::kTimingProximity_by_time(), timeProximityByTimeDetection*1000);
4156  statistics_.addStatistic(Statistics::kTimingProximity_by_space_search(), timeProximityBySpaceSearch*1000);
4157  statistics_.addStatistic(Statistics::kTimingProximity_by_space_visual(), timeProximityBySpaceVisualDetection*1000);
4158  statistics_.addStatistic(Statistics::kTimingProximity_by_space(), timeProximityBySpaceDetection*1000);
4159  statistics_.addStatistic(Statistics::kTimingReactivation(), timeReactivations*1000);
4160  statistics_.addStatistic(Statistics::kTimingAdd_loop_closure_link(), timeAddLoopClosureLink*1000);
4161  statistics_.addStatistic(Statistics::kTimingMap_optimization(), timeMapOptimization*1000);
4162  statistics_.addStatistic(Statistics::kTimingLikelihood_computation(), timeLikelihoodCalculation*1000);
4163  statistics_.addStatistic(Statistics::kTimingPosterior_computation(), timePosteriorCalculation*1000);
4164  statistics_.addStatistic(Statistics::kTimingHypotheses_creation(), timeHypothesesCreation*1000);
4165  statistics_.addStatistic(Statistics::kTimingHypotheses_validation(), timeHypothesesValidation*1000);
4166  statistics_.addStatistic(Statistics::kTimingCleaning_neighbors(), timeCleaningNeighbors*1000);
4167 
4168  // retrieval
4169  statistics_.addStatistic(Statistics::kMemorySignatures_retrieved(), (float)signaturesRetrieved.size());
4170 
4171  // Feature specific parameters
4172  statistics_.addStatistic(Statistics::kKeypointDictionary_size(), dictionarySize);
4173  statistics_.addStatistic(Statistics::kKeypointCurrent_frame(), refWordsCount);
4174  statistics_.addStatistic(Statistics::kKeypointIndexed_words(), _memory->getVWDictionary()->getIndexedWordsCount());
4175  statistics_.addStatistic(Statistics::kKeypointIndex_memory_usage(), _memory->getVWDictionary()->getIndexMemoryUsed());
4176 
4177  //Epipolar geometry constraint
4178  statistics_.addStatistic(Statistics::kLoopRejectedHypothesis(), rejectedLoopClosure?1.0f:0);
4179 
4180  statistics_.addStatistic(Statistics::kMemorySmall_movement(), smallDisplacement?1.0f:0);
4181  statistics_.addStatistic(Statistics::kMemoryDistance_travelled(), _distanceTravelled);
4182  statistics_.addStatistic(Statistics::kMemoryFast_movement(), tooFastMovement?1.0f:0);
4183  statistics_.addStatistic(Statistics::kMemoryNew_landmark(), addedNewLandmark?1.0f:0);
4184 
4185  if(distanceToClosestNodeInTheGraph>0.0)
4186  {
4187  statistics_.addStatistic(Statistics::kMemoryClosest_node_distance(), distanceToClosestNodeInTheGraph);
4188  statistics_.addStatistic(Statistics::kMemoryClosest_node_angle(), angleToClosestNodeInTheGraph);
4189  }
4190 
4191  if(_publishRAMUsage)
4192  {
4193  UTimer ramTimer;
4194  statistics_.addStatistic(Statistics::kMemoryRAM_usage(), UProcessInfo::getMemoryUsage()/(1024*1024));
4195  long estimatedMemoryUsage = sizeof(Rtabmap);
4196  estimatedMemoryUsage += _optimizedPoses.size() * (sizeof(int) + sizeof(Transform) + 12 * sizeof(float) + sizeof(std::map<int, Transform>::iterator)) + sizeof(std::map<int, Transform>);
4197  estimatedMemoryUsage += _constraints.size() * (sizeof(int) + sizeof(Transform) + 12 * sizeof(float) + sizeof(cv::Mat) + 36 * sizeof(double) + sizeof(std::map<int, Link>::iterator)) + sizeof(std::map<int, Link>);
4198  estimatedMemoryUsage += _memory->getMemoryUsed();
4199  estimatedMemoryUsage += _bayesFilter->getMemoryUsed();
4200  estimatedMemoryUsage += _parameters.size()*(sizeof(std::string)*2+sizeof(ParametersMap::iterator)) + sizeof(ParametersMap);
4201  statistics_.addStatistic(Statistics::kMemoryRAM_estimated(), (float)(estimatedMemoryUsage/(1024*1024)));//MB
4202  statistics_.addStatistic(Statistics::kTimingRAM_estimation(), ramTimer.ticks()*1000);
4203  }
4204 
4206  {
4207  // Child count by parent signature on the root of the memory ... for statistics
4208  statistics_.setWeights(weights);
4209  if(_publishPdf)
4210  {
4211  statistics_.setPosterior(posterior);
4212  }
4213  if(_publishLikelihood)
4214  {
4215  statistics_.setLikelihood(likelihood);
4216  statistics_.setRawLikelihood(rawLikelihood);
4217  }
4218  }
4219 
4221 
4222  // Path
4223  if(_path.size())
4224  {
4227  }
4228  }
4229 
4230  timeStatsCreation = timer.ticks();
4231  ULOGGER_INFO("Time creating stats = %f...", timeStatsCreation);
4232  }
4233 
4234  Signature lastSignatureData = *signature;
4235  Transform lastSignatureLocalizedPose;
4236  if(_optimizedPoses.find(signature->id()) != _optimizedPoses.end())
4237  {
4238  lastSignatureLocalizedPose = _optimizedPoses.at(signature->id());
4239  }
4241  {
4242  lastSignatureData.sensorData().clearCompressedData();
4243  lastSignatureData.sensorData().clearRawData();
4244  }
4245  if(!_rawDataKept)
4246  {
4247  _memory->removeRawData(signature->id(), true, !_neighborLinkRefining && !_proximityBySpace, true);
4248  }
4249 
4250  // Localization mode and saving localization data: save odometry covariance in a prior link
4251  // so that DBReader can republish the covariance of localization data
4252  if(!_memory->isIncremental() && _memory->isLocalizationDataSaved() && !odomCovariance.empty())
4253  {
4254  _memory->addLink(Link(signature->id(), signature->id(), Link::kPosePrior, odomPose, odomCovariance.inv()));
4255  }
4256 
4257  // remove last signature if the memory is not incremental or is a bad signature (if bad signatures are ignored)
4258  int signatureRemoved = _memory->cleanup();
4259  if(signatureRemoved)
4260  {
4261  signaturesRemoved.push_back(signatureRemoved);
4262  }
4263 
4264  // If this option activated, add new nodes only if there are linked with a previous map.
4265  // Used when rtabmap is first started, it will wait a
4266  // global loop closure detection before starting the new map,
4267  // otherwise it deletes the current node.
4268  if(signatureRemoved != lastSignatureData.id())
4269  {
4271  _memory->isIncremental() && // only in mapping mode
4272  graph::filterLinks(signature->getLinks(), Link::kSelfRefLink).size() == 0 && // alone in the current map
4273  (landmarksDetected.empty() || rejectedLoopClosure) && // if we re not seeing a landmark from a previous map
4274  _memory->getWorkingMem().size()>=2) // The working memory should not be empty (beside virtual signature)
4275  {
4276  UWARN("Ignoring location %d because a global loop closure is required before starting a new map!",
4277  signature->id());
4278  signaturesRemoved.push_back(signature->id());
4279  _memory->deleteLocation(signature->id());
4280  }
4281  else if(_startNewMapOnGoodSignature &&
4282  (signature->getLandmarks().empty() && signature->isBadSignature()) &&
4283  graph::filterLinks(signature->getLinks(), Link::kSelfRefLink).size() == 0) // alone in the current map
4284  {
4285  UWARN("Ignoring location %d because a good signature (with enough features or with a landmark detected) is required before starting a new map!",
4286  signature->id());
4287  signaturesRemoved.push_back(signature->id());
4288  _memory->deleteLocation(signature->id());
4289  }
4290  else if((smallDisplacement || tooFastMovement) &&
4291  _loopClosureHypothesis.first == 0 &&
4292  lastProximitySpaceClosureId == 0 &&
4293  (rejectedLoopClosure || landmarksDetected.empty()) &&
4294  !addedNewLandmark)
4295  {
4296  // Don't delete the location if a loop closure is detected
4297  UINFO("Ignoring location %d because the displacement is too small! (d=%f a=%f)",
4298  signature->id(), _rgbdLinearUpdate, _rgbdAngularUpdate);
4299  // If there is a too small displacement, remove the node
4300  signaturesRemoved.push_back(signature->id());
4301  _memory->deleteLocation(signature->id());
4302  }
4303  else
4304  {
4305  _memory->saveLocationData(signature->id());
4306  }
4307  }
4308  else if(!_memory->isIncremental() &&
4309  (smallDisplacement || tooFastMovement) &&
4310  _loopClosureHypothesis.first == 0 &&
4311  lastProximitySpaceClosureId == 0 &&
4312  !delayedLocalization &&
4313  (rejectedLoopClosure || landmarksDetected.empty()))
4314  {
4315  _odomCachePoses.erase(signatureRemoved);
4316  for(std::multimap<int, Link>::iterator iter=_odomCacheConstraints.begin(); iter!=_odomCacheConstraints.end();)
4317  {
4318  if(iter->second.from() == signatureRemoved || iter->second.to() == signatureRemoved)
4319  {
4320  _odomCacheConstraints.erase(iter++);
4321  }
4322  else
4323  {
4324  ++iter;
4325  }
4326  }
4327  }
4328 
4329  // Pass this point signature should not be used, since it could have been transferred...
4330  signature = 0;
4331 
4332  timeMemoryCleanup = timer.ticks();
4333  ULOGGER_INFO("timeMemoryCleanup = %fs... %d signatures removed", timeMemoryCleanup, (int)signaturesRemoved.size());
4334 
4335 
4336 
4337  //============================================================
4338  // TRANSFER
4339  //============================================================
4340  // If time allowed for the detection exceeds the limit of
4341  // real-time, move the oldest signature with less frequency
4342  // entry (from X oldest) from the short term memory to the
4343  // long term memory.
4344  //============================================================
4345  double totalTime = timerTotal.ticks();
4346  ULOGGER_INFO("Total time processing = %fs...", totalTime);
4347  if((_maxTimeAllowed != 0 && totalTime*1000>_maxTimeAllowed) ||
4349  {
4350  ULOGGER_INFO("Removing old signatures because time limit is reached %f>%f or memory is reached %d>%d...", totalTime*1000, _maxTimeAllowed, _memory->getWorkingMem().size(), _maxMemoryAllowed);
4351  immunizedLocations.insert(_lastLocalizationNodeId); // keep the latest localization in working memory
4352  std::list<int> transferred = _memory->forget(immunizedLocations);
4353  signaturesRemoved.insert(signaturesRemoved.end(), transferred.begin(), transferred.end());
4354  if(!_someNodesHaveBeenTransferred && transferred.size())
4355  {
4356  _someNodesHaveBeenTransferred = true; // only used to hide a warning on close nodes immunization
4357  }
4358  }
4359  _lastProcessTime = totalTime;
4360 
4361  // cleanup cached gps values
4362  for(std::list<int>::iterator iter=signaturesRemoved.begin(); iter!=signaturesRemoved.end() && _gpsGeocentricCache.size(); ++iter)
4363  {
4364  _gpsGeocentricCache.erase(*iter);
4365  }
4366 
4367  //Remove optimized poses from signatures transferred
4368  if(signaturesRemoved.size() && (_optimizedPoses.size() || _constraints.size()))
4369  {
4370  //refresh the local map because some transferred nodes may have broken the tree
4371  int id = 0;
4372  if(!_memory->isIncremental() && (_lastLocalizationNodeId > 0 || _path.size()))
4373  {
4374  if(_path.size())
4375  {
4376  // priority on node on the path
4377  UASSERT(_pathCurrentIndex < _path.size());
4378  UASSERT_MSG(uContains(_optimizedPoses, _path.at(_pathCurrentIndex).first), uFormat("id=%d", _path.at(_pathCurrentIndex).first).c_str());
4379  id = _path.at(_pathCurrentIndex).first;
4380  UDEBUG("Refresh local map from %d", id);
4381  }
4382  else
4383  {
4385  {
4387  UDEBUG("Refresh local map from %d", id);
4388  }
4389  else
4390  {
4391  UDEBUG("Clearing _lastLocalizationNodeId(%d)", _lastLocalizationNodeId);
4393  }
4394  }
4395  }
4396  else if(_memory->isIncremental() &&
4397  _optimizedPoses.size() &&
4399  {
4400  id = _memory->getLastWorkingSignature()->id();
4401  UDEBUG("Refresh local map from %d", id);
4402  }
4403  UDEBUG("id=%d _optimizedPoses=%d", id, (int)_optimizedPoses.size());
4404  if(id > 0)
4405  {
4406  if(_lastLocalizationNodeId != 0)
4407  {
4409  }
4410  UASSERT_MSG(_memory->getSignature(id) != 0, uFormat("id=%d", id).c_str());
4411 
4412  if(signaturesRemoved.size() == 1 && signaturesRemoved.front() == lastSignatureData.id())
4413  {
4414  int lastId = signaturesRemoved.front();
4415  UDEBUG("Detected that only last signature has been removed (lastId=%d)", lastId);
4416  _optimizedPoses.erase(lastId);
4417  for(std::multimap<int, Link>::iterator iter=_constraints.find(lastId); iter!=_constraints.end() && iter->first==lastId;++iter)
4418  {
4419  if(iter->second.to() != iter->second.from())
4420  {
4421  std::multimap<int, Link>::iterator jter = graph::findLink(_constraints, iter->second.to(), iter->second.from(), false);
4422  if(jter != _constraints.end())
4423  {
4424  _constraints.erase(jter);
4425  }
4426  }
4427  }
4428  _constraints.erase(lastId);
4429  }
4430  else
4431  {
4432 
4433  std::map<int, int> ids = _memory->getNeighborsId(id, 0, 0, true);
4434  for(std::map<int, Transform>::iterator iter=_optimizedPoses.begin(); iter!=_optimizedPoses.end();)
4435  {
4436  if(iter->first > 0 && !uContains(ids, iter->first))
4437  {
4438  UDEBUG("Removed %d from local map", iter->first);
4440  _optimizedPoses.erase(iter++);
4441 
4442  if(!_globalScanMap.empty())
4443  {
4444  UWARN("optimized poses have been modified, clearing global scan map...");
4446  _globalScanMapPoses.clear();
4447  }
4448  }
4449  else
4450  {
4451  ++iter;
4452  }
4453  }
4454  for(std::multimap<int, Link>::iterator iter=_constraints.begin(); iter!=_constraints.end();)
4455  {
4456  if(iter->first > 0 && (!uContains(ids, iter->second.from()) || !uContains(ids, iter->second.to())))
4457  {
4458  _constraints.erase(iter++);
4459  }
4460  else
4461  {
4462  ++iter;
4463  }
4464  }
4465  }
4466  }
4467  else
4468  {
4469  if(!_optimizedPoses.empty())
4470  UDEBUG("Optimized poses cleared!");
4471  _optimizedPoses.clear();
4472  _constraints.clear();
4473  }
4474  }
4475  // just some verifications to make sure that planning path is still in the local map!
4476  if(_path.size())
4477  {
4478  UASSERT(_pathCurrentIndex < _path.size());
4479  UASSERT(_pathGoalIndex < _path.size());
4480  UASSERT_MSG(uContains(_optimizedPoses, _path.at(_pathCurrentIndex).first), uFormat("local map size=%d, id=%d", (int)_optimizedPoses.size(), _path.at(_pathCurrentIndex).first).c_str());
4481  UASSERT_MSG(uContains(_optimizedPoses, _path.at(_pathGoalIndex).first), uFormat("local map size=%d, id=%d", (int)_optimizedPoses.size(), _path.at(_pathGoalIndex).first).c_str());
4482  }
4483 
4484 
4485  timeRealTimeLimitReachedProcess = timer.ticks();
4486  ULOGGER_INFO("Time limit reached processing = %f...", timeRealTimeLimitReachedProcess);
4487 
4488  //==============================================================
4489  // Finalize statistics and log files
4490  //==============================================================
4491  int localGraphSize = 0;
4492  if(_publishStats)
4493  {
4494  statistics_.addStatistic(Statistics::kTimingStatistics_creation(), timeStatsCreation*1000);
4495  statistics_.addStatistic(Statistics::kTimingTotal(), totalTime*1000);
4496  statistics_.addStatistic(Statistics::kTimingForgetting(), timeRealTimeLimitReachedProcess*1000);
4497  statistics_.addStatistic(Statistics::kTimingJoining_trash(), timeJoiningTrash*1000);
4498  statistics_.addStatistic(Statistics::kTimingEmptying_trash(), timeEmptyingTrash*1000);
4499  statistics_.addStatistic(Statistics::kTimingMemory_cleanup(), timeMemoryCleanup*1000);
4500 
4501  // Transfer
4502  statistics_.addStatistic(Statistics::kMemorySignatures_removed(), signaturesRemoved.size());
4503  statistics_.addStatistic(Statistics::kMemoryImmunized_globally(), immunizedGlobally);
4504  statistics_.addStatistic(Statistics::kMemoryImmunized_locally(), immunizedLocally);
4505  statistics_.addStatistic(Statistics::kMemoryImmunized_locally_max(), maxLocalLocationsImmunized);
4506 
4507  // place after transfer because the memory/local graph may have changed
4508  statistics_.addStatistic(Statistics::kMemoryWorking_memory_size(), _memory->getWorkingMem().size());
4509  statistics_.addStatistic(Statistics::kMemoryShort_time_memory_size(), _memory->getStMem().size());
4510  statistics_.addStatistic(Statistics::kMemoryDatabase_memory_used(), _memory->getDatabaseMemoryUsed());
4511 
4512  // Set local graph
4513  std::map<int, Transform> poses;
4514  std::multimap<int, Link> constraints;
4515  if(!_rgbdSlamMode)
4516  {
4517  UDEBUG("");
4518  // no optimization on appearance-only mode, create a local graph
4519  std::map<int, int> ids = _memory->getNeighborsId(lastSignatureData.id(), 0, 0, true);
4520  _memory->getMetricConstraints(uKeysSet(ids), poses, constraints, false);
4521  }
4522  else // RGBD-SLAM mode
4523  {
4524  poses = _optimizedPoses;
4525  constraints = _constraints;
4526  }
4527  UINFO("Adding data %d [%d] (rgb/left=%d depth/right=%d)", lastSignatureData.id(), lastSignatureData.mapId(), lastSignatureData.sensorData().imageRaw().empty()?0:1, lastSignatureData.sensorData().depthOrRightRaw().empty()?0:1);
4528  statistics_.addSignatureData(lastSignatureData);
4529 
4530  if(_nodesToRepublish.size())
4531  {
4532  std::multimap<int, int> missingIds;
4533 
4534  // priority to loopId
4535  int tmpId = loopId>0?loopId:_highestHypothesis.first;
4536  if(tmpId>0 && _nodesToRepublish.find(tmpId) != _nodesToRepublish.end())
4537  {
4538  missingIds.insert(std::make_pair(-1, tmpId));
4539  }
4540 
4542  {
4543  // Republish data from closest nodes of the current localization
4544  std::map<int, Transform> nodesOnly(_optimizedPoses.lower_bound(1), _optimizedPoses.end());
4546  if(id>0)
4547  {
4548  std::map<int, int> ids = _memory->getNeighborsId(id, 0, 0, true, false, true);
4549  for(std::map<int, int>::iterator iter=ids.begin(); iter!=ids.end(); ++iter)
4550  {
4551  if(iter->first != loopId &&
4552  _nodesToRepublish.find(iter->first) != _nodesToRepublish.end())
4553  {
4554  missingIds.insert(std::make_pair(iter->second, iter->first));
4555  }
4556  }
4557 
4558  if(_nodesToRepublish.size() != missingIds.size())
4559  {
4560  // remove requested nodes not anymore in the graph
4561  for(std::set<int>::iterator iter=_nodesToRepublish.begin(); iter!=_nodesToRepublish.end();)
4562  {
4563  if(ids.find(*iter) == ids.end())
4564  {
4565  iter = _nodesToRepublish.erase(iter);
4566  }
4567  else
4568  {
4569  ++iter;
4570  }
4571  }
4572  }
4573  }
4574  }
4575 
4576  int loaded = 0;
4577  std::stringstream stream;
4578  for(std::multimap<int, int>::iterator iter=missingIds.begin(); iter!=missingIds.end() && loaded<(int)_maxRepublished; ++iter)
4579  {
4580  statistics_.addSignatureData(getSignatureCopy(iter->second, true, true, true, true, true, true));
4581  _nodesToRepublish.erase(iter->second);
4582  ++loaded;
4583  stream << iter->second << " ";
4584  }
4585  if(loaded)
4586  {
4587  UWARN("Republishing data of requested node(s) %s(%s=%d)",
4588  stream.str().c_str(),
4589  Parameters::kRtabmapMaxRepublished().c_str(),
4590  _maxRepublished);
4591  }
4592  }
4593 
4594  UDEBUG("");
4595  localGraphSize = (int)poses.size();
4596  if(!lastSignatureLocalizedPose.isNull())
4597  {
4598  poses.insert(std::make_pair(lastSignatureData.id(), lastSignatureLocalizedPose)); // in case we are in localization
4599  }
4600  statistics_.setPoses(poses);
4601  statistics_.setConstraints(constraints);
4602 
4603  statistics_.addStatistic(Statistics::kMemoryLocal_graph_size(), poses.size());
4604 
4607  statistics_.addStatistic(Statistics::kMemoryOdom_cache_poses(), _odomCachePoses.size());
4608  statistics_.addStatistic(Statistics::kMemoryOdom_cache_links(), _odomCacheConstraints.size());
4609 
4610  if(_computeRMSE && _memory->getGroundTruths().size())
4611  {
4612  UDEBUG("Computing RMSE...");
4613  float translational_rmse = 0.0f;
4614  float translational_mean = 0.0f;
4615  float translational_median = 0.0f;
4616  float translational_std = 0.0f;
4617  float translational_min = 0.0f;
4618  float translational_max = 0.0f;
4619  float rotational_rmse = 0.0f;
4620  float rotational_mean = 0.0f;
4621  float rotational_median = 0.0f;
4622  float rotational_std = 0.0f;
4623  float rotational_min = 0.0f;
4624  float rotational_max = 0.0f;
4625 
4628  poses,
4629  translational_rmse,
4630  translational_mean,
4631  translational_median,
4632  translational_std,
4633  translational_min,
4634  translational_max,
4635  rotational_rmse,
4636  rotational_mean,
4637  rotational_median,
4638  rotational_std,
4639  rotational_min,
4640  rotational_max);
4641 
4642  statistics_.addStatistic(Statistics::kGtTranslational_rmse(), translational_rmse);
4643  statistics_.addStatistic(Statistics::kGtTranslational_mean(), translational_mean);
4644  statistics_.addStatistic(Statistics::kGtTranslational_median(), translational_median);
4645  statistics_.addStatistic(Statistics::kGtTranslational_std(), translational_std);
4646  statistics_.addStatistic(Statistics::kGtTranslational_min(), translational_min);
4647  statistics_.addStatistic(Statistics::kGtTranslational_max(), translational_max);
4648  statistics_.addStatistic(Statistics::kGtRotational_rmse(), rotational_rmse);
4649  statistics_.addStatistic(Statistics::kGtRotational_mean(), rotational_mean);
4650  statistics_.addStatistic(Statistics::kGtRotational_median(), rotational_median);
4651  statistics_.addStatistic(Statistics::kGtRotational_std(), rotational_std);
4652  statistics_.addStatistic(Statistics::kGtRotational_min(), rotational_min);
4653  statistics_.addStatistic(Statistics::kGtRotational_max(), rotational_max);
4654  UDEBUG("Computing RMSE...done!");
4655  }
4656 
4657  std::vector<int> ids;
4658  ids.reserve(_memory->getWorkingMem().size() + _memory->getStMem().size());
4659  for(std::set<int>::const_iterator iter=_memory->getStMem().begin(); iter!=_memory->getStMem().end(); ++iter)
4660  {
4661  ids.push_back(*iter);
4662  }
4663  for(std::map<int, double>::const_iterator iter=_memory->getWorkingMem().lower_bound(0); iter!=_memory->getWorkingMem().end(); ++iter)
4664  {
4665  ids.push_back(iter->first);
4666  }
4667  statistics_.setWmState(ids);
4668  UDEBUG("wmState=%d", (int)ids.size());
4669  }
4670 
4671  //Save statistics to database
4673  {
4675  }
4676 
4677  //Start trashing
4678  UDEBUG("Empty trash...");
4679  _memory->emptyTrash();
4680 
4681  // Log info...
4682  // TODO : use a specific class which will handle the RtabmapEvent
4683  if(_foutFloat && _foutInt)
4684  {
4685  UDEBUG("Logging...");
4686  std::string logF = uFormat("%f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f\n",
4687  totalTime,
4688  timeMemoryUpdate,
4689  timeReactivations,
4690  timeLikelihoodCalculation,
4691  timePosteriorCalculation,
4692  timeHypothesesCreation,
4693  timeHypothesesValidation,
4694  timeRealTimeLimitReachedProcess,
4695  timeStatsCreation,
4696  _highestHypothesis.second,
4697  0.0f,
4698  0.0f,
4699  0.0f,
4700  0.0f,
4701  0.0f,
4702  vpHypothesis,
4703  timeJoiningTrash,
4704  rehearsalValue,
4705  timeEmptyingTrash,
4706  timeRetrievalDbAccess,
4707  timeAddLoopClosureLink,
4708  timeMemoryCleanup,
4709  timeNeighborLinkRefining,
4710  timeProximityByTimeDetection,
4711  timeProximityBySpaceDetection,
4712  timeMapOptimization);
4713  std::string logI = uFormat("%d %d %d %d %d %d %d %d %d %d %d %d %d %d %d %d %d %d %d %d %d\n",
4714  _loopClosureHypothesis.first,
4715  _highestHypothesis.first,
4716  (int)signaturesRemoved.size(),
4717  0,
4718  refWordsCount,
4719  dictionarySize,
4720  int(_memory->getWorkingMem().size()),
4721  rejectedLoopClosure?1:0,
4722  0,
4723  0,
4724  int(signaturesRetrieved.size()),
4725  lcHypothesisReactivated,
4726  refUniqueWordsCount,
4727  retrievalId,
4728  0,
4729  rehearsalMaxId,
4730  rehearsalMaxId>0?1:0,
4731  localGraphSize,
4732  data.id(),
4736  {
4737  _bufferedLogsF.push_back(logF);
4738  _bufferedLogsI.push_back(logI);
4739  }
4740  else
4741  {
4742  if(_foutFloat)
4743  {
4744  fprintf(_foutFloat, "%s", logF.c_str());
4745  }
4746  if(_foutInt)
4747  {
4748  fprintf(_foutInt, "%s", logI.c_str());
4749  }
4750  }
4751  UINFO("Time logging = %f...", timer.ticks());
4752  //ULogger::flush();
4753  }
4754  timeFinalizingStatistics = timer.ticks();
4755  UDEBUG("End process, timeFinalizingStatistics=%fs", timeFinalizingStatistics);
4756  if(_publishStats)
4757  {
4758  statistics_.addStatistic(Statistics::kTimingFinalizing_statistics(), timeFinalizingStatistics*1000);
4759  }
4760 
4761  return true;
4762 }
4763 
4764 // SETTERS
4765 void Rtabmap::setTimeThreshold(float maxTimeAllowed)
4766 {
4767  //must be positive, 0 mean inf time allowed (no time limit)
4768  _maxTimeAllowed = maxTimeAllowed;
4769  if(_maxTimeAllowed < 0)
4770  {
4771  ULOGGER_WARN("maxTimeAllowed < 0, then setting it to 0 (inf).");
4772  _maxTimeAllowed = 0;
4773  }
4774  else if(_maxTimeAllowed > 0.0f && _maxTimeAllowed < 1.0f)
4775  {
4776  ULOGGER_WARN("Time threshold set to %fms, it is not in seconds!", _maxTimeAllowed);
4777  }
4778 }
4779 void Rtabmap::setMemoryThreshold(int maxMemoryAllowed)
4780 {
4781  //must be positive, 0 mean inf memory allowed (no memory limit)
4782  _maxMemoryAllowed = maxMemoryAllowed;
4783  if(maxMemoryAllowed < 0)
4784  {
4785  ULOGGER_WARN("maxMemoryAllowed < 0, then setting it to 0 (inf).");
4786  _maxMemoryAllowed = 0;
4787  }
4788 }
4789 
4790 void Rtabmap::setWorkingDirectory(std::string path)
4791 {
4793  if(!path.empty() && UDirectory::exists(path))
4794  {
4795  ULOGGER_DEBUG("Comparing new working directory path \"%s\" with \"%s\"", path.c_str(), _wDir.c_str());
4796  if(path.compare(_wDir) != 0)
4797  {
4798  if (_foutFloat || _foutInt)
4799  {
4800  UWARN("Working directory has been changed from \"%s\" with \"%s\", new log files will be created.",
4801  path.c_str(), _wDir.c_str());
4802  }
4803  _wDir = path;
4804  setupLogFiles();
4805  }
4806  }
4807  else if(path.empty())
4808  {
4809  _wDir.clear();
4810  setupLogFiles();
4811  }
4812  else
4813  {
4814  ULOGGER_ERROR("Directory \"%s\" doesn't exist!", path.c_str());
4815  }
4816 }
4817 
4819 {
4820  if(_memory && _memory->getStMem().find(getLastLocationId())!=_memory->getStMem().end())
4821  {
4822  std::multimap<int, Link> links = _memory->getLinks(getLastLocationId(), false);
4823  bool linksRemoved = false;
4824  for(std::multimap<int, Link>::iterator iter = links.begin(); iter!=links.end(); ++iter)
4825  {
4826  if(iter->second.type() == Link::kGlobalClosure ||
4827  iter->second.type() == Link::kLocalSpaceClosure ||
4828  iter->second.type() == Link::kLocalTimeClosure ||
4829  iter->second.type() == Link::kUserClosure)
4830  {
4831  _memory->removeLink(iter->second.from(), iter->second.to());
4832  std::multimap<int, Link>::iterator jter = graph::findLink(_constraints, iter->second.from(), iter->second.to(), true);
4833  if(jter!=_constraints.end())
4834  {
4835  _constraints.erase(jter);
4836  // second time if link is also inverted
4837  jter = graph::findLink(_constraints, iter->second.from(), iter->second.to(), true);
4838  if(jter!=_constraints.end())
4839  {
4840  _constraints.erase(jter);
4841  }
4842  }
4843  linksRemoved = true;
4844  }
4845  }
4846 
4847  if(linksRemoved)
4848  {
4849  _loopClosureHypothesis.first = 0;
4850 
4851  // we have to re-optimize the graph without the rejected links
4852  if(_memory->isIncremental() && _optimizedPoses.size())
4853  {
4854  UINFO("Update graph");
4855  std::map<int, Transform> poses = _optimizedPoses;
4856  std::multimap<int, Link> constraints;
4857  cv::Mat covariance;
4858  optimizeCurrentMap(getLastLocationId(), false, poses, covariance, &constraints);
4859 
4860  if(poses.empty())
4861  {
4862  UWARN("Graph optimization failed after removing loop closure links from last location!");
4863  }
4864  else
4865  {
4866  UINFO("Updated local map (old size=%d, new size=%d)", (int)_optimizedPoses.size(), (int)poses.size());
4867  _optimizedPoses = poses;
4868  _constraints = constraints;
4870  }
4871  }
4872  }
4873  }
4874 }
4875 
4877 {
4878  if(_memory && _memory->getStMem().size())
4879  {
4880  int lastId = *_memory->getStMem().rbegin();
4881  _memory->deleteLocation(lastId);
4882  // we have to re-optimize the graph without the deleted location
4883  if(_memory->isIncremental() && _optimizedPoses.size())
4884  {
4885  UINFO("Update graph");
4886  _optimizedPoses.erase(lastId);
4887  std::map<int, Transform> poses = _optimizedPoses;
4888  //remove all constraints with last localization id
4889  for(std::multimap<int, Link>::iterator iter=_constraints.begin(); iter!=_constraints.end();)
4890  {
4891  if(iter->second.from() == lastId || iter->second.to() == lastId)
4892  {
4893  _constraints.erase(iter++);
4894  }
4895  else
4896  {
4897  ++iter;
4898  }
4899  }
4900 
4901  if(poses.empty())
4902  {
4904  }
4905  else
4906  {
4907  std::multimap<int, Link> constraints;
4908  cv::Mat covariance;
4909  optimizeCurrentMap(_memory->getLastWorkingSignature()->id(), false, poses, covariance, &constraints);
4910 
4911  if(poses.empty())
4912  {
4913  UWARN("Graph optimization failed after deleting the last location!");
4914  }
4915  else
4916  {
4917  _optimizedPoses = poses;
4918  _constraints = constraints;
4920  }
4921  }
4922  }
4923  }
4924 }
4925 
4926 void Rtabmap::setOptimizedPoses(const std::map<int, Transform> & poses, const std::multimap<int, Link> & constraints)
4927 {
4928  _optimizedPoses = poses;
4929  _constraints = constraints;
4930 }
4931 
4932 void Rtabmap::dumpData() const
4933 {
4934  UDEBUG("");
4935  if(_memory)
4936  {
4937  if(this->getWorkingDir().empty())
4938  {
4939  UERROR("Working directory not set.");
4940  }
4941  else
4942  {
4943  _memory->dumpMemory(this->getWorkingDir());
4944  }
4945  }
4946 }
4947 
4948 // fromId must be in _memory and in _optimizedPoses
4949 // Get poses in front of the robot, return optimized poses
4950 std::map<int, Transform> Rtabmap::getForwardWMPoses(
4951  int fromId,
4952  int maxNearestNeighbors,
4953  float radius,
4954  int maxGraphDepth // 0 means ignore
4955  ) const
4956 {
4957  std::map<int, Transform> poses;
4958  if(_memory && fromId > 0)
4959  {
4960  UDEBUG("");
4961  const Signature * fromS = _memory->getSignature(fromId);
4962  UASSERT(fromS != 0);
4963  UASSERT(_optimizedPoses.find(fromId) != _optimizedPoses.end());
4964 
4965  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
4966  cloud->resize(_optimizedPoses.size());
4967  std::vector<int> ids(_optimizedPoses.size());
4968  int oi = 0;
4969  const std::set<int> & stm = _memory->getStMem();
4970  //get distances
4971  std::map<int, float> foundIds;
4972  if(_memory->isIncremental())
4973  {
4974  foundIds = _memory->getNeighborsIdRadius(fromId, radius, _optimizedPoses, maxGraphDepth);
4975  }
4976  else
4977  {
4978  foundIds = graph::findNearestNodes(fromId, _optimizedPoses, radius);
4979  }
4980 
4981  float radiusSqrd = radius * radius;
4982  for(std::map<int, Transform>::const_iterator iter = _optimizedPoses.begin(); iter!=_optimizedPoses.end(); ++iter)
4983  {
4984  if(iter->first != fromId)
4985  {
4986  if(stm.find(iter->first) == stm.end() &&
4987  uContains(foundIds, iter->first) &&
4988  (radiusSqrd==0 || foundIds.at(iter->first) <= radiusSqrd))
4989  {
4990  (*cloud)[oi] = pcl::PointXYZ(iter->second.x(), iter->second.y(), iter->second.z());
4991  ids[oi++] = iter->first;
4992  }
4993  }
4994  }
4995 
4996  cloud->resize(oi);
4997  ids.resize(oi);
4998 
4999  Transform fromT = _optimizedPoses.at(fromId);
5000 
5001  if(cloud->size())
5002  {
5003  //if(cloud->size())
5004  //{
5005  // pcl::io::savePCDFile("radiusPoses.pcd", *cloud);
5006  // UWARN("Saved radiusPoses.pcd");
5007  //}
5008 
5009  //filter poses in front of the fromId
5010  float x,y,z, roll,pitch,yaw;
5012 
5013  pcl::CropBox<pcl::PointXYZ> cropbox;
5014  cropbox.setInputCloud(cloud);
5015  cropbox.setMin(Eigen::Vector4f(-1, -radius, -999999, 0));
5016  cropbox.setMax(Eigen::Vector4f(radius, radius, 999999, 0));
5017  cropbox.setRotation(Eigen::Vector3f(roll, pitch, yaw));
5018  cropbox.setTranslation(Eigen::Vector3f(x, y, z));
5019  cropbox.setRotation(Eigen::Vector3f(roll,pitch,yaw));
5020  pcl::IndicesPtr indices(new std::vector<int>());
5021  cropbox.filter(*indices);
5022 
5023  //if(indices->size())
5024  //{
5025  // pcl::io::savePCDFile("radiusCrop.pcd", *cloud, *indices);
5026  // UWARN("Saved radiusCrop.pcd");
5027  //}
5028 
5029  if(indices->size())
5030  {
5031  pcl::search::KdTree<pcl::PointXYZ>::Ptr kdTree(new pcl::search::KdTree<pcl::PointXYZ>);
5032  kdTree->setInputCloud(cloud, indices);
5033  std::vector<int> ind;
5034  std::vector<float> dist;
5035  pcl::PointXYZ pt(fromT.x(), fromT.y(), fromT.z());
5036  kdTree->radiusSearch(pt, radius, ind, dist, maxNearestNeighbors);
5037  //pcl::PointCloud<pcl::PointXYZ> inliers;
5038  for(unsigned int i=0; i<ind.size(); ++i)
5039  {
5040  if(ind[i] >=0)
5041  {
5042  Transform tmp = _optimizedPoses.find(ids[ind[i]])->second;
5043  //inliers.push_back(pcl::PointXYZ(tmp.x(), tmp.y(), tmp.z()));
5044  UDEBUG("Inlier %d: %s", ids[ind[i]], tmp.prettyPrint().c_str());
5045  poses.insert(std::make_pair(ids[ind[i]], tmp));
5046  }
5047  }
5048 
5049  //if(inliers.size())
5050  //{
5051  // pcl::io::savePCDFile("radiusInliers.pcd", inliers);
5052  //}
5053  //if(nearestId >0)
5054  //{
5055  // pcl::PointCloud<pcl::PointXYZ> c;
5056  // Transform ct = _optimizedPoses.find(nearestId)->second;
5057  // c.push_back(pcl::PointXYZ(ct.x(), ct.y(), ct.z()));
5058  // pcl::io::savePCDFile("radiusNearestPt.pcd", c);
5059  //}
5060  }
5061  }
5062  }
5063  return poses;
5064 }
5065 
5066 std::map<int, std::map<int, Transform> > Rtabmap::getPaths(const std::map<int, Transform> & posesIn, const Transform & target, int maxGraphDepth) const
5067 {
5068  std::map<int, std::map<int, Transform> > paths;
5069  std::set<int> nodesSet;
5070  std::map<int, Transform> poses;
5071  for(std::map<int, Transform>::const_iterator iter=posesIn.lower_bound(1); iter!=posesIn.end(); ++iter)
5072  {
5073  nodesSet.insert(iter->first);
5074  poses.insert(*iter);
5075  }
5076  if(_memory && nodesSet.size() && !target.isNull())
5077  {
5078  double e0=0,e1=0,e2=0,e3=0,e4=0;
5079  UTimer t;
5080  e0 = t.ticks();
5081  // Segment poses connected only by neighbor links
5082  while(poses.size())
5083  {
5084  std::map<int, Transform> path;
5085  // select nearest pose and iterate neighbors from there
5086  int nearestId = rtabmap::graph::findNearestNode(poses, target);
5087 
5088  e1+=t.ticks();
5089 
5090  if(nearestId == 0)
5091  {
5092  UWARN("Nearest id of %s in %d poses is 0 !? Returning empty path.", target.prettyPrint().c_str(), (int)poses.size());
5093  break;
5094  }
5095  std::map<int, int> ids = _memory->getNeighborsId(nearestId, maxGraphDepth, 0, true, true, true, true, nodesSet);
5096 
5097  e2+=t.ticks();
5098 
5099  for(std::map<int, int>::iterator iter=ids.begin(); iter!=ids.end(); ++iter)
5100  {
5101  std::map<int, Transform>::iterator jter = poses.find(iter->first);
5102  if(jter != poses.end())
5103  {
5104  bool valid = path.empty();
5105  if(!valid)
5106  {
5107  // make sure it has a neighbor added to path
5108  std::multimap<int, Link> links = _memory->getNeighborLinks(iter->first);
5109  for(std::multimap<int, Link>::iterator kter=links.begin(); kter!=links.end() && !valid; ++kter)
5110  {
5111  valid = path.find(kter->first) != path.end();
5112  }
5113  }
5114 
5115  if(valid)
5116  {
5117  //UDEBUG("%d <- %d", nearestId, jter->first);
5118  path.insert(*jter);
5119  poses.erase(jter);
5120  }
5121  }
5122  }
5123 
5124  e3+=t.ticks();
5125 
5126  if (path.size())
5127  {
5128  if (maxGraphDepth > 0 && !_memory->isGraphReduced() && (int)path.size() > maxGraphDepth * 2 + 1)
5129  {
5130  UWARN("%s=Off but path(%d) > maxGraphDepth(%d)*2+1, nearestId=%d ids=%d. Is reduce graph activated before?",
5131  Parameters::kMemReduceGraph().c_str(), (int)path.size(), maxGraphDepth, nearestId, (int)ids.size());
5132  }
5133  paths.insert(std::make_pair(nearestId, path));
5134  }
5135  else
5136  {
5137  UWARN("path.size()=0!? nearestId=%d ids=%d, aborting...", nearestId, (int)ids.size());
5138  break;
5139  }
5140 
5141  e4+=t.ticks();
5142  }
5143  UDEBUG("e0=%fs e1=%fs e2=%fs e3=%fs e4=%fs", e0, e1, e2, e3, e4);
5144  }
5145  return paths;
5146 }
5147 
5149  int id,
5150  bool lookInDatabase,
5151  std::map<int, Transform> & optimizedPoses,
5152  cv::Mat & covariance,
5153  std::multimap<int, Link> * constraints,
5154  double * error,
5155  int * iterationsDone) const
5156 {
5157  //Optimize the map
5158  UINFO("Optimize map: around location %d (lookInDatabase=%s)", id, lookInDatabase?"true":"false");
5159  if(_memory && id > 0)
5160  {
5161  UTimer timer;
5162  std::map<int, int> ids = _memory->getNeighborsId(id, 0, lookInDatabase?-1:0, true, false);
5163  if(!_optimizeFromGraphEnd && ids.size() > 1)
5164  {
5165  id = ids.begin()->first;
5166  }
5167  UINFO("get %d ids time %f s", (int)ids.size(), timer.ticks());
5168 
5169  std::map<int, Transform> poses = Rtabmap::optimizeGraph(id, uKeysSet(ids), optimizedPoses, lookInDatabase, covariance, constraints, error, iterationsDone);
5170  UINFO("optimize time %f s", timer.ticks());
5171 
5172  if(poses.size())
5173  {
5174  optimizedPoses = poses;
5175 
5176  if(_memory->getSignature(id) && uContains(optimizedPoses, id))
5177  {
5178  Transform t = optimizedPoses.at(id) * _memory->getSignature(id)->getPose().inverse();
5179  UINFO("Correction (from node %d) %s", id, t.prettyPrint().c_str());
5180  }
5181  }
5182  else
5183  {
5184  UWARN("Failed to optimize the graph! returning empty optimized poses...");
5185  optimizedPoses.clear();
5186  if(constraints)
5187  {
5188  constraints->clear();
5189  }
5190  }
5191  }
5192 }
5193 
5194 std::map<int, Transform> Rtabmap::optimizeGraph(
5195  int fromId,
5196  const std::set<int> & ids,
5197  const std::map<int, Transform> & guessPoses,
5198  bool lookInDatabase,
5199  cv::Mat & covariance,
5200  std::multimap<int, Link> * constraints,
5201  double * error,
5202  int * iterationsDone) const
5203 {
5204  UTimer timer;
5205  std::map<int, Transform> optimizedPoses;
5206  std::map<int, Transform> poses;
5207  std::multimap<int, Link> edgeConstraints;
5208  UDEBUG("ids=%d", (int)ids.size());
5209  _memory->getMetricConstraints(ids, poses, edgeConstraints, lookInDatabase, !_graphOptimizer->landmarksIgnored());
5210  UINFO("get constraints (ids=%d, %d poses, %d edges) time %f s", (int)ids.size(), (int)poses.size(), (int)edgeConstraints.size(), timer.ticks());
5211 
5212  // add landmark priors if there are some
5213  for(std::map<int, Transform>::iterator iter=poses.begin(); iter!=poses.end() && iter->first < 0; ++iter)
5214  {
5215  if(_markerPriors.find(iter->first) != _markerPriors.end())
5216  {
5217  cv::Mat infMatrix = cv::Mat::eye(6, 6, CV_64FC1);
5218  infMatrix(cv::Range(0,3), cv::Range(0,3)) /= _markerPriorsLinearVariance;
5219  infMatrix(cv::Range(3,6), cv::Range(3,6)) /= _markerPriorsAngularVariance;
5220  edgeConstraints.insert(std::make_pair(iter->first, Link(iter->first, iter->first, Link::kPosePrior, _markerPriors.at(iter->first), infMatrix)));
5221  UDEBUG("Added prior %d : %s (variance: lin=%f ang=%f)", iter->first, _markerPriors.at(iter->first).prettyPrint().c_str(),
5223  }
5224  }
5225 
5226  if(_graphOptimizer->iterations() > 0)
5227  {
5228  for(std::map<int, Transform>::iterator iter=poses.begin(); iter!=poses.end(); ++iter)
5229  {
5230  // Apply guess poses (if some), ignore for rootid to avoid origin drifting
5231  std::map<int, Transform>::const_iterator foundGuess = guessPoses.find(iter->first);
5232  if(foundGuess!=guessPoses.end() && iter->first != fromId)
5233  {
5234  iter->second = foundGuess->second;
5235  }
5236  }
5237  }
5238 
5239 
5241  if(_graphOptimizer->iterations() == 0)
5242  {
5243  // Optimization disabled! Return not optimized poses.
5244  optimizedPoses = poses;
5245  if(constraints)
5246  {
5247  *constraints = edgeConstraints;
5248  }
5249  }
5250  else
5251  {
5252  bool hasLandmarks = !edgeConstraints.empty() && edgeConstraints.begin()->first < 0;
5253  if(poses.size() != guessPoses.size() || hasLandmarks)
5254  {
5255  UDEBUG("recompute poses using only links (robust to multi-session)");
5256  std::map<int, Transform> posesOut;
5257  std::multimap<int, Link> edgeConstraintsOut;
5258  _graphOptimizer->getConnectedGraph(fromId, poses, edgeConstraints, posesOut, edgeConstraintsOut);
5259  optimizedPoses = _graphOptimizer->optimize(fromId, posesOut, edgeConstraintsOut, covariance, 0, error, iterationsDone);
5260  if(constraints)
5261  {
5262  *constraints = edgeConstraintsOut;
5263  }
5264  }
5265  else
5266  {
5267  UDEBUG("use input guess poses");
5268  optimizedPoses = _graphOptimizer->optimize(fromId, poses, edgeConstraints, covariance, 0, error, iterationsDone);
5269  if(constraints)
5270  {
5271  *constraints = edgeConstraints;
5272  }
5273  }
5274 
5275  if(!poses.empty() && optimizedPoses.empty())
5276  {
5277  UWARN("Optimization has failed (poses=%d, guess=%d, links=%d)...",
5278  (int)poses.size(), (int)guessPoses.size(), (int)edgeConstraints.size());
5279  }
5280  }
5281 
5282  UINFO("Optimization time %f s", timer.ticks());
5283 
5284  return optimizedPoses;
5285 }
5286 
5287 void Rtabmap::adjustLikelihood(std::map<int, float> & likelihood) const
5288 {
5289  ULOGGER_DEBUG("likelihood.size()=%d", likelihood.size());
5290  UTimer timer;
5291  timer.start();
5292  if(likelihood.size()==0)
5293  {
5294  return;
5295  }
5296 
5297  // Use only non-null values (ignore virtual place)
5298  std::list<float> values;
5299  bool likelihoodNullValuesIgnored = true;
5300  for(std::map<int, float>::iterator iter = ++likelihood.begin(); iter!=likelihood.end(); ++iter)
5301  {
5302  if((iter->second >= 0 && !likelihoodNullValuesIgnored) ||
5303  (iter->second > 0 && likelihoodNullValuesIgnored))
5304  {
5305  values.push_back(iter->second);
5306  }
5307  }
5308  UDEBUG("values.size=%d", values.size());
5309 
5310  float mean = uMean(values);
5311  float stdDev = std::sqrt(uVariance(values, mean));
5312 
5313 
5314  //Adjust likelihood with mean and standard deviation (see Angeli phd)
5315  float epsilon = 0.0001;
5316  float max = 0.0f;
5317  int maxId = 0;
5318  for(std::map<int, float>::iterator iter=++likelihood.begin(); iter!= likelihood.end(); ++iter)
5319  {
5320  float value = iter->second;
5321  iter->second = 1.0f;
5322  if(value > mean+stdDev)
5323  {
5325  {
5326  iter->second = (value-(stdDev-epsilon))/mean;
5327  }
5328  else if(_virtualPlaceLikelihoodRatio!=0 && stdDev)
5329  {
5330  iter->second = (value-mean)/stdDev;
5331  }
5332  }
5333 
5334  if(value > max)
5335  {
5336  max = value;
5337  maxId = iter->first;
5338  }
5339  }
5340 
5341  if(_virtualPlaceLikelihoodRatio==0 && stdDev > epsilon && max)
5342  {
5343  likelihood.begin()->second = mean/stdDev + 1.0f;
5344  }
5345  else if(_virtualPlaceLikelihoodRatio!=0 && max > mean)
5346  {
5347  likelihood.begin()->second = stdDev/(max-mean) + 1.0f;
5348  }
5349  else
5350  {
5351  likelihood.begin()->second = 2.0f; //2 * std dev
5352  }
5353 
5354  double time = timer.ticks();
5355  UDEBUG("mean=%f, stdDev=%f, max=%f, maxId=%d, time=%fs", mean, stdDev, max, maxId, time);
5356 }
5357 
5359 {
5360  if(_memory && _bayesFilter)
5361  {
5362  if(this->getWorkingDir().empty())
5363  {
5364  UERROR("Working directory not set.");
5365  return;
5366  }
5367  std::list<int> signaturesToCompare;
5368  for(std::map<int, double>::const_iterator iter=_memory->getWorkingMem().begin();
5369  iter!=_memory->getWorkingMem().end();
5370  ++iter)
5371  {
5372  if(iter->first > 0)
5373  {
5374  const Signature * s = _memory->getSignature(iter->first);
5375  UASSERT(s!=0);
5376  if(s->getWeight() != -1) // ignore intermediate nodes
5377  {
5378  signaturesToCompare.push_back(iter->first);
5379  }
5380  }
5381  else
5382  {
5383  // virtual signature should be added
5384  signaturesToCompare.push_back(iter->first);
5385  }
5386  }
5387  cv::Mat prediction = _bayesFilter->generatePrediction(_memory, uListToVector(signaturesToCompare));
5388 
5389  FILE* fout = 0;
5390  std::string fileName = this->getWorkingDir() + "/DumpPrediction.txt";
5391  #ifdef _MSC_VER
5392  fopen_s(&fout, fileName.c_str(), "w");
5393  #else
5394  fout = fopen(fileName.c_str(), "w");
5395  #endif
5396 
5397  if(fout)
5398  {
5399  for(int i=0; i<prediction.rows; ++i)
5400  {
5401  for(int j=0; j<prediction.cols; ++j)
5402  {
5403  fprintf(fout, "%f ",((float*)prediction.data)[j + i*prediction.cols]);
5404  }
5405  fprintf(fout, "\n");
5406  }
5407  fclose(fout);
5408  }
5409  }
5410  else
5411  {
5412  UWARN("Memory and/or the Bayes filter are not created");
5413  }
5414 }
5415 
5416 Signature Rtabmap::getSignatureCopy(int id, bool images, bool scan, bool userData, bool occupancyGrid, bool withWords, bool withGlobalDescriptors) const
5417 {
5418  Signature s;
5419  if(_memory)
5420  {
5421  Transform odomPoseLocal;
5422  int weight = -1;
5423  int mapId = -1;
5424  std::string label;
5425  double stamp = 0;
5426  Transform groundTruth;
5427  std::vector<float> velocity;
5428  GPS gps;
5429  EnvSensors sensors;
5430  _memory->getNodeInfo(id, odomPoseLocal, mapId, weight, label, stamp, groundTruth, velocity, gps, sensors, true);
5431  SensorData data;
5432  data.setId(id);
5433  if(images || scan || userData || occupancyGrid)
5434  {
5435  data = _memory->getNodeData(id, images, scan, userData, occupancyGrid);
5436  }
5437  if(!images && withWords)
5438  {
5439  std::vector<CameraModel> models;
5440  std::vector<StereoCameraModel> stereoModels;
5441  _memory->getNodeCalibration(id, models, stereoModels);
5442  data.setCameraModels(models);
5443  data.setStereoCameraModels(stereoModels);
5444  }
5445 
5446  s=Signature(id,
5447  mapId,
5448  weight,
5449  stamp,
5450  label,
5451  odomPoseLocal,
5452  groundTruth,
5453  data);
5454 
5455  std::multimap<int, Link> links = _memory->getLinks(id, true, true);
5456  for(std::multimap<int, Link>::iterator iter=links.begin(); iter!=links.end(); ++iter)
5457  {
5458  if(iter->second.type() == Link::kLandmark)
5459  {
5460  s.addLandmark(iter->second);
5461  }
5462  else
5463  {
5464  s.addLink(iter->second);
5465  }
5466  }
5467 
5468  if(withWords || withGlobalDescriptors)
5469  {
5470  std::multimap<int, int> words;
5471  std::vector<cv::KeyPoint> wordsKpts;
5472  std::vector<cv::Point3f> words3;
5473  cv::Mat wordsDescriptors;
5474  std::vector<rtabmap::GlobalDescriptor> globalDescriptors;
5475  _memory->getNodeWordsAndGlobalDescriptors(id, words, wordsKpts, words3, wordsDescriptors, globalDescriptors);
5476  if(withWords)
5477  {
5478  s.setWords(words, wordsKpts, words3, wordsDescriptors);
5479  }
5480  if(withGlobalDescriptors)
5481  {
5482  s.sensorData().setGlobalDescriptors(globalDescriptors);
5483  }
5484  }
5485  if(velocity.size()==6)
5486  {
5487  s.setVelocity(velocity[0], velocity[1], velocity[2], velocity[3], velocity[4], velocity[5]);
5488  }
5489  s.sensorData().setGPS(gps);
5490  s.sensorData().setEnvSensors(sensors);
5491  }
5492  return s;
5493 }
5494 
5496  std::map<int, Signature> & signatures,
5497  std::map<int, Transform> & poses,
5498  std::multimap<int, Link> & constraints,
5499  bool optimized,
5500  bool global) const
5501 {
5502  UDEBUG("");
5503  return getGraph(poses, constraints, optimized, global, &signatures, true, true, true, true);
5504 }
5505 
5507  std::map<int, Transform> & poses,
5508  std::multimap<int, Link> & constraints,
5509  bool optimized,
5510  bool global,
5511  std::map<int, Signature> * signatures,
5512  bool withImages,
5513  bool withScan,
5514  bool withUserData,
5515  bool withGrid,
5516  bool withWords,
5517  bool withGlobalDescriptors) const
5518 {
5520  {
5521  if(_rgbdSlamMode)
5522  {
5523  if(optimized)
5524  {
5525  poses = _optimizedPoses; // guess
5526  cv::Mat covariance;
5527  this->optimizeCurrentMap(_memory->getLastWorkingSignature()->id(), global, poses, covariance, &constraints);
5528  if(!global && !_optimizedPoses.empty())
5529  {
5530  // We send directly the already optimized poses if they are set
5531  UDEBUG("_optimizedPoses=%ld poses=%ld", _optimizedPoses.size(), poses.size());
5532  poses = _optimizedPoses;
5533  }
5534  }
5535  else
5536  {
5537  std::map<int, int> ids = _memory->getNeighborsId(_memory->getLastWorkingSignature()->id(), 0, global?-1:0, true);
5538  _memory->getMetricConstraints(uKeysSet(ids), poses, constraints, global);
5539  }
5540  }
5541  else
5542  {
5543  // no optimization on appearance-only mode
5544  std::map<int, int> ids = _memory->getNeighborsId(_memory->getLastWorkingSignature()->id(), 0, global?-1:0, true);
5545  _memory->getMetricConstraints(uKeysSet(ids), poses, constraints, global);
5546  }
5547 
5548  if(signatures)
5549  {
5550  // Get data
5551  std::set<int> ids = uKeysSet(_memory->getWorkingMem()); // WM
5552 
5553  //remove virtual signature
5554  ids.erase(Memory::kIdVirtual);
5555 
5556  ids.insert(_memory->getStMem().begin(), _memory->getStMem().end()); // STM + WM
5557  if(global)
5558  {
5559  ids = _memory->getAllSignatureIds(); // STM + WM + LTM, ignoreChildren=true
5560  }
5561 
5562  for(std::set<int>::iterator iter = ids.begin(); iter!=ids.end(); ++iter)
5563  {
5564  signatures->insert(std::make_pair(*iter, getSignatureCopy(*iter, withImages, withScan, withUserData, withGrid, withWords, withGlobalDescriptors)));
5565  }
5566  }
5567  }
5568  else if(_memory && (_memory->getStMem().size() || _memory->getWorkingMem().size() > 1))
5569  {
5570  UERROR("Last working signature is null!?");
5571  }
5572  else if(_memory == 0)
5573  {
5574  UWARN("Memory not initialized...");
5575  }
5576 }
5577 
5578 std::map<int, Transform> Rtabmap::getNodesInRadius(const Transform & pose, float radius, int k, std::map<int, float> * distsSqr)
5579 {
5580  std::map<int, float> nearestNodesTmp;
5581  std::map<int, float> * nearestNodesPtr = distsSqr == 0? &nearestNodesTmp : distsSqr;
5582  *nearestNodesPtr = graph::findNearestNodes(pose, _optimizedPoses, radius<=0?_localRadius:radius, 0, k);
5583  std::map<int, Transform> nearestPoses;
5584  for(std::map<int, float>::iterator iter=nearestNodesPtr->begin(); iter!=nearestNodesPtr->end(); ++iter)
5585  {
5586  nearestPoses.insert(*_optimizedPoses.find(iter->first));
5587  }
5588  return nearestPoses;
5589 }
5590 
5591 std::map<int, Transform> Rtabmap::getNodesInRadius(int nodeId, float radius, int k, std::map<int, float> * distsSqr)
5592 {
5593  UDEBUG("nodeId=%d, radius=%f", nodeId, radius);
5594  std::map<int, float> nearestNodesTmp;
5595  std::map<int, float> * nearestNodesPtr = distsSqr == 0? &nearestNodesTmp : distsSqr;
5597  {
5598  *nearestNodesPtr = graph::findNearestNodes(_lastLocalizationPose, _optimizedPoses, radius<=0?_localRadius:radius, 0, k);
5599  }
5600  else
5601  {
5602  if(nodeId==0 && !_optimizedPoses.empty())
5603  {
5604  nodeId = _optimizedPoses.rbegin()->first;
5605  }
5606 
5607  if(_optimizedPoses.find(nodeId) != _optimizedPoses.end())
5608  {
5609  *nearestNodesPtr = graph::findNearestNodes(nodeId, _optimizedPoses, radius<=0?_localRadius:radius, 0, k);
5610  }
5611  }
5612 
5613  std::map<int, Transform> nearestPoses;
5614  for(std::map<int, float>::iterator iter=nearestNodesPtr->begin(); iter!=nearestNodesPtr->end(); ++iter)
5615  {
5616  nearestPoses.insert(*_optimizedPoses.find(iter->first));
5617  }
5618 
5619  return nearestPoses;
5620 }
5621 
5623  float clusterRadiusMax,
5624  float clusterAngle,
5625  int iterations,
5626  bool intraSession,
5627  bool interSession,
5628  const ProgressState * processState,
5629  float clusterRadiusMin)
5630 {
5631  UASSERT(iterations>0);
5632 
5633  if(_graphOptimizer->iterations() <= 0)
5634  {
5635  UERROR("Cannot detect more loop closures if graph optimization iterations = 0");
5636  return -1;
5637  }
5638  if(!_rgbdSlamMode)
5639  {
5640  UERROR("Detecting more loop closures can be done only in RGBD-SLAM mode.");
5641  return -1;
5642  }
5643  if(!intraSession && !interSession)
5644  {
5645  UERROR("Intra and/or inter session argument should be true.");
5646  return -1;
5647  }
5648 
5649  std::list<Link> loopClosuresAdded;
5650  std::multimap<int, int> checkedLoopClosures;
5651 
5652  std::map<int, Transform> posesToCheckLoopClosures;
5653  std::map<int, Transform> poses;
5654  std::multimap<int, Link> links;
5655  std::map<int, Signature> signatures; // some signatures may be in LTM, get them all
5656  this->getGraph(poses, links, true, true, &signatures);
5657 
5658  std::map<int, int> mapIds;
5659  UDEBUG("remove all invalid or intermediate nodes, fill mapIds");
5660  for(std::map<int, Transform>::iterator iter=poses.upper_bound(0); iter!=poses.end();++iter)
5661  {
5662  if(signatures.at(iter->first).getWeight() >= 0)
5663  {
5664  posesToCheckLoopClosures.insert(*iter);
5665  mapIds.insert(std::make_pair(iter->first, signatures.at(iter->first).mapId()));
5666  }
5667  }
5668 
5669  for(int n=0; n<iterations; ++n)
5670  {
5671  UINFO("Looking for more loop closures, clustering poses... (iteration=%d/%d, radius=%f m angle=%f rad)",
5672  n+1, iterations, clusterRadiusMax, clusterAngle);
5673 
5674  std::multimap<int, int> clusters = graph::radiusPosesClustering(
5675  posesToCheckLoopClosures,
5676  clusterRadiusMax,
5677  clusterAngle);
5678 
5679  UINFO("Looking for more loop closures, clustering poses... found %d clusters.", (int)clusters.size());
5680 
5681  int i=0;
5682  std::set<int> addedLinks;
5683  for(std::multimap<int, int>::iterator iter=clusters.begin(); iter!= clusters.end(); ++iter, ++i)
5684  {
5685  if(processState && processState->isCanceled())
5686  {
5687  return -1;
5688  break;
5689  }
5690 
5691  int from = iter->first;
5692  int to = iter->second;
5693  if(from > to)
5694  {
5695  from = iter->second;
5696  to = iter->first;
5697  }
5698 
5699  int mapIdFrom = uValue(mapIds, from, 0);
5700  int mapIdTo = uValue(mapIds, to, 0);
5701 
5702  if((interSession && mapIdFrom != mapIdTo) ||
5703  (intraSession && mapIdFrom == mapIdTo))
5704  {
5705 
5706  bool alreadyChecked = false;
5707  for(std::multimap<int, int>::iterator jter = checkedLoopClosures.lower_bound(from);
5708  !alreadyChecked && jter!=checkedLoopClosures.end() && jter->first == from;
5709  ++jter)
5710  {
5711  if(to == jter->second)
5712  {
5713  alreadyChecked = true;
5714  }
5715  }
5716 
5717  if(!alreadyChecked)
5718  {
5719  // only add new links and one per cluster per iteration
5720  if(addedLinks.find(from) == addedLinks.end() &&
5721  addedLinks.find(to) == addedLinks.end() &&
5722  rtabmap::graph::findLink(links, from, to) == links.end())
5723  {
5724  // Reverify if in the bounds with the current optimized graph
5725  Transform delta = poses.at(from).inverse() * poses.at(to);
5726  if(delta.getNorm() < clusterRadiusMax &&
5727  delta.getNorm() >= clusterRadiusMin)
5728  {
5729  checkedLoopClosures.insert(std::make_pair(from, to));
5730 
5731  UASSERT(signatures.find(from) != signatures.end());
5732  UASSERT(signatures.find(to) != signatures.end());
5733 
5734  Transform guess;
5735  if(_proximityBySpace && uContains(poses, from) && uContains(poses, to))
5736  {
5737  guess = poses.at(from).inverse() * poses.at(to);
5738  }
5739 
5741  // use signatures instead of IDs because some signatures may not be in WM
5742  Transform t = _memory->computeTransform(signatures.at(from), signatures.at(to), guess, &info);
5743 
5744  if(!t.isNull())
5745  {
5746  bool updateConstraints = true;
5747 
5748  //optimize the graph to see if the new constraint is globally valid
5749 
5750  int fromId = from;
5751  int mapId = signatures.at(from).mapId();
5752  // use first node of the map containing from
5753  for(std::map<int, Signature>::iterator ster=signatures.begin(); ster!=signatures.end(); ++ster)
5754  {
5755  if(ster->second.mapId() == mapId)
5756  {
5757  fromId = ster->first;
5758  break;
5759  }
5760  }
5761  std::multimap<int, Link> linksIn = links;
5762  linksIn.insert(std::make_pair(from, Link(from, to, Link::kUserClosure, t, getInformation(info.covariance))));
5763  const Link * maxLinearLink = 0;
5764  const Link * maxAngularLink = 0;
5765  float maxLinearError = 0.0f;
5766  float maxAngularError = 0.0f;
5767  float maxLinearErrorRatio = 0.0f;
5768  float maxAngularErrorRatio = 0.0f;
5769  std::map<int, Transform> optimizedPoses;
5770  std::multimap<int, Link> links;
5771  UASSERT(poses.find(fromId) != poses.end());
5772  UASSERT_MSG(poses.find(from) != poses.end(), uFormat("id=%d poses=%d links=%d", from, (int)poses.size(), (int)links.size()).c_str());
5773  UASSERT_MSG(poses.find(to) != poses.end(), uFormat("id=%d poses=%d links=%d", to, (int)poses.size(), (int)links.size()).c_str());
5774  _graphOptimizer->getConnectedGraph(fromId, poses, linksIn, optimizedPoses, links);
5775  UASSERT(optimizedPoses.find(fromId) != optimizedPoses.end());
5776  UASSERT_MSG(optimizedPoses.find(from) != optimizedPoses.end(), uFormat("id=%d poses=%d links=%d", from, (int)optimizedPoses.size(), (int)links.size()).c_str());
5777  UASSERT_MSG(optimizedPoses.find(to) != optimizedPoses.end(), uFormat("id=%d poses=%d links=%d", to, (int)optimizedPoses.size(), (int)links.size()).c_str());
5778  UASSERT(graph::findLink(links, from, to) != links.end());
5779  optimizedPoses = _graphOptimizer->optimize(fromId, optimizedPoses, links);
5780  std::string msg;
5781  if(optimizedPoses.size())
5782  {
5784  optimizedPoses,
5785  links,
5786  maxLinearErrorRatio,
5787  maxAngularErrorRatio,
5788  maxLinearError,
5789  maxAngularError,
5790  &maxLinearLink,
5791  &maxAngularLink);
5792  if(maxLinearLink)
5793  {
5794  UINFO("Max optimization linear error = %f m (link %d->%d)", maxLinearError, maxLinearLink->from(), maxLinearLink->to());
5795  if(_optimizationMaxError > 0.0f && maxLinearErrorRatio > _optimizationMaxError)
5796  {
5797  msg = uFormat("Rejecting edge %d->%d because "
5798  "graph error is too large after optimization (%f m for edge %d->%d with ratio %f > std=%f m). "
5799  "\"%s\" is %f.",
5800  from,
5801  to,
5802  maxLinearError,
5803  maxLinearLink->from(),
5804  maxLinearLink->to(),
5805  maxLinearErrorRatio,
5806  sqrt(maxLinearLink->transVariance()),
5807  Parameters::kRGBDOptimizeMaxError().c_str(),
5809  }
5810  else if(_optimizationMaxError == 0.0f && maxLinearErrorRatio>100 && !_graphOptimizer->isRobust())
5811  {
5812  UERROR("Huge optimization error detected!"
5813  "Linear error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). You may consider "
5814  "enabling \"%s\" to reject those bad optimizations by setting it to a non null value!",
5815  maxLinearErrorRatio,
5816  maxLinearLink->from(),
5817  maxLinearLink->to(),
5818  maxLinearLink->type(),
5819  maxLinearError,
5820  sqrt(maxLinearLink->transVariance()),
5821  Parameters::kRGBDOptimizeMaxError().c_str());
5822  }
5823  }
5824  else if(maxAngularLink)
5825  {
5826  UINFO("Max optimization angular error = %f deg (link %d->%d)", maxAngularError*180.0f/M_PI, maxAngularLink->from(), maxAngularLink->to());
5827  if(_optimizationMaxError > 0.0f && maxAngularErrorRatio > _optimizationMaxError)
5828  {
5829  msg = uFormat("Rejecting edge %d->%d because "
5830  "graph error is too large after optimization (%f deg for edge %d->%d with ratio %f > std=%f deg). "
5831  "\"%s\" is %f m.",
5832  from,
5833  to,
5834  maxAngularError*180.0f/M_PI,
5835  maxAngularLink->from(),
5836  maxAngularLink->to(),
5837  maxAngularErrorRatio,
5838  sqrt(maxAngularLink->rotVariance()),
5839  Parameters::kRGBDOptimizeMaxError().c_str(),
5841  }
5842  else if(_optimizationMaxError == 0.0f && maxAngularErrorRatio>100 && !_graphOptimizer->isRobust())
5843  {
5844  UERROR("Huge optimization error detected!"
5845  "Angular error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). You may consider "
5846  "enabling \"%s\" to reject those bad optimizations by setting it to a non null value!",
5847  maxAngularErrorRatio,
5848  maxAngularLink->from(),
5849  maxAngularLink->to(),
5850  maxAngularLink->type(),
5851  maxAngularError*180.0f/CV_PI,
5852  sqrt(maxAngularLink->rotVariance()),
5853  Parameters::kRGBDOptimizeMaxError().c_str());
5854  }
5855  }
5856  }
5857  else
5858  {
5859  msg = uFormat("Rejecting edge %d->%d because graph optimization has failed!",
5860  from,
5861  to);
5862  }
5863  if(!msg.empty())
5864  {
5865  UWARN("%s", msg.c_str());
5866  updateConstraints = false;
5867  }
5868  else
5869  {
5870  poses = optimizedPoses;
5871  }
5872 
5873  if(updateConstraints)
5874  {
5875  addedLinks.insert(from);
5876  addedLinks.insert(to);
5877  cv::Mat inf = getInformation(info.covariance);
5878  links.insert(std::make_pair(from, Link(from, to, Link::kUserClosure, t, inf)));
5879  loopClosuresAdded.push_back(Link(from, to, Link::kUserClosure, t, inf));
5880  std::string msg = uFormat("Iteration %d/%d: Added loop closure %d->%d! (%d/%d)", n+1, iterations, from, to, i+1, (int)clusters.size());
5881  UINFO(msg.c_str());
5882 
5883  if(processState)
5884  {
5885  UINFO(msg.c_str());
5886  if(!processState->callback(msg))
5887  {
5888  return -1;
5889  }
5890  }
5891  }
5892  }
5893  }
5894  }
5895  }
5896  }
5897  }
5898 
5899  if(processState)
5900  {
5901  std::string msg = uFormat("Iteration %d/%d: Detected %d total loop closures!", n+1, iterations, (int)addedLinks.size()/2);
5902  UINFO(msg.c_str());
5903  if(!processState->callback(msg))
5904  {
5905  return -1;
5906  }
5907  }
5908  else
5909  {
5910  UINFO("Iteration %d/%d: Detected %d total loop closures!", n+1, iterations, (int)addedLinks.size()/2);
5911  }
5912 
5913  if(addedLinks.size() == 0)
5914  {
5915  break;
5916  }
5917 
5918  UINFO("Optimizing graph with new links (%d nodes, %d constraints)...",
5919  (int)poses.size(), (int)links.size());
5920  int fromId = _optimizeFromGraphEnd?poses.rbegin()->first:poses.begin()->first;
5921  poses = _graphOptimizer->optimize(fromId, poses, links, 0);
5922  if(poses.size() == 0)
5923  {
5924  UERROR("Optimization failed! Rejecting all loop closures...");
5925  loopClosuresAdded.clear();
5926  return -1;
5927  }
5928  UINFO("Optimizing graph with new links... done!");
5929  }
5930  UINFO("Total added %d loop closures.", (int)loopClosuresAdded.size());
5931 
5932  if(loopClosuresAdded.size())
5933  {
5934  for(std::list<Link>::iterator iter=loopClosuresAdded.begin(); iter!=loopClosuresAdded.end(); ++iter)
5935  {
5936  _memory->addLink(*iter, true);
5937  }
5938  // Update optimized poses
5939  for(std::map<int, Transform>::iterator iter=_optimizedPoses.begin(); iter!=_optimizedPoses.end(); ++iter)
5940  {
5941  std::map<int, Transform>::iterator jter = poses.find(iter->first);
5942  if(jter != poses.end())
5943  {
5944  iter->second = jter->second;
5945  }
5946  }
5947  std::map<int, Transform> tmp;
5948  // Update also the links if some have been added in WM
5950  // This will force rtabmap_ros to regenerate the global occupancy grid if there was one
5951  _memory->save2DMap(cv::Mat(), 0, 0, 0);
5952  }
5953  return (int)loopClosuresAdded.size();
5954 }
5955 
5957  int optimizerType,
5958  bool rematchFeatures,
5959  int iterations,
5960  float pixelVariance)
5961 {
5962  if(!_optimizedPoses.empty() && !_constraints.empty())
5963  {
5964  int iterations = Parameters::defaultOptimizerIterations();
5965  float pixelVariance = Parameters::defaultg2oPixelVariance();
5967  Parameters::parse(params, Parameters::kOptimizerIterations(), iterations);
5968  Parameters::parse(params, Parameters::kg2oPixelVariance(), pixelVariance);
5969  if(iterations > 0)
5970  {
5971  uInsert(params, ParametersPair(Parameters::kOptimizerIterations(), uNumber2Str(iterations)));
5972  }
5973  if(pixelVariance > 0.0f)
5974  {
5975  uInsert(params, ParametersPair(Parameters::kg2oPixelVariance(), uNumber2Str(pixelVariance)));
5976  }
5977 
5978  std::map<int, Signature> signatures;
5979  for(std::map<int, Transform>::iterator iter=_optimizedPoses.lower_bound(1); iter!=_optimizedPoses.end(); ++iter)
5980  {
5981  if(_memory->getSignature(iter->first))
5982  {
5983  signatures.insert(std::make_pair(iter->first, *_memory->getSignature(iter->first)));
5984  }
5985  }
5986 
5987  Optimizer * optimizer = Optimizer::create((Optimizer::Type)optimizerType, params);
5988  std::map<int, Transform> poses = optimizer->optimizeBA(
5989  _optimizeFromGraphEnd?_optimizedPoses.lower_bound(1)->first:_optimizedPoses.rbegin()->first,
5991  _constraints,
5992  signatures,
5993  rematchFeatures);
5994  delete optimizer;
5995 
5996  if(poses.empty())
5997  {
5998  UERROR("Optimization failed!");
5999  }
6000  else
6001  {
6002  _optimizedPoses = poses;
6003  // This will force rtabmap_ros to regenerate the global occupancy grid if there was one
6004  _memory->save2DMap(cv::Mat(), 0, 0, 0);
6005  return true;
6006  }
6007  }
6008  else
6009  {
6010  UERROR("Optimized poses (%ld) or constraints (%ld) are empty!", _optimizedPoses.size(), _constraints.size());
6011  }
6012  return false;
6013 }
6014 
6016  const std::map<int, Transform> & poses,
6017  const cv::Mat & map,
6018  float xMin,
6019  float yMin,
6020  float cellSize,
6021  int cropRadius,
6022  bool filterScans)
6023 {
6024  if(_memory)
6025  {
6026  return _memory->cleanupLocalGrids(
6027  poses,
6028  map,
6029  xMin,
6030  yMin,
6031  cellSize,
6032  cropRadius,
6033  filterScans);
6034  }
6035  return -1;
6036 }
6037 
6039 {
6040  if(!_rgbdSlamMode)
6041  {
6042  UERROR("Refining links can be done only in RGBD-SLAM mode.");
6043  return -1;
6044  }
6045 
6046  std::list<Link> linksRefined;
6047 
6048  std::map<int, Transform> poses;
6049  std::multimap<int, Link> links;
6050  std::map<int, Signature> signatures;
6051  this->getGraph(poses, links, false, true, &signatures);
6052 
6053  int i=0;
6054  for(std::multimap<int, Link>::iterator iter=links.lower_bound(1); iter!= links.end(); ++iter)
6055  {
6056  int from = iter->second.from();
6057  int to = iter->second.to();
6058 
6059  UASSERT(signatures.find(from) != signatures.end());
6060  UASSERT(signatures.find(to) != signatures.end());
6061 
6063  // use signatures instead of IDs because some signatures may not be in WM
6064  Transform t = _memory->computeTransform(signatures.at(from), signatures.at(to), iter->second.transform(), &info);
6065 
6066  if(!t.isNull())
6067  {
6068  linksRefined.push_back(Link(from, to, iter->second.type(), t, info.covariance.inv()));
6069  UINFO("Refined link %d->%d! (%d/%d)", from, to, ++i, (int)links.size());
6070  }
6071  }
6072  UINFO("Total refined %d links.", (int)linksRefined.size());
6073 
6074  if(linksRefined.size())
6075  {
6076  for(std::list<Link>::iterator iter=linksRefined.begin(); iter!=linksRefined.end(); ++iter)
6077  {
6078  _memory->updateLink(*iter, true);
6079  }
6080  }
6081  return (int)linksRefined.size();
6082 }
6083 
6084 bool Rtabmap::addLink(const Link & link)
6085 {
6086  const Transform & t = link.transform();
6087  if(!_rgbdSlamMode)
6088  {
6089  UERROR("Adding new link can be done only in RGBD-SLAM mode.");
6090  return false;
6091  }
6092  if(!_memory)
6093  {
6094  UERROR("Memory is not initialized.");
6095  return false;
6096  }
6097  if(t.isNull())
6098  {
6099  UERROR("Link's transform is null! (%d->%d type=%s)", link.from(), link.to(), link.typeName().c_str());
6100  return false;
6101  }
6102  if(_memory->isIncremental())
6103  {
6104  if(_memory->getSignature(link.from()) == 0)
6105  {
6106  UERROR("Link's \"from id\" %d is not in working memory", link.from());
6107  return false;
6108  }
6109  if(_memory->getSignature(link.to()) == 0)
6110  {
6111  UERROR("Link's \"to id\" %d is not in working memory", link.to());
6112  return false;
6113  }
6114 
6115  if(_optimizedPoses.find(link.from()) == _optimizedPoses.end() &&
6116  _optimizedPoses.find(link.to()) == _optimizedPoses.end())
6117  {
6118  UERROR("Neither nodes %d or %d are in the local graph (size=%d). One of the 2 nodes should be in the local graph.", (int)_optimizedPoses.size(), link.from(), link.to());
6119  return false;
6120  }
6121 
6122  // add temporary the link
6123  if(!_memory->addLink(link))
6124  {
6125  UERROR("Cannot add new link %d->%d to memory", link.from(), link.to());
6126  return false;
6127  }
6128 
6129  // optimize with new link
6130  std::map<int, Transform> poses = _optimizedPoses;
6131  std::multimap<int, Link> links;
6132  cv::Mat covariance;
6133  optimizeCurrentMap(this->getLastLocationId(), false, poses, covariance, &links);
6134 
6135  if(poses.find(link.from()) == poses.end())
6136  {
6137  UERROR("Link's \"from id\" %d is not in the graph (size=%d)", link.from(), (int)poses.size());
6138  _memory->removeLink(link.from(), link.to());
6139  return false;
6140  }
6141  if(poses.find(link.to()) == poses.end())
6142  {
6143  UERROR("Link's \"to id\" %d is not in the graph (size=%d)", link.to(), (int)poses.size());
6144  _memory->removeLink(link.from(), link.to());
6145  return false;
6146  }
6147 
6148  std::string msg;
6149  if(poses.empty())
6150  {
6151  msg = uFormat("Rejecting edge %d->%d because graph optimization has failed!", link.from(), link.to());
6152  }
6153  else
6154  {
6155  float maxLinearError = 0.0f;
6156  float maxLinearErrorRatio = 0.0f;
6157  float maxAngularError = 0.0f;
6158  float maxAngularErrorRatio = 0.0f;
6159  const Link * maxLinearLink = 0;
6160  const Link * maxAngularLink = 0;
6161 
6163  poses,
6164  links,
6165  maxLinearErrorRatio,
6166  maxAngularErrorRatio,
6167  maxLinearError,
6168  maxAngularError,
6169  &maxLinearLink,
6170  &maxAngularLink);
6171  if(maxLinearLink)
6172  {
6173  UINFO("Max optimization linear error = %f m (link %d->%d)", maxLinearError, maxLinearLink->from(), maxLinearLink->to());
6174  if(_optimizationMaxError > 0.0f && maxLinearErrorRatio > _optimizationMaxError)
6175  {
6176  msg = uFormat("Rejecting edge %d->%d because "
6177  "graph error is too large after optimization (%f m for edge %d->%d with ratio %f > std=%f m). "
6178  "\"%s\" is %f.",
6179  link.from(),
6180  link.to(),
6181  maxLinearError,
6182  maxLinearLink->from(),
6183  maxLinearLink->to(),
6184  maxLinearErrorRatio,
6185  sqrt(maxLinearLink->transVariance()),
6186  Parameters::kRGBDOptimizeMaxError().c_str(),
6188  }
6189  else if(_optimizationMaxError == 0.0f && maxLinearErrorRatio>100 && !_graphOptimizer->isRobust())
6190  {
6191  UERROR("Huge optimization error detected!"
6192  "Linear error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). You may consider "
6193  "enabling \"%s\" to reject those bad optimizations by setting it to a non null value!",
6194  maxLinearErrorRatio,
6195  maxLinearLink->from(),
6196  maxLinearLink->to(),
6197  maxLinearLink->type(),
6198  maxLinearError,
6199  sqrt(maxLinearLink->transVariance()),
6200  Parameters::kRGBDOptimizeMaxError().c_str());
6201  }
6202  }
6203  else if(maxAngularLink)
6204  {
6205  UINFO("Max optimization angular error = %f deg (link %d->%d)", maxAngularError*180.0f/M_PI, maxAngularLink->from(), maxAngularLink->to());
6206  if(_optimizationMaxError > 0.0f && maxAngularErrorRatio > _optimizationMaxError)
6207  {
6208  msg = uFormat("Rejecting edge %d->%d because "
6209  "graph error is too large after optimization (%f deg for edge %d->%d with ratio %f > std=%f deg). "
6210  "\"%s\" is %f m.",
6211  link.from(),
6212  link.to(),
6213  maxAngularError*180.0f/M_PI,
6214  maxAngularLink->from(),
6215  maxAngularLink->to(),
6216  maxAngularErrorRatio,
6217  sqrt(maxAngularLink->rotVariance()),
6218  Parameters::kRGBDOptimizeMaxError().c_str(),
6220  }
6221  else if(_optimizationMaxError == 0.0f && maxAngularErrorRatio>100 && !_graphOptimizer->isRobust())
6222  {
6223  UERROR("Huge optimization error detected!"
6224  "Angular error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). You may consider "
6225  "enabling \"%s\" to reject those bad optimizations by setting it to a non null value!",
6226  maxAngularErrorRatio,
6227  maxAngularLink->from(),
6228  maxAngularLink->to(),
6229  maxAngularLink->type(),
6230  maxAngularError*180.0f/CV_PI,
6231  sqrt(maxAngularLink->rotVariance()),
6232  Parameters::kRGBDOptimizeMaxError().c_str());
6233  }
6234  }
6235  }
6236  if(!msg.empty())
6237  {
6238  UERROR("%s", msg.c_str());
6239  _memory->removeLink(link.from(), link.to());
6240  return false;
6241  }
6242 
6243  // Update optimized poses
6244  for(std::map<int, Transform>::iterator iter=_optimizedPoses.begin(); iter!=_optimizedPoses.end(); ++iter)
6245  {
6246  std::map<int, Transform>::iterator jter = poses.find(iter->first);
6247  if(jter != poses.end())
6248  {
6249  iter->second = jter->second;
6250  }
6251  }
6253  {
6254  _mapCorrection = _optimizedPoses.rbegin()->second * _memory->getSignature(_optimizedPoses.rbegin()->first)->getPose().inverse();
6255  }
6256 
6257  std::map<int, Transform> tmp;
6258  // Update also the links if some have been added in WM
6260  // This will force rtabmap_ros to regenerate the global occupancy grid if there was one
6261  _memory->save2DMap(cv::Mat(), 0, 0, 0);
6262 
6263  return true;
6264  }
6265  else // localization mode
6266  {
6267  int oldestId = link.from()>link.to()?link.to():link.from();
6268  int newestId = link.from()<link.to()?link.to():link.from();
6269 
6270  if(_memory->getSignature(oldestId) == 0)
6271  {
6272  UERROR("Link's id %d is not in working memory", oldestId);
6273  return false;
6274  }
6275  if(_optimizedPoses.find(oldestId) == _optimizedPoses.end())
6276  {
6277  UERROR("Link's id %d is not in the optimized graph (_optimizedPoses=%d)", oldestId, (int)_optimizedPoses.size());
6278  return false;
6279  }
6281  {
6282  UERROR("Adding link with %s=true in localization mode is not supported.", Parameters::kRGBDOptimizeFromGraphEnd().c_str());
6283  return false;
6284  }
6285  if(_odomCachePoses.find(newestId) == _odomCachePoses.end())
6286  {
6287  if(!_odomCachePoses.empty())
6288  {
6289  UERROR("Link's id %d is not in the odometry cache (oldest=%d, newest=%d, %s=%d)",
6290  newestId,
6291  _odomCachePoses.begin()->first,
6292  _odomCachePoses.rbegin()->first,
6293  Parameters::kRGBDMaxOdomCacheSize().c_str(),
6295  }
6296  else
6297  {
6298  UERROR("Link's id %d is not in the odometry cache (%s=%d).",
6299  newestId,
6300  Parameters::kRGBDMaxOdomCacheSize().c_str(),
6302  }
6303  return false;
6304  }
6305 
6306  // Verify if the new localization is valid by checking if there is
6307  // not too much deformation using current odometry poses
6308  // This will also refine localization links
6309 
6310  std::map<int, Transform> poses = _odomCachePoses;
6311  std::multimap<int, Link> constraints = _odomCacheConstraints;
6312  constraints.insert(std::make_pair(link.from(), link));
6313  for(std::multimap<int, Link>::iterator iter=constraints.begin(); iter!=constraints.end(); ++iter)
6314  {
6315  std::map<int, Transform>::iterator iterPose = _optimizedPoses.find(iter->second.to());
6316  if(iterPose != _optimizedPoses.end() && poses.find(iterPose->first) == poses.end())
6317  {
6318  poses.insert(*iterPose);
6319  // make the poses in the map fixed
6320  constraints.insert(std::make_pair(iterPose->first, Link(iterPose->first, iterPose->first, Link::kPosePrior, iterPose->second, cv::Mat::eye(6,6, CV_64FC1)*999999)));
6321  }
6322  }
6323 
6324  std::map<int, Transform> posesOut;
6325  std::multimap<int, Link> edgeConstraintsOut;
6326  bool priorsIgnored = _graphOptimizer->priorsIgnored();
6327  _graphOptimizer->setPriorsIgnored(false); //temporary set false to use priors above to fix nodes of the map
6328  _graphOptimizer->getConnectedGraph(newestId, poses, constraints, posesOut, edgeConstraintsOut);
6329  std::map<int, Transform> optPoses = _graphOptimizer->optimize(poses.begin()->first, posesOut, edgeConstraintsOut);
6330  _graphOptimizer->setPriorsIgnored(priorsIgnored); // set back
6331 
6332  bool rejectLocalization = false;
6333  if(optPoses.empty())
6334  {
6335  UWARN("Optimization failed, rejecting localization!");
6336  rejectLocalization = true;
6337  }
6338  else
6339  {
6340  UINFO("Compute max graph errors...");
6341  float maxLinearError = 0.0f;
6342  float maxLinearErrorRatio = 0.0f;
6343  float maxAngularError = 0.0f;
6344  float maxAngularErrorRatio = 0.0f;
6345  const Link * maxLinearLink = 0;
6346  const Link * maxAngularLink = 0;
6348  optPoses,
6349  edgeConstraintsOut,
6350  maxLinearErrorRatio,
6351  maxAngularErrorRatio,
6352  maxLinearError,
6353  maxAngularError,
6354  &maxLinearLink,
6355  &maxAngularLink,
6357  if(maxLinearLink == 0 && maxAngularLink==0)
6358  {
6359  UWARN("Could not compute graph errors! Wrong loop closures could be accepted!");
6360  }
6361 
6362  if(maxLinearLink)
6363  {
6364  UINFO("Max optimization linear error = %f m (link %d->%d, var=%f, ratio error/std=%f)", maxLinearError, maxLinearLink->from(), maxLinearLink->to(), maxLinearLink->transVariance(), maxLinearError/sqrt(maxLinearLink->transVariance()));
6365  if(_optimizationMaxError > 0.0f && maxLinearErrorRatio > _optimizationMaxError)
6366  {
6367  UWARN("Rejecting localization (%d <-> %d) in this "
6368  "iteration because a wrong loop closure has been "
6369  "detected after graph optimization, resulting in "
6370  "a maximum graph error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). The "
6371  "maximum error ratio parameter \"%s\" is %f of std deviation.",
6372  link.from(),
6373  link.to(),
6374  maxLinearErrorRatio,
6375  maxLinearLink->from(),
6376  maxLinearLink->to(),
6377  maxLinearLink->type(),
6378  maxLinearError,
6379  sqrt(maxLinearLink->transVariance()),
6380  Parameters::kRGBDOptimizeMaxError().c_str(),
6382  rejectLocalization = true;
6383  }
6384  else if(_optimizationMaxError == 0.0f && maxLinearErrorRatio>100 && !_graphOptimizer->isRobust())
6385  {
6386  UERROR("Huge optimization error detected!"
6387  "Linear error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). You may consider "
6388  "enabling \"%s\" to reject those bad optimizations by setting it to a non null value!",
6389  maxLinearErrorRatio,
6390  maxLinearLink->from(),
6391  maxLinearLink->to(),
6392  maxLinearLink->type(),
6393  maxLinearError,
6394  sqrt(maxLinearLink->transVariance()),
6395  Parameters::kRGBDOptimizeMaxError().c_str());
6396  }
6397  }
6398  if(maxAngularLink)
6399  {
6400  UINFO("Max optimization angular error = %f deg (link %d->%d, var=%f, ratio error/std=%f)", maxAngularError*180.0f/CV_PI, maxAngularLink->from(), maxAngularLink->to(), maxAngularLink->rotVariance(), maxAngularError/sqrt(maxAngularLink->rotVariance()));
6401  if(_optimizationMaxError > 0.0f && maxAngularErrorRatio > _optimizationMaxError)
6402  {
6403  UWARN("Rejecting localization (%d <-> %d) in this "
6404  "iteration because a wrong loop closure has been "
6405  "detected after graph optimization, resulting in "
6406  "a maximum graph error ratio of %f (edge %d->%d, type=%d, abs error=%f deg, stddev=%f). The "
6407  "maximum error ratio parameter \"%s\" is %f of std deviation.",
6408  link.from(),
6409  link.to(),
6410  maxAngularErrorRatio,
6411  maxAngularLink->from(),
6412  maxAngularLink->to(),
6413  maxAngularLink->type(),
6414  maxAngularError*180.0f/CV_PI,
6415  sqrt(maxAngularLink->rotVariance()),
6416  Parameters::kRGBDOptimizeMaxError().c_str(),
6418  rejectLocalization = true;
6419  }
6420  else if(_optimizationMaxError == 0.0f && maxAngularErrorRatio>100 && !_graphOptimizer->isRobust())
6421  {
6422  UERROR("Huge optimization error detected!"
6423  "Angular error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). You may consider "
6424  "enabling \"%s\" to reject those bad optimizations by setting it to a non null value!",
6425  maxAngularErrorRatio,
6426  maxAngularLink->from(),
6427  maxAngularLink->to(),
6428  maxAngularLink->type(),
6429  maxAngularError*180.0f/CV_PI,
6430  sqrt(maxAngularLink->rotVariance()),
6431  Parameters::kRGBDOptimizeMaxError().c_str());
6432  }
6433  }
6434  }
6435 
6436  if(!rejectLocalization)
6437  {
6438  Transform newOptPoseInv = optPoses.at(link.from()).inverse();
6439  Transform newT = newOptPoseInv * optPoses.at(link.to());
6440  Link linkTmp = link;
6441  linkTmp.setTransform(newT);
6442  if(oldestId == link.from())
6443  {
6444  _lastLocalizationPose = _optimizedPoses.at(link.from()) * linkTmp.transform();
6445  _odomCacheConstraints.insert(std::make_pair(linkTmp.to(), linkTmp.inverse()));
6446  }
6447  else
6448  {
6449  _lastLocalizationPose = _optimizedPoses.at(link.to()) * linkTmp.transform().inverse();
6450  _odomCacheConstraints.insert(std::make_pair(linkTmp.from(), linkTmp));
6451  }
6452  UINFO("Set _lastLocalizationPose=%s", _lastLocalizationPose.prettyPrint().c_str());
6453  if(_graphOptimizer->isSlam2d())
6454  {
6455  // transform constraint to 2D
6457  }
6458  Transform odomPose = _odomCachePoses.find(newestId)->second;
6460  _lastLocalizationNodeId = oldestId;
6461  return true;
6462  }
6463  }
6464  return false;
6465 }
6466 
6467 cv::Mat Rtabmap::getInformation(const cv::Mat & covariance) const
6468 {
6469  cv::Mat information = covariance.inv();
6470  if(_loopCovLimited)
6471  {
6472  const std::vector<double> & odomMaxInf = _memory->getOdomMaxInf();
6473  if(odomMaxInf.size() == 6)
6474  {
6475  for(int i=0; i<6; ++i)
6476  {
6477  if(information.at<double>(i,i) > odomMaxInf[i])
6478  {
6479  information.at<double>(i,i) = odomMaxInf[i];
6480  }
6481  }
6482  }
6483  }
6484  return information;
6485 }
6486 
6487 void Rtabmap::addNodesToRepublish(const std::vector<int> & ids)
6488 {
6489  if(ids.empty())
6490  {
6491  _nodesToRepublish.clear();
6492  }
6494  {
6495  _nodesToRepublish.insert(ids.begin(), ids.end());
6496  }
6497  else if(_maxRepublished == 0)
6498  {
6499  UWARN("%s=0, so cannot republish the %d requested nodes.", Parameters::kRtabmapMaxRepublished().c_str(), (int)ids.size());
6500  }
6501  else //_publishLastSignatureData=false
6502  {
6503  UWARN("%s=false, so cannot republish the %d requested nodes.", Parameters::kRtabmapPublishLastSignature().c_str(), (int)ids.size());
6504  }
6505 }
6506 
6507 void Rtabmap::clearPath(int status)
6508 {
6509  UINFO("status=%d", status);
6510  _pathStatus = status;
6511  _path.clear();
6513  _pathGoalIndex = 0;
6515  _pathUnreachableNodes.clear();
6516  _pathStuckCount = 0;
6517  _pathStuckDistance = 0.0f;
6518  if(_memory)
6519  {
6521  }
6522 }
6523 
6524 // return true if path is updated
6525 bool Rtabmap::computePath(int targetNode, bool global)
6526 {
6527  this->clearPath(0);
6528 
6529  if(targetNode>0)
6530  {
6531  UINFO("Planning a path to node %d (global=%d)", targetNode, global?1:0);
6532  }
6533  else
6534  {
6535  UINFO("Planning a path to landmark %d (global=%d)", -targetNode, global?1:0);
6536  }
6537 
6538  if(!_rgbdSlamMode)
6539  {
6540  UWARN("A path can only be computed in RGBD-SLAM mode");
6541  return false;
6542  }
6543 
6544  UTimer totalTimer;
6545  UTimer timer;
6546  Transform transformToLandmark = Transform::getIdentity();
6547 
6548  // No need to optimize the graph
6549  if(_memory)
6550  {
6551  int currentNode = 0;
6552  if(_memory->isIncremental())
6553  {
6555  {
6556  UWARN("Working memory is empty... cannot compute a path");
6557  return false;
6558  }
6559  currentNode = _memory->getLastWorkingSignature()->id();
6560  }
6561  else
6562  {
6564  {
6565  UWARN("Last localization pose is null or optimized graph is empty... cannot compute a path");
6566  return false;
6567  }
6568  if(_optimizedPoses.begin()->first < 0)
6569  {
6570  std::map<int, Transform> poses(_optimizedPoses.lower_bound(1), _optimizedPoses.end());
6571  currentNode = graph::findNearestNode(poses, _lastLocalizationPose);
6572  }
6573  else
6574  {
6576  }
6577  }
6578  if(currentNode && targetNode)
6579  {
6580  std::list<std::pair<int, Transform> > path = graph::computePath(
6581  currentNode,
6582  targetNode,
6583  _memory,
6584  global,
6585  false,
6588 
6589  //transform in current referential
6591  _path.resize(path.size());
6592  int oi = 0;
6593  for(std::list<std::pair<int, Transform> >::iterator iter=path.begin(); iter!=path.end();++iter)
6594  {
6595  if(iter->first > 0)
6596  {
6597  // just keep nodes in the path
6598  _path[oi].first = iter->first;
6599  _path[oi++].second = t * iter->second;
6600  }
6601  }
6602  _path.resize(oi);
6603  if(!_path.empty() && !path.empty() && path.rbegin()->first < 0)
6604  {
6605  transformToLandmark = _path.back().second.inverse() * t * path.rbegin()->second;
6606  }
6607  }
6608  else if(currentNode == 0)
6609  {
6610  UWARN("We should be localized before planning.");
6611  }
6612  }
6613  UINFO("Total planning time = %fs (%d nodes, %f m long)", totalTimer.ticks(), (int)_path.size(), graph::computePathLength(_path));
6614 
6615  if(_path.size() == 0)
6616  {
6617  _path.clear();
6618  UWARN("Cannot compute a path!");
6619  return false;
6620  }
6621  else
6622  {
6623  UINFO("Path generated! Size=%d", (int)_path.size());
6625  {
6626  std::stringstream stream;
6627  for(unsigned int i=0; i<_path.size(); ++i)
6628  {
6629  stream << _path[i].first;
6630  if(i+1 < _path.size())
6631  {
6632  stream << " ";
6633  }
6634  }
6635  UINFO("Path = [%s]", stream.str().c_str());
6636  }
6638  {
6639  // set goal to latest signature
6640  std::string goalStr = uFormat("GOAL:%d", targetNode);
6641 
6642  // use label is exist
6643  if(_memory->getSignature(targetNode))
6644  {
6645  if(!_memory->getSignature(targetNode)->getLabel().empty())
6646  {
6647  goalStr = std::string("GOAL:")+_memory->getSignature(targetNode)->getLabel();
6648  }
6649  }
6650  else if(global)
6651  {
6652  std::map<int, std::string> labels = _memory->getAllLabels();
6653  std::map<int, std::string>::iterator iter = labels.find(targetNode);
6654  if(iter != labels.end() && !iter->second.empty())
6655  {
6656  goalStr = std::string("GOAL:")+labels.at(targetNode);
6657  }
6658  }
6659  setUserData(0, cv::Mat(1, int(goalStr.size()+1), CV_8SC1, (void *)goalStr.c_str()).clone());
6660  }
6661  _pathTransformToGoal = transformToLandmark;
6662 
6663  updateGoalIndex();
6664  return _path.size() || _pathStatus > 0;
6665  }
6666 
6667  return false;
6668 }
6669 
6670 bool Rtabmap::computePath(const Transform & targetPose, float tolerance)
6671 {
6672  this->clearPath(0);
6673 
6674  UINFO("Planning a path to pose %s ", targetPose.prettyPrint().c_str());
6675  if(tolerance < 0.0f)
6676  {
6677  tolerance = _localRadius;
6678  }
6679 
6680  std::list<std::pair<int, Transform> > pathPoses;
6681 
6682  if(!_rgbdSlamMode)
6683  {
6684  UWARN("This method can only be used in RGBD-SLAM mode");
6685  return false;
6686  }
6687 
6688  //Find the nearest node
6689  UTimer timer;
6690  std::map<int, Transform> nodes = _optimizedPoses;
6691  std::multimap<int, int> links;
6692  for(std::map<int, Transform>::iterator iter=nodes.upper_bound(0); iter!=nodes.end(); ++iter)
6693  {
6694  const Signature * s = _memory->getSignature(iter->first);
6695  UASSERT(s);
6696  for(std::map<int, Link>::const_iterator jter=s->getLinks().begin(); jter!=s->getLinks().end(); ++jter)
6697  {
6698  // only add links for which poses are in "nodes"
6699  if(jter->second.from() != jter->second.to() && uContains(nodes, jter->second.to()))
6700  {
6701  links.insert(std::make_pair(jter->second.from(), jter->second.to()));
6702  //links.insert(std::make_pair(jter->second.to(), jter->second.from())); // <-> (commented: already added when iterating in nodes)
6703  }
6704  }
6705  }
6706  UINFO("Time getting links = %fs", timer.ticks());
6707 
6708  int currentNode = 0;
6709  if(_memory->isIncremental())
6710  {
6712  {
6713  UWARN("Working memory is empty... cannot compute a path");
6714  return false;
6715  }
6716  currentNode = _memory->getLastWorkingSignature()->id();
6717  }
6718  else
6719  {
6721  {
6722  UWARN("Last localization pose is null... cannot compute a path");
6723  return false;
6724  }
6725  if(_optimizedPoses.begin()->first < 0)
6726  {
6727  std::map<int, Transform> poses(_optimizedPoses.lower_bound(1), _optimizedPoses.end());
6728  currentNode = graph::findNearestNode(poses, _lastLocalizationPose);
6729  }
6730  else
6731  {
6733  }
6734  }
6735 
6736  int nearestId;
6737  if(!_lastLocalizationPose.isNull() && _lastLocalizationPose.getDistance(targetPose) < tolerance)
6738  {
6739  // target can be reached from the current node
6740  nearestId = currentNode;
6741  }
6742  else
6743  {
6744  nearestId = rtabmap::graph::findNearestNode(nodes, targetPose);
6745  }
6746  UINFO("Nearest node found=%d ,%fs", nearestId, timer.ticks());
6747  if(nearestId > 0)
6748  {
6749  if(tolerance != 0.0f && targetPose.getDistance(nodes.at(nearestId)) > tolerance)
6750  {
6751  UWARN("Cannot plan farther than %f m from the graph! (distance=%f m from node %d)",
6752  tolerance, targetPose.getDistance(nodes.at(nearestId)), nearestId);
6753  }
6754  else
6755  {
6756  UINFO("Computing path from location %d to %d", currentNode, nearestId);
6757  UTimer timer;
6758  _path = uListToVector(rtabmap::graph::computePath(nodes, links, currentNode, nearestId));
6759  UINFO("A* time = %fs", timer.ticks());
6760 
6761  if(_path.size() == 0)
6762  {
6763  UWARN("Cannot compute a path!");
6764  }
6765  else
6766  {
6767  UINFO("Path generated! Size=%d", (int)_path.size());
6769  {
6770  std::stringstream stream;
6771  for(unsigned int i=0; i<_path.size(); ++i)
6772  {
6773  stream << _path[i].first;
6774  if(i+1 < _path.size())
6775  {
6776  stream << " ";
6777  }
6778  }
6779  UINFO("Path = [%s]", stream.str().c_str());
6780  }
6781 
6782  UASSERT(uContains(nodes, _path.back().first));
6783  _pathTransformToGoal = nodes.at(_path.back().first).inverse() * targetPose;
6784 
6785  updateGoalIndex();
6786 
6787  return true;
6788  }
6789  }
6790  }
6791  else
6792  {
6793  UWARN("Nearest node not found in graph (size=%d) for pose %s", (int)nodes.size(), targetPose.prettyPrint().c_str());
6794  }
6795 
6796  return false;
6797 }
6798 
6799 std::vector<std::pair<int, Transform> > Rtabmap::getPathNextPoses() const
6800 {
6801  std::vector<std::pair<int, Transform> > poses;
6802  if(_path.size())
6803  {
6804  UASSERT(_pathCurrentIndex < _path.size() && _pathGoalIndex < _path.size());
6805  poses.resize(_pathGoalIndex-_pathCurrentIndex+1);
6806  int oi=0;
6807  for(unsigned int i=_pathCurrentIndex; i<=_pathGoalIndex; ++i)
6808  {
6809  std::map<int, Transform>::const_iterator iter = _optimizedPoses.find(_path[i].first);
6810  if(iter != _optimizedPoses.end())
6811  {
6812  poses[oi++] = *iter;
6813  }
6814  else
6815  {
6816  break;
6817  }
6818  }
6819  poses.resize(oi);
6820  }
6821  return poses;
6822 }
6823 
6824 std::vector<int> Rtabmap::getPathNextNodes() const
6825 {
6826  std::vector<int> ids;
6827  if(_path.size())
6828  {
6829  UASSERT(_pathCurrentIndex < _path.size() && _pathGoalIndex < _path.size());
6830  ids.resize(_pathGoalIndex-_pathCurrentIndex+1);
6831  int oi = 0;
6832  for(unsigned int i=_pathCurrentIndex; i<=_pathGoalIndex; ++i)
6833  {
6834  std::map<int, Transform>::const_iterator iter = _optimizedPoses.find(_path[i].first);
6835  if(iter != _optimizedPoses.end())
6836  {
6837  ids[oi++] = iter->first;
6838  }
6839  else
6840  {
6841  break;
6842  }
6843  }
6844  ids.resize(oi);
6845  }
6846  return ids;
6847 }
6848 
6850 {
6851  if(_path.size())
6852  {
6853  UASSERT(_pathGoalIndex <= _path.size());
6854  return _path[_pathGoalIndex].first;
6855  }
6856  return 0;
6857 }
6858 
6860 {
6861  if(!_rgbdSlamMode)
6862  {
6863  UWARN("This method can on be used in RGBD-SLAM mode!");
6864  return;
6865  }
6866 
6867  if( _memory && _path.size())
6868  {
6869  // remove all previous virtual links
6870  for(unsigned int i=0; i<_pathCurrentIndex && i<_path.size(); ++i)
6871  {
6872  const Signature * s = _memory->getSignature(_path[i].first);
6873  if(s)
6874  {
6875  _memory->removeVirtualLinks(s->id());
6876  }
6877  }
6878 
6879  // for the current index, only keep the newest virtual link
6880  // This will make sure that the path is still connected even
6881  // if the new signature is removed (e.g., because of a small displacement)
6882  UASSERT(_pathCurrentIndex < _path.size());
6883  const Signature * currentIndexS = _memory->getSignature(_path[_pathCurrentIndex].first);
6884  UASSERT_MSG(currentIndexS != 0, uFormat("_path[%d].first=%d", _pathCurrentIndex, _path[_pathCurrentIndex].first).c_str());
6885  std::multimap<int, Link> links = currentIndexS->getLinks(); // make a copy
6886  bool latestVirtualLinkFound = false;
6887  for(std::multimap<int, Link>::reverse_iterator iter=links.rbegin(); iter!=links.rend(); ++iter)
6888  {
6889  if(iter->second.type() == Link::kVirtualClosure)
6890  {
6891  if(latestVirtualLinkFound)
6892  {
6893  _memory->removeLink(currentIndexS->id(), iter->first);
6894  }
6895  else
6896  {
6897  latestVirtualLinkFound = true;
6898  }
6899  }
6900  }
6901 
6902  // Make sure the next signatures on the path are linked together
6903  float distanceSoFar = 0.0f;
6904  for(unsigned int i=_pathCurrentIndex+1;
6905  i<_path.size();
6906  ++i)
6907  {
6908  if(i>0)
6909  {
6910  if(_localRadius > 0.0f)
6911  {
6912  distanceSoFar += _path[i-1].second.getDistance(_path[i].second);
6913  }
6914  if(distanceSoFar <= _localRadius)
6915  {
6916  if(_path[i].first != _path[i-1].first)
6917  {
6918  const Signature * s = _memory->getSignature(_path[i].first);
6919  if(s)
6920  {
6921  if(!s->hasLink(_path[i-1].first) && _memory->getSignature(_path[i-1].first) != 0)
6922  {
6923  Transform virtualLoop = _path[i].second.inverse() * _path[i-1].second;
6924  _memory->addLink(Link(_path[i].first, _path[i-1].first, Link::kVirtualClosure, virtualLoop, cv::Mat::eye(6,6,CV_64FC1)*0.01)); // on the optimized path
6925  UINFO("Added Virtual link between %d and %d", _path[i-1].first, _path[i].first);
6926  }
6927  }
6928  }
6929  }
6930  else
6931  {
6932  break;
6933  }
6934  }
6935  }
6936 
6937  UDEBUG("current node = %d current goal = %d", _path[_pathCurrentIndex].first, _path[_pathGoalIndex].first);
6938  Transform currentPose;
6939  if(_memory->isIncremental())
6940  {
6941  if(_memory->getLastWorkingSignature() == 0 ||
6943  {
6944  UERROR("Last node is null in memory or not in optimized poses. Aborting the plan...");
6945  this->clearPath(-1);
6946  return;
6947  }
6948  currentPose = _optimizedPoses.at(_memory->getLastWorkingSignature()->id());
6949  }
6950  else
6951  {
6953  {
6954  UERROR("Last localization pose is null. Aborting the plan...");
6955  this->clearPath(-1);
6956  return;
6957  }
6958  currentPose = _lastLocalizationPose;
6959  }
6960 
6961  int goalId = _path.back().first;
6962  if(uContains(_optimizedPoses, goalId))
6963  {
6964  //use local position to know if the goal is reached
6965  float d = currentPose.getDistance(_optimizedPoses.at(goalId)*_pathTransformToGoal);
6966  if(d < _goalReachedRadius)
6967  {
6968  UINFO("Goal %d reached!", goalId);
6969  this->clearPath(1);
6970  }
6971  }
6972 
6973  if(_path.size())
6974  {
6975  //Always check if the farthest node is accessible in local map (max to local space radius if set)
6976  unsigned int goalIndex = _pathCurrentIndex;
6977  float distanceFromCurrentNode = 0.0f;
6978  bool sameGoalIndex = false;
6979  for(unsigned int i=_pathCurrentIndex+1; i<_path.size(); ++i)
6980  {
6982  {
6983  if(_localRadius > 0.0f)
6984  {
6985  distanceFromCurrentNode = _path[_pathCurrentIndex].second.getDistance(_path[i].second);
6986  }
6987 
6988  if((goalIndex == _pathCurrentIndex && i == _path.size()-1) ||
6990  {
6991  if(distanceFromCurrentNode <= _localRadius)
6992  {
6993  goalIndex = i;
6994  }
6995  else
6996  {
6997  break;
6998  }
6999  }
7000  }
7001  else
7002  {
7003  break;
7004  }
7005  }
7006  UASSERT(_pathGoalIndex < _path.size() && goalIndex < _path.size());
7007  if(_pathGoalIndex != goalIndex)
7008  {
7009  UINFO("Updated current goal from %d to %d (%d/%d)",
7010  (int)_path[_pathGoalIndex].first, _path[goalIndex].first, (int)goalIndex+1, (int)_path.size());
7011  _pathGoalIndex = goalIndex;
7012  }
7013  else
7014  {
7015  sameGoalIndex = true;
7016  }
7017 
7018  // update nearest pose in the path
7019  unsigned int nearestNodeIndex = 0;
7020  float distance = -1.0f;
7021  bool sameCurrentIndex = false;
7022  UASSERT(_pathGoalIndex < _path.size());
7023  for(unsigned int i=_pathCurrentIndex; i<=_pathGoalIndex; ++i)
7024  {
7025  std::map<int, Transform>::iterator iter = _optimizedPoses.find(_path[i].first);
7026  if(iter != _optimizedPoses.end())
7027  {
7028  float d = currentPose.getDistanceSquared(iter->second);
7029  if(distance == -1.0f || distance > d)
7030  {
7031  distance = d;
7032  nearestNodeIndex = i;
7033  }
7034  }
7035  }
7036  if(distance < 0)
7037  {
7038  UERROR("The nearest pose on the path not found! Aborting the plan...");
7039  this->clearPath(-1);
7040  }
7041  else
7042  {
7043  UDEBUG("Nearest node = %d", _path[nearestNodeIndex].first);
7044  }
7045  if(distance >= 0 && nearestNodeIndex != _pathCurrentIndex)
7046  {
7047  _pathCurrentIndex = nearestNodeIndex;
7048  _pathUnreachableNodes.erase(nearestNodeIndex); // if we are on it, it is reachable
7049  }
7050  else
7051  {
7052  sameCurrentIndex = true;
7053  }
7054 
7055  bool isStuck = false;
7056  if(sameGoalIndex && sameCurrentIndex && _pathStuckIterations>0)
7057  {
7058  float distanceToCurrentGoal = 0.0f;
7059  std::map<int, Transform>::iterator iter = _optimizedPoses.find(_path[_pathGoalIndex].first);
7060  if(iter != _optimizedPoses.end())
7061  {
7063  _pathGoalIndex == _path.size()-1)
7064  {
7065  distanceToCurrentGoal = currentPose.getDistanceSquared(iter->second*_pathTransformToGoal);
7066  }
7067  else
7068  {
7069  distanceToCurrentGoal = currentPose.getDistanceSquared(iter->second);
7070  }
7071  }
7072 
7073  if(distanceToCurrentGoal > 0.0f)
7074  {
7075  if(distanceToCurrentGoal >= _pathStuckDistance)
7076  {
7077  // we are not approaching the goal
7078  isStuck = true;
7079  if(_pathStuckDistance == 0.0f)
7080  {
7081  _pathStuckDistance = distanceToCurrentGoal;
7082  }
7083  }
7084  }
7085  else
7086  {
7087  // no nodes available, cannot plan
7088  isStuck = true;
7089  }
7090  }
7091 
7092  if(isStuck && ++_pathStuckCount > _pathStuckIterations)
7093  {
7094  UWARN("Current goal %d not reached since %d iterations (\"RGBD/PlanStuckIterations\"=%d), mark that node as unreachable.",
7098  _pathStuckCount = 0;
7099  _pathStuckDistance = 0.0;
7101  // select previous reachable one
7103  {
7105  {
7106  // plan failed!
7107  UERROR("No upcoming nodes on the path are reachable! Aborting the plan...");
7108  this->clearPath(-1);
7109  return;
7110  }
7111  }
7112  }
7113  else if(!isStuck)
7114  {
7115  _pathStuckCount = 0;
7116  _pathStuckDistance = 0.0;
7117  }
7118  }
7119  }
7120 }
7121 
7123 {
7124  UDEBUG("Creating global scan map (if scans are available)");
7126  _globalScanMapPoses.clear();
7127  std::vector<int> scanIndices;
7128  std::map<int, Transform> scanViewpoints;
7129  for(std::map<int, Transform>::iterator iter=_optimizedPoses.begin(); iter!=_optimizedPoses.end(); ++iter)
7130  {
7131  SensorData data = _memory->getNodeData(iter->first, false, true, false, false);
7132  if(!data.laserScanCompressed().empty())
7133  {
7134  LaserScan scan;
7135  data.uncompressDataConst(0, 0, &scan, 0, 0, 0, 0);
7136  if(!scan.empty())
7137  {
7138  UDEBUG("Adding scan %d (format=%s, points=%d)", iter->first, scan.formatName().c_str(), scan.size());
7139  scan = util3d::transformLaserScan(scan, iter->second*scan.localTransform());
7140  if(_globalScanMap.empty() || _globalScanMap.format() == scan.format())
7141  {
7142  _globalScanMap += scan;
7143  _globalScanMapPoses.insert(*iter);
7144  scanViewpoints.insert(std::make_pair(iter->first, iter->second * scan.localTransform()));
7145  scanIndices.resize(_globalScanMap.size(), iter->first);
7146  }
7147  else
7148  {
7149  UWARN("Incompatible scan formats (%s vs %s), cannot create global scan map.",
7150  _globalScanMap.formatName().c_str(),
7151  scan.formatName().c_str());
7153  _globalScanMapPoses.clear();
7154  break;
7155  }
7156  }
7157  else
7158  {
7159  UDEBUG("Ignored %d (scan is empty), pose still added.", iter->first);
7160  _globalScanMapPoses.insert(*iter);
7161  }
7162  }
7163  else
7164  {
7165  UDEBUG("Ignored %d (no scan), pose still added.", iter->first);
7166  _globalScanMapPoses.insert(*iter);
7167  }
7168  }
7169  if(_globalScanMap.size() > 3)
7170  {
7171  float voxelSize = 0.0f;
7172  int normalK = 0;
7173  float normalRadius = 0.0f;
7174  Parameters::parse(_parameters, Parameters::kMemLaserScanVoxelSize(), voxelSize);
7175  Parameters::parse(_parameters, Parameters::kMemLaserScanNormalK(), normalK);
7176  Parameters::parse(_parameters, Parameters::kMemLaserScanNormalRadius(), normalRadius);
7177 
7178  if(voxelSize > 0.0f)
7179  {
7180  LaserScan voxelScan = util3d::commonFiltering(_globalScanMap, 1, 0, 0, voxelSize, normalK, normalRadius);
7181  if(voxelScan.hasNormals())
7182  {
7183  // adjust with point of views
7185  scanViewpoints,
7187  scanIndices,
7188  voxelScan);
7189  }
7190  _globalScanMap = voxelScan;
7191  }
7192 
7193  UINFO("Global scan map has been assembled (size=%d points, %d poses) "
7194  "for proximity detection (only in localization mode %s=false and with %s=true)",
7195  (int)_globalScanMap.size(),
7196  (int)_globalScanMapPoses.size(),
7197  Parameters::kMemIncrementalMemory().c_str(),
7198  Parameters::kRGBDProximityGlobalScanMap().c_str());
7199 
7200  //for debugging...
7202  {
7203  if(!_wDir.empty())
7204  {
7205  UWARN("Saving %s/rtabmap_global_scan_map.pcd (only saved when logger level is debug)", _wDir.c_str());
7206  pcl::PCLPointCloud2::Ptr cloud2 = util3d::laserScanToPointCloud2(_globalScanMap);
7207  pcl::io::savePCDFile(_wDir+"/rtabmap_global_scan_map.pcd", *cloud2);
7208  }
7209  else
7210  {
7211  UWARN("%s is enabled and logger is debug, but %s is not set, cannot save global scan map for debugging.",
7212  Parameters::kRGBDProximityGlobalScanMap().c_str(), Parameters::kRtabmapWorkingDirectory().c_str());
7213  }
7214  }
7215  }
7216  if(!_globalScanMap.empty() && _globalScanMap.size()<100)
7217  {
7218  UWARN("Ignoring global scan map because it is too small (%d points).", (int)_globalScanMap.size());
7220  _globalScanMapPoses.clear();
7221  }
7222 }
7223 
7224 } // namespace rtabmap
rtabmap::Memory::cleanupLocalGrids
int cleanupLocalGrids(const std::map< int, Transform > &poses, const cv::Mat &map, float xMin, float yMin, float cellSize, int cropRadius=1, bool filterScans=false)
Definition: Memory.cpp:4255
rtabmap::Memory::getLandmarksIndex
const std::map< int, std::set< int > > & getLandmarksIndex() const
Definition: Memory.h:169
rtabmap::SensorData
Definition: SensorData.h:51
ind
std::vector< int > ind
rtabmap::ParametersPair
std::pair< std::string, std::string > ParametersPair
Definition: Parameters.h:44
w
RowVector3d w
int
int
rtabmap::Memory::isInSTM
bool isInSTM(int signatureId) const
Definition: Memory.h:216
rtabmap::LaserScan::localTransform
Transform localTransform() const
Definition: LaserScan.h:127
compare
bool compare
Compression.h
rtabmap::Rtabmap::_globalScanMap
LaserScan _globalScanMap
Definition: Rtabmap.h:375
rtabmap::Rtabmap::adjustLikelihood
void adjustLikelihood(std::map< int, float > &likelihood) const
Definition: Rtabmap.cpp:5287
rtabmap::SensorData::setLaserScan
void setLaserScan(const LaserScan &laserScan, bool clearPreviousData=true)
Definition: SensorData.cpp:382
rtabmap::Rtabmap::getPathNextPoses
std::vector< std::pair< int, Transform > > getPathNextPoses() const
Definition: Rtabmap.cpp:6799
rtabmap::Statistics::setMapCorrection
void setMapCorrection(const Transform &mapCorrection)
Definition: Statistics.h:247
rtabmap::Rtabmap::get3DMap
RTABMAP_DEPRECATED void get3DMap(std::map< int, Signature > &signatures, std::map< int, Transform > &poses, std::multimap< int, Link > &constraints, bool optimized, bool global) const
Definition: Rtabmap.cpp:5495
LOG_I
#define LOG_I
Definition: Rtabmap.cpp:76
rtabmap::Rtabmap::refineLinks
int refineLinks()
Definition: Rtabmap.cpp:6038
rtabmap::Statistics::addSignatureData
void addSignatureData(const Signature &data)
Definition: Statistics.h:242
rtabmap::Memory::updateAge
void updateAge(int signatureId)
Definition: Memory.cpp:1719
rtabmap::Rtabmap::cleanupLocalGrids
int cleanupLocalGrids(const std::map< int, Transform > &mapPoses, const cv::Mat &map, float xMin, float yMin, float cellSize, int cropRadius=1, bool filterScans=false)
Definition: Rtabmap.cpp:6015
rtabmap::Rtabmap::_distanceTravelled
float _distanceTravelled
Definition: Rtabmap.h:344
rtabmap::Memory::isIncremental
bool isIncremental() const
Definition: Memory.h:213
rtabmap::Rtabmap::getSTMSize
int getSTMSize() const
Definition: Rtabmap.cpp:839
rtabmap::Rtabmap::_someNodesHaveBeenTransferred
bool _someNodesHaveBeenTransferred
Definition: Rtabmap.h:343
UINFO
#define UINFO(...)
rtabmap::Transform::is3DoF
bool is3DoF() const
Definition: Transform.cpp:234
rtabmap::DBDriver::getLastParameters
ParametersMap getLastParameters() const
Definition: DBDriver.cpp:239
rtabmap::Memory::getMetricConstraints
void getMetricConstraints(const std::set< int > &ids, std::map< int, Transform > &poses, std::multimap< int, Link > &links, bool lookInDatabase=false, bool landmarksAdded=false)
Definition: Memory.cpp:6553
rtabmap::Rtabmap::_parameters
ParametersMap _parameters
Definition: Rtabmap.h:353
uMean
T uMean(const T *v, unsigned int size)
Definition: UMath.h:399
rtabmap::Statistics
Definition: Statistics.h:53
rtabmap::Rtabmap::_mapCorrectionBackup
Transform _mapCorrectionBackup
Definition: Rtabmap.h:369
rtabmap::Optimizer::priorsIgnored
bool priorsIgnored() const
Definition: Optimizer.h:95
rtabmap::util3d::laserScanToPointCloud2
pcl::PCLPointCloud2::Ptr RTABMAP_CORE_EXPORT laserScanToPointCloud2(const LaserScan &laserScan, const Transform &transform=Transform())
Definition: util3d.cpp:2250
rtabmap::Rtabmap::~Rtabmap
virtual ~Rtabmap()
Definition: Rtabmap.cpp:187
rtabmap::Optimizer::optimizeBA
virtual std::map< int, Transform > optimizeBA(int rootId, const std::map< int, Transform > &poses, const std::multimap< int, Link > &links, const std::map< int, std::vector< CameraModel > > &models, std::map< int, cv::Point3f > &points3DMap, const std::map< int, std::map< int, FeatureBA > > &wordReferences, std::set< int > *outliers=0)
Definition: Optimizer.cpp:430
glm::yaw
GLM_FUNC_DECL T yaw(detail::tquat< T, P > const &x)
util3d_surface.h
rtabmap::Rtabmap::_bayesFilter
BayesFilter * _bayesFilter
Definition: Rtabmap.h:351
format
std::string format(const std::string &str, const std::vector< std::string > &find, const std::vector< std::string > &replace)
rtabmap::Memory::getNeighborsId
std::map< int, int > getNeighborsId(int signatureId, int maxGraphDepth, int maxCheckedInDatabase=-1, bool incrementMarginOnLoop=false, bool ignoreLoopIds=false, bool ignoreIntermediateNodes=false, bool ignoreLocalSpaceLoopIds=false, const std::set< int > &nodesSet=std::set< int >(), double *dbAccessTime=0) const
Definition: Memory.cpp:1454
rtabmap::Rtabmap::_distanceTravelledSinceLastLocalization
float _distanceTravelledSinceLastLocalization
Definition: Rtabmap.h:345
rtabmap::LaserScan::maxPoints
int maxPoints() const
Definition: LaserScan.h:120
rtabmap::Memory::close
void close(bool databaseSaved=true, bool postInitClosingEvents=false, const std::string &ouputDatabasePath="")
Definition: Memory.cpp:485
rtabmap::Memory::loadOptimizedPoses
std::map< int, Transform > loadOptimizedPoses(Transform *lastlocalizationPose) const
Definition: Memory.cpp:2168
rtabmap::Memory::removeVirtualLinks
void removeVirtualLinks(int signatureId)
Definition: Memory.cpp:3591
rtabmap::Signature::getLinks
const std::multimap< int, Link > & getLinks() const
Definition: Signature.h:101
gtsam::Values::size
size_t size() const
rtabmap::LaserScan::rangeMax
float rangeMax() const
Definition: LaserScan.h:122
timer
s
RealScalar s
rtabmap::Rtabmap::updateGoalIndex
void updateGoalIndex()
Definition: Rtabmap.cpp:6859
rtabmap::Rtabmap::setupLogFiles
void setupLogFiles(bool overwrite=false)
Definition: Rtabmap.cpp:192
rtabmap::VWDictionary::getVisualWords
const std::map< int, VisualWord * > & getVisualWords() const
Definition: VWDictionary.h:97
rtabmap::Rtabmap::_foutFloat
FILE * _foutFloat
Definition: Rtabmap.h:357
rtabmap::Rtabmap::setTimeThreshold
void setTimeThreshold(float maxTimeAllowed)
Definition: Rtabmap.cpp:4765
Registration.h
rtabmap::DBDriver::openConnection
bool openConnection(const std::string &url, bool overwritten=false)
Definition: DBDriver.cpp:86
rtabmap::graph::radiusPosesClustering
std::multimap< int, int > RTABMAP_CORE_EXPORT radiusPosesClustering(const std::map< int, Transform > &poses, float radius, float angle)
Definition: Graph.cpp:1489
stream
stream
VWDictionary.h
rtabmap::Transform::r33
float r33() const
Definition: Transform.h:70
rtabmap::Memory::addLink
bool addLink(const Link &link, bool addInDatabase=false)
Definition: Memory.cpp:3437
rtabmap::Rtabmap::_gpsGeocentricCache
std::map< int, std::pair< cv::Point3d, Transform > > _gpsGeocentricCache
Definition: Rtabmap.h:373
rtabmap::Rtabmap::_pathStuckCount
int _pathStuckCount
Definition: Rtabmap.h:390
rtabmap::Memory::getNodeInfo
bool getNodeInfo(int signatureId, Transform &odomPose, int &mapId, int &weight, std::string &label, double &stamp, Transform &groundTruth, std::vector< float > &velocity, GPS &gps, EnvSensors &sensors, bool lookInDatabase=false) const
Definition: Memory.cpp:4093
rtabmap::Memory::saveOptimizedPoses
void saveOptimizedPoses(const std::map< int, Transform > &optimizedPoses, const Transform &lastlocalizationPose) const
Definition: Memory.cpp:2160
rtabmap::Signature::getWords
const std::multimap< int, int > & getWords() const
Definition: Signature.h:112
rtabmap::Rtabmap::_pathCurrentIndex
unsigned int _pathCurrentIndex
Definition: Rtabmap.h:387
rtabmap::Rtabmap::_startNewMapOnLoopClosure
bool _startNewMapOnLoopClosure
Definition: Rtabmap.h:322
rtabmap::SensorData::laserScanCompressed
const LaserScan & laserScanCompressed() const
Definition: SensorData.h:181
UProcessInfo.h
rtabmap::RegistrationInfo
Definition: RegistrationInfo.h:34
rtabmap::Transform::getIdentity
static Transform getIdentity()
Definition: Transform.cpp:411
rtabmap::Transform::getNorm
float getNorm() const
Definition: Transform.cpp:283
size
Index size
uUniqueKeys
std::list< K > uUniqueKeys(const std::multimap< K, V > &mm)
Definition: UStl.h:46
rtabmap::Memory::getStMem
const std::set< int > & getStMem() const
Definition: Memory.h:150
rtabmap::graph::exportPoses
bool RTABMAP_CORE_EXPORT exportPoses(const std::string &filePath, int format, const std::map< int, Transform > &poses, const std::multimap< int, Link > &constraints=std::multimap< int, Link >(), const std::map< int, double > &stamps=std::map< int, double >(), const ParametersMap &parameters=ParametersMap())
Definition: Graph.cpp:54
rtabmap::Rtabmap::_statisticLogsBufferedInRAM
bool _statisticLogsBufferedInRAM
Definition: Rtabmap.h:295
rtabmap::Optimizer
Definition: Optimizer.h:61
rtabmap::Memory::removeRawData
void removeRawData(int id, bool image=true, bool scan=true, bool userData=true)
Definition: Memory.cpp:2843
rtabmap::Rtabmap::_odomCachePoses
std::map< int, Transform > _odomCachePoses
Definition: Rtabmap.h:377
rtabmap::Rtabmap::rejectLastLoopClosure
void rejectLastLoopClosure()
Definition: Rtabmap.cpp:4818
rtabmap::Rtabmap::_loopClosureHypothesis
std::pair< int, float > _loopClosureHypothesis
Definition: Rtabmap.h:340
rtabmap::Rtabmap::_pathStatus
int _pathStatus
Definition: Rtabmap.h:384
rtabmap::Rtabmap::_verifyLoopClosureHypothesis
bool _verifyLoopClosureHypothesis
Definition: Rtabmap.h:290
rtabmap::Optimizer::landmarksIgnored
bool landmarksIgnored() const
Definition: Optimizer.h:96
rtabmap::Rtabmap::_bufferedLogsI
std::list< std::string > _bufferedLogsI
Definition: Rtabmap.h:360
rtabmap::util3d::transformLaserScan
LaserScan RTABMAP_CORE_EXPORT transformLaserScan(const LaserScan &laserScan, const Transform &transform)
Definition: util3d_transforms.cpp:39
rtabmap::NearestPathKey
Definition: Rtabmap.cpp:1144
rtabmap::Rtabmap::_maxOdomCacheSize
int _maxOdomCacheSize
Definition: Rtabmap.h:333
rtabmap::Optimizer::create
static Optimizer * create(const ParametersMap &parameters)
Definition: Optimizer.cpp:72
rtabmap::Rtabmap::optimizeCurrentMap
void optimizeCurrentMap(int id, bool lookInDatabase, std::map< int, Transform > &optimizedPoses, cv::Mat &covariance, std::multimap< int, Link > *constraints=0, double *error=0, int *iterationsDone=0) const
Definition: Rtabmap.cpp:5148
rtabmap::Rtabmap::createGlobalScanMap
void createGlobalScanMap()
Definition: Rtabmap.cpp:7122
rtabmap::Signature::mapId
int mapId() const
Definition: Signature.h:71
rtabmap::EpipolarGeometry::parseParameters
void parseParameters(const ParametersMap &parameters)
Definition: EpipolarGeometry.cpp:58
rtabmap::Signature::getGroundTruthPose
const Transform & getGroundTruthPose() const
Definition: Signature.h:135
rtabmap::Rtabmap::_proximityFilteringRadius
float _proximityFilteringRadius
Definition: Rtabmap.h:314
rtabmap::GPS
Definition: GPS.h:35
rtabmap::Rtabmap::_localizationPriorInf
double _localizationPriorInf
Definition: Rtabmap.h:335
ULogger::kDebug
@ kDebug
Definition: ULogger.h:252
rtabmap::LaserScan::formatName
static std::string formatName(const Format &format)
Definition: LaserScan.cpp:34
rtabmap::Transform::theta
float theta() const
Definition: Transform.cpp:162
RegistrationInfo.h
rtabmap::Rtabmap::_odomCacheConstraints
std::multimap< int, Link > _odomCacheConstraints
Definition: Rtabmap.h:378
rtabmap::Memory::getLastSignatureId
int getLastSignatureId() const
Definition: Memory.cpp:2573
type
rtabmap::GeodeticCoords::toGeocentric_WGS84
cv::Point3d toGeocentric_WGS84() const
Definition: GeodeticCoords.cpp:75
rtabmap::Rtabmap::globalBundleAdjustment
bool globalBundleAdjustment(int optimizerType=1, bool rematchFeatures=true, int iterations=0, float pixelVariance=0.0f)
Definition: Rtabmap.cpp:5956
rtabmap::Statistics::setPosterior
void setPosterior(const std::map< int, float > &posterior)
Definition: Statistics.h:252
rtabmap::Rtabmap::getGraph
void getGraph(std::map< int, Transform > &poses, std::multimap< int, Link > &constraints, bool optimized, bool global, std::map< int, Signature > *signatures=0, bool withImages=false, bool withScan=false, bool withUserData=false, bool withGrid=false, bool withWords=true, bool withGlobalDescriptors=true) const
Definition: Rtabmap.cpp:5506
rtabmap::Rtabmap::_lastProcessTime
double _lastProcessTime
Definition: Rtabmap.h:342
rtabmap::Signature::getLabel
const std::string & getLabel() const
Definition: Signature.h:77
rtabmap::Rtabmap::_optimizationMaxError
float _optimizationMaxError
Definition: Rtabmap.h:321
rtabmap::GPS::error
const double & error() const
Definition: GPS.h:63
rtabmap::util3d::commonFiltering
LaserScan RTABMAP_CORE_EXPORT commonFiltering(const LaserScan &scan, int downsamplingStep, float rangeMin=0.0f, float rangeMax=0.0f, float voxelSize=0.0f, int normalK=0, float normalRadius=0.0f, float groundNormalsUp=0.0f)
Definition: util3d_filtering.cpp:74
rtabmap::ProgressState::callback
virtual bool callback(const std::string &msg) const
Definition: ProgressState.h:39
y
Matrix3f y
rtabmap::Rtabmap::_maxRepublished
unsigned int _maxRepublished
Definition: Rtabmap.h:293
rtabmap::Rtabmap::_maxTimeAllowed
float _maxTimeAllowed
Definition: Rtabmap.h:283
UTimer::start
void start()
Definition: UTimer.cpp:87
LOG_F
#define LOG_F
Definition: Rtabmap.cpp:75
rtabmap::Transform::fromString
static Transform fromString(const std::string &string)
Definition: Transform.cpp:475
iterator
rtabmap::LaserScan::hasNormals
bool hasNormals() const
Definition: LaserScan.h:134
rtabmap::Memory::reactivateSignatures
std::set< int > reactivateSignatures(const std::list< int > &ids, unsigned int maxLoaded, double &timeDbAccess)
Definition: Memory.cpp:6472
rtabmap::Rtabmap::dumpData
void dumpData() const
Definition: Rtabmap.cpp:4932
uVariance
T uVariance(const T *v, unsigned int size, T meanV)
Definition: UMath.h:489
rtabmap::Rtabmap::getWeights
std::map< int, int > getWeights() const
Definition: Rtabmap.cpp:819
rtabmap::Transform::isInvertible
bool isInvertible() const
Definition: Transform.cpp:169
rtabmap::Memory::getWeights
std::map< int, int > getWeights() const
Definition: Memory.cpp:2023
rtabmap::Transform::setNull
void setNull()
Definition: Transform.cpp:152
util3d.h
BayesFilter.h
rtabmap::Rtabmap::_proximityRawPosesUsed
bool _proximityRawPosesUsed
Definition: Rtabmap.h:315
rtabmap::Rtabmap::_proximityMergedScanCovFactor
double _proximityMergedScanCovFactor
Definition: Rtabmap.h:318
rtabmap::LaserScan
Definition: LaserScan.h:37
uListToVector
std::vector< V > uListToVector(const std::list< V > &list)
Definition: UStl.h:473
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
rtabmap::Memory::save2DMap
void save2DMap(const cv::Mat &map, float xMin, float yMin, float cellSize) const
Definition: Memory.cpp:2200
rtabmap::Memory::getLastWorkingSignature
const Signature * getLastWorkingSignature() const
Definition: Memory.cpp:2578
rtabmap::Rtabmap::addNodesToRepublish
void addNodesToRepublish(const std::vector< int > &ids)
Definition: Rtabmap.cpp:6487
rtabmap::Transform::to4DoF
Transform to4DoF() const
Definition: Transform.cpp:222
rtabmap::Rtabmap::setWorkingDirectory
void setWorkingDirectory(std::string path)
Definition: Rtabmap.cpp:4790
UTimer.h
rtabmap::Signature::getWeight
int getWeight() const
Definition: Signature.h:74
rtabmap::Memory::getGPS
void getGPS(int id, GPS &gps, Transform &offsetENU, bool lookInDatabase, int maxGraphDepth=0) const
Definition: Memory.cpp:4045
rtabmap::Memory::getSignature
const Signature * getSignature(int id) const
Definition: Memory.cpp:1257
ULOGGER_DEBUG
#define ULOGGER_DEBUG(...)
Definition: ULogger.h:53
EpipolarGeometry.h
rtabmap::Rtabmap::_globalScanMapPoses
std::map< int, Transform > _globalScanMapPoses
Definition: Rtabmap.h:376
rtabmap::LaserScan::size
int size() const
Definition: LaserScan.h:131
rtabmap::Transform::isNull
bool isNull() const
Definition: Transform.cpp:107
rtabmap::Rtabmap::_proximityOdomGuess
bool _proximityOdomGuess
Definition: Rtabmap.h:317
rtabmap::Transform::o14
float o14() const
Definition: Transform.h:72
rtabmap::Memory::getDbSavingTime
double getDbSavingTime() const
Definition: Memory.cpp:1759
rtabmap::Registration::COVARIANCE_LINEAR_EPSILON
static double COVARIANCE_LINEAR_EPSILON
Definition: Registration.h:48
rtabmap::LaserScan::isEmpty
bool isEmpty() const
Definition: LaserScan.h:130
rtabmap::Signature::hasLink
bool hasLink(int idTo, Link::Type type=Link::kUndef) const
Definition: Signature.cpp:129
UMath.h
Basic mathematics functions.
rtabmap::Rtabmap::_neighborLinkRefining
bool _neighborLinkRefining
Definition: Rtabmap.h:304
rtabmap::Rtabmap::_publishLikelihood
bool _publishLikelihood
Definition: Rtabmap.h:279
rtabmap::Parameters::parse
static bool parse(const ParametersMap &parameters, const std::string &key, bool &value)
Definition: Parameters.cpp:506
rtabmap::Rtabmap::_forceOdom3doF
bool _forceOdom3doF
Definition: Rtabmap.h:329
rtabmap::Memory::joinTrashThread
void joinTrashThread()
Definition: Memory.cpp:2257
indices
indices
rtabmap::Transform::getTranslationAndEulerAngles
void getTranslationAndEulerAngles(float &x, float &y, float &z, float &roll, float &pitch, float &yaw) const
Definition: Transform.cpp:258
rtabmap::Statistics::setLocalPath
void setLocalPath(const std::vector< int > &localPath)
Definition: Statistics.h:255
rtabmap::Rtabmap::_restartAtOrigin
bool _restartAtOrigin
Definition: Rtabmap.h:330
rtabmap::Memory::saveStatistics
void saveStatistics(const Statistics &statistics, bool saveWMState)
Definition: Memory.cpp:2136
fabs
Real fabs(const Real &a)
rtabmap::Rtabmap::_proximityAngle
float _proximityAngle
Definition: Rtabmap.h:316
rtabmap::Optimizer::isSlam2d
bool isSlam2d() const
Definition: Optimizer.h:91
rtabmap::Rtabmap::_wDir
std::string _wDir
Definition: Rtabmap.h:364
uSplitNumChar
std::list< std::string > uSplitNumChar(const std::string &str)
Definition: UStl.h:670
uKeysList
std::list< K > uKeysList(const std::multimap< K, V > &mm)
Definition: UStl.h:84
rtabmap::Statistics::setRefImageMapId
void setRefImageMapId(int id)
Definition: Statistics.h:233
n
int n
rtabmap::Rtabmap::_pathStuckIterations
int _pathStuckIterations
Definition: Rtabmap.h:326
UDirectory::homeDir
static std::string homeDir()
Definition: UDirectory.cpp:355
rtabmap::Rtabmap::_pathUnreachableNodes
std::set< unsigned int > _pathUnreachableNodes
Definition: Rtabmap.h:386
rtabmap::Rtabmap::_foutInt
FILE * _foutInt
Definition: Rtabmap.h:358
rtabmap::LaserScan::format
Format format() const
Definition: LaserScan.h:117
labels
std::vector< std::string > labels
rtabmap::Memory::generateGraph
void generateGraph(const std::string &fileName, const std::set< int > &ids=std::set< int >())
Definition: Memory.cpp:4244
rtabmap::Rtabmap::getStatistics
const Statistics & getStatistics() const
Definition: Rtabmap.cpp:879
rtabmap::Rtabmap::_constraints
std::multimap< int, Link > _constraints
Definition: Rtabmap.h:367
rtabmap::Rtabmap::_highestHypothesis
std::pair< int, float > _highestHypothesis
Definition: Rtabmap.h:341
rtabmap::util3d::adjustNormalsToViewPoints
void RTABMAP_CORE_EXPORT adjustNormalsToViewPoints(const std::map< int, Transform > &poses, const std::vector< int > &cameraIndices, pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, float groundNormalsUp=0.0f)
Definition: util3d_surface.cpp:3730
rtabmap::Rtabmap::_localImmunizationRatio
float _localImmunizationRatio
Definition: Rtabmap.h:310
rtabmap::Rtabmap::_lastLocalizationNodeId
int _lastLocalizationNodeId
Definition: Rtabmap.h:371
uInsert
void uInsert(std::map< K, V > &map, const std::pair< K, V > &pair)
Definition: UStl.h:441
rtabmap::Rtabmap::_epipolarGeometry
EpipolarGeometry * _epipolarGeometry
Definition: Rtabmap.h:350
rtabmap::Memory::cleanup
int cleanup()
Definition: Memory.cpp:2117
rtabmap::Memory::getNodeCalibration
void getNodeCalibration(int nodeId, std::vector< CameraModel > &models, std::vector< StereoCameraModel > &stereoModels) const
Definition: Memory.cpp:4226
rtabmap::Transform::y
float & y()
Definition: Transform.h:93
rtabmap::graph::findNearestNode
int RTABMAP_CORE_EXPORT findNearestNode(const std::map< int, rtabmap::Transform > &poses, const rtabmap::Transform &targetPose, float *distance=0)
Definition: Graph.cpp:2209
rtabmap::Parameters::getDefaultParameters
static const ParametersMap & getDefaultParameters()
Definition: Parameters.h:910
uContains
bool uContains(const std::list< V > &list, const V &value)
Definition: UStl.h:407
rtabmap::Transform::getNormSquared
float getNormSquared() const
Definition: Transform.cpp:288
rtabmap::Transform::z
float & z()
Definition: Transform.h:94
rtabmap::Statistics::setRawLikelihood
void setRawLikelihood(const std::map< int, float > &rawLikelihood)
Definition: Statistics.h:254
rtabmap::Statistics::data
const std::map< std::string, float > & data() const
Definition: Statistics.h:292
UFATAL
#define UFATAL(...)
rtabmap::Rtabmap::_goalsSavedInUserData
bool _goalsSavedInUserData
Definition: Rtabmap.h:325
rtabmap::Memory::saveLocationData
void saveLocationData(int locationId)
Definition: Memory.cpp:2748
rtabmap::graph::calcRMSE
Transform RTABMAP_CORE_EXPORT calcRMSE(const std::map< int, Transform > &groundTruth, const std::map< int, Transform > &poses, float &translational_rmse, float &translational_mean, float &translational_median, float &translational_std, float &translational_min, float &translational_max, float &rotational_rmse, float &rotational_mean, float &rotational_median, float &rotational_std, float &rotational_min, float &rotational_max, bool align2D=false)
Definition: Graph.cpp:772
rtabmap::Rtabmap::_startNewMapOnGoodSignature
bool _startNewMapOnGoodSignature
Definition: Rtabmap.h:323
rtabmap::NearestPathKey::distance
float distance
Definition: Rtabmap.cpp:1172
rtabmap::Transform::getEulerAngles
void getEulerAngles(float &roll, float &pitch, float &yaw) const
Definition: Transform.cpp:263
rtabmap::EpipolarGeometry::check
bool check(const Signature *ssA, const Signature *ssB)
Definition: EpipolarGeometry.cpp:65
rtabmap::Transform::prettyPrint
std::string prettyPrint() const
Definition: Transform.cpp:326
rtabmap::Rtabmap::getWorkingDir
const std::string & getWorkingDir() const
Definition: Rtabmap.h:126
rtabmap::Rtabmap::_rawDataKept
bool _rawDataKept
Definition: Rtabmap.h:294
rtabmap::Rtabmap::getNodesInRadius
std::map< int, Transform > getNodesInRadius(const Transform &pose, float radius, int k=0, std::map< int, float > *distsSqr=0)
Definition: Rtabmap.cpp:5578
rtabmap::SensorData::laserScanRaw
const LaserScan & laserScanRaw() const
Definition: SensorData.h:185
rtabmap::Memory::init
bool init(const std::string &dbUrl, bool dbOverwritten=false, const ParametersMap &parameters=ParametersMap(), bool postInitClosingEvents=false)
Definition: Memory.cpp:168
rtabmap::Transform::getAngle
float getAngle(float x=1.0f, float y=0.0f, float z=0.0f) const
Definition: Transform.cpp:276
data
int data[]
delta
def delta(g0, g1)
util3d_transforms.h
rtabmap::Rtabmap::_loopClosureIdentityGuess
bool _loopClosureIdentityGuess
Definition: Rtabmap.h:308
rtabmap::Statistics::setLoopClosureId
void setLoopClosureId(int id)
Definition: Statistics.h:234
rtabmap::Rtabmap::_localizationCovariance
cv::Mat _localizationCovariance
Definition: Rtabmap.h:372
Features2d.h
rtabmap::Rtabmap::computePath
bool computePath(int targetNode, bool global)
Definition: Rtabmap.cpp:6525
rtabmap::Memory::getNeighborsIdRadius
std::map< int, float > getNeighborsIdRadius(int signatureId, float radius, const std::map< int, Transform > &optimizedPoses, int maxGraphDepth) const
Definition: Memory.cpp:1631
rtabmap::Rtabmap::exportPoses
void exportPoses(const std::string &path, bool optimized, bool global, int format)
Definition: Rtabmap.cpp:1054
rtabmap::Rtabmap::_maxMemoryAllowed
unsigned int _maxMemoryAllowed
Definition: Rtabmap.h:284
g
float g
rtabmap::Optimizer::Type
Type
Definition: Optimizer.h:64
j
std::ptrdiff_t j
rtabmap::Transform::r13
float r13() const
Definition: Transform.h:64
rtabmap::Memory::update
bool update(const SensorData &data, Statistics *stats=0)
Definition: Memory.cpp:866
uNumber2Str
std::string UTILITE_EXPORT uNumber2Str(unsigned int number)
Definition: UConversion.cpp:91
rtabmap::Rtabmap::_rgbdSlamMode
bool _rgbdSlamMode
Definition: Rtabmap.h:298
rtabmap::Memory::computeIcpTransform
Transform computeIcpTransform(const Signature &fromS, const Signature &toS, Transform guess, RegistrationInfo *info=0) const
Definition: Memory.cpp:3222
rtabmap::graph::computePathLength
float RTABMAP_CORE_EXPORT computePathLength(const std::vector< std::pair< int, Transform > > &path, unsigned int fromIndex=0, unsigned int toIndex=0)
Definition: Graph.cpp:2372
rtabmap::Rtabmap::_publishLastSignatureData
bool _publishLastSignatureData
Definition: Rtabmap.h:277
UConversion.h
Some conversion functions.
rtabmap::Rtabmap::triggerNewMap
int triggerNewMap()
Definition: Rtabmap.cpp:917
rtabmap::Rtabmap::_pathStuckDistance
float _pathStuckDistance
Definition: Rtabmap.h:391
glm::sqrt
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
UFile::getExtension
std::string getExtension()
Definition: UFile.h:140
rtabmap::Rtabmap::addLink
bool addLink(const Link &link)
Definition: Rtabmap.cpp:6084
rtabmap::Signature::getLandmarks
const std::map< int, Link > & getLandmarks() const
Definition: Signature.h:94
rtabmap::Rtabmap::setUserData
bool setUserData(int id, const cv::Mat &data)
Definition: Rtabmap.cpp:1002
rtabmap::Rtabmap::_optimizedPoses
std::map< int, Transform > _optimizedPoses
Definition: Rtabmap.h:366
util3d_filtering.h
uMax3
T uMax3(const T &a, const T &b, const T &c)
Definition: UMath.h:78
rtabmap::Rtabmap::clearPath
void clearPath(int status)
Definition: Rtabmap.cpp:6507
rtabmap::Rtabmap::_maxLoopClosureDistance
float _maxLoopClosureDistance
Definition: Rtabmap.h:289
rtabmap::Rtabmap::_mapCorrection
Transform _mapCorrection
Definition: Rtabmap.h:368
rtabmap::Rtabmap::_computeRMSE
bool _computeRMSE
Definition: Rtabmap.h:281
rtabmap::Rtabmap::_maxRetrieved
unsigned int _maxRetrieved
Definition: Rtabmap.h:291
rtabmap::GPS::bearing
const double & bearing() const
Definition: GPS.h:64
rtabmap::Memory::deleteLocation
void deleteLocation(int locationId, std::list< int > *deletedWords=0)
Definition: Memory.cpp:2738
rtabmap::LaserScan::is2d
bool is2d() const
Definition: LaserScan.h:133
rtabmap::Rtabmap::_pathLinearVelocity
float _pathLinearVelocity
Definition: Rtabmap.h:327
rtabmap::PythonInterface
Definition: PythonInterface.h:26
Signature.h
rtabmap::Rtabmap::_graphOptimizer
Optimizer * _graphOptimizer
Definition: Rtabmap.h:352
rtabmap::Memory::kIdInvalid
static const int kIdInvalid
Definition: Memory.h:69
Rtabmap.h
rtabmap::Signature::isBadSignature
bool isBadSignature() const
Definition: Signature.cpp:341
rtabmap::Transform::x
float & x()
Definition: Transform.h:92
first
constexpr int first(int i)
rtabmap::Rtabmap::isInSTM
bool isInSTM(int locationId) const
Definition: Rtabmap.cpp:861
rtabmap::Memory::getNeighborLinks
std::multimap< int, Link > getNeighborLinks(int signatureId, bool lookInDatabase=false) const
Definition: Memory.cpp:1272
Optimizer.h
rtabmap::Memory::getDatabaseMemoryUsed
int getDatabaseMemoryUsed() const
Definition: Memory.cpp:1728
rtabmap::SensorData::clearCompressedData
void clearCompressedData(bool images=true, bool scan=true, bool userData=true)
Definition: SensorData.cpp:833
glm::max
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
rtabmap::Memory::getAllLabels
const std::map< int, std::string > & getAllLabels() const
Definition: Memory.h:168
ULogger::kInfo
@ kInfo
Definition: ULogger.h:252
velocity
Velocity3 velocity(const NavState &X, OptionalJacobian< 3, 9 > H)
rtabmap::Memory::removeAllVirtualLinks
void removeAllVirtualLinks()
Definition: Memory.cpp:3582
rtabmap::Memory::isOdomGravityUsed
bool isOdomGravityUsed() const
Definition: Memory.h:224
rtabmap::Memory::getGroundTruths
const std::map< int, Transform > & getGroundTruths() const
Definition: Memory.h:187
rtabmap::Rtabmap::getSignatureCopy
Signature getSignatureCopy(int id, bool images, bool scan, bool userData, bool occupancyGrid, bool withWords, bool withGlobalDescriptors) const
Definition: Rtabmap.cpp:5416
rtabmap::Transform::o34
float o34() const
Definition: Transform.h:74
rtabmap::Rtabmap::setInitialPose
void setInitialPose(const Transform &initialPose)
Definition: Rtabmap.cpp:889
rtabmap::Rtabmap::_proximityMaxPaths
int _proximityMaxPaths
Definition: Rtabmap.h:312
rtabmap::Transform::o24
float o24() const
Definition: Transform.h:73
rtabmap::ProgressState::isCanceled
bool isCanceled() const
Definition: ProgressState.h:51
info
else if n * info
rtabmap::Rtabmap::_goalReachedRadius
float _goalReachedRadius
Definition: Rtabmap.h:324
rtabmap::Statistics::setLabels
void setLabels(const std::map< int, std::string > &labels)
Definition: Statistics.h:250
rtabmap::Rtabmap::_createGlobalScanMap
bool _createGlobalScanMap
Definition: Rtabmap.h:336
rtabmap::Transform::r21
float r21() const
Definition: Transform.h:65
rtabmap::Rtabmap::_lastLocalizationPose
Transform _lastLocalizationPose
Definition: Rtabmap.h:370
rtabmap::BayesFilter::getMemoryUsed
unsigned long getMemoryUsed() const
Definition: BayesFilter.cpp:420
rtabmap::Rtabmap::_virtualPlaceLikelihoodRatio
int _virtualPlaceLikelihoodRatio
Definition: Rtabmap.h:288
target
target
rtabmap::SensorData::setId
void setId(int id)
Definition: SensorData.h:175
UASSERT
#define UASSERT(condition)
d
d
rtabmap::ProgressState
Definition: ProgressState.h:35
params
SmartProjectionParams params(gtsam::HESSIAN, gtsam::ZERO_ON_DEGENERACY)
z
z
rtabmap::Rtabmap::_pathGoalIndex
unsigned int _pathGoalIndex
Definition: Rtabmap.h:388
uValue
V uValue(const std::map< K, V > &m, const K &key, const V &defaultValue=V())
Definition: UStl.h:238
x
x
m
Matrix3f m
error
void error(const char *str)
rtabmap::Memory::getLastGlobalLoopClosureId
int getLastGlobalLoopClosureId() const
Definition: Memory.h:220
rtabmap::Statistics::setProximityDetectionId
void setProximityDetectionId(int id)
Definition: Statistics.h:236
rtabmap::Memory::getOdomMaxInf
const std::vector< double > & getOdomMaxInf() const
Definition: Memory.h:223
PythonInterface.h
rtabmap::GPS::stamp
const double & stamp() const
Definition: GPS.h:59
rtabmap::Rtabmap::getLastLocationId
int getLastLocationId() const
Definition: Rtabmap.cpp:789
rtabmap::Transform::getDistanceSquared
float getDistanceSquared(const Transform &t) const
Definition: Transform.cpp:298
rtabmap::Rtabmap::_nodesToRepublish
std::set< int > _nodesToRepublish
Definition: Rtabmap.h:381
rtabmap::Memory::getNodeData
SensorData getNodeData(int locationId, bool images, bool scan, bool userData, bool occupancyGrid) const
Definition: Memory.cpp:4143
rtabmap::Rtabmap::_publishStats
bool _publishStats
Definition: Rtabmap.h:276
DBDriver.h
rtabmap::Transform::getDistance
float getDistance(const Transform &t) const
Definition: Transform.cpp:293
rtabmap::Transform::r31
float r31() const
Definition: Transform.h:68
rtabmap::Parameters
Definition: Parameters.h:170
rtabmap::Memory::computeTransform
Transform computeTransform(Signature &fromS, Signature &toS, Transform guess, RegistrationInfo *info=0, bool useKnownCorrespondencesIfPossible=false) const
Definition: Memory.cpp:2886
rtabmap::Transform::setIdentity
void setIdentity()
Definition: Transform.cpp:157
rtabmap::Statistics::setWeights
void setWeights(const std::map< int, int > &weights)
Definition: Statistics.h:251
rtabmap::Memory::kIdVirtual
static const int kIdVirtual
Definition: Memory.h:68
rtabmap::Optimizer::gravitySigma
float gravitySigma() const
Definition: Optimizer.h:97
rtabmap::Rtabmap::_rgbdAngularSpeedUpdate
float _rgbdAngularSpeedUpdate
Definition: Rtabmap.h:302
rtabmap::Statistics::setLikelihood
void setLikelihood(const std::map< int, float > &likelihood)
Definition: Statistics.h:253
rtabmap::BayesFilter::getPredictionLC
const std::vector< double > & getPredictionLC() const
Definition: BayesFilter.cpp:118
rtabmap::NearestPathKey::NearestPathKey
NearestPathKey(float l, int i, float d)
Definition: Rtabmap.cpp:1147
rtabmap::Rtabmap::_memory
Memory * _memory
Definition: Rtabmap.h:355
time
#define time
uKeysSet
std::set< K > uKeysSet(const std::map< K, V > &m)
Definition: UStl.h:186
rtabmap::BayesFilter::computePosterior
const std::map< int, float > & computePosterior(const Memory *memory, const std::map< int, float > &likelihood)
Definition: BayesFilter.cpp:145
rtabmap::Rtabmap::_currentSessionHasGPS
bool _currentSessionHasGPS
Definition: Rtabmap.h:374
glm::pitch
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
rtabmap::Rtabmap::_localizationSmoothing
bool _localizationSmoothing
Definition: Rtabmap.h:334
rtabmap::Rtabmap::generateDOTGraph
void generateDOTGraph(const std::string &path, int id=0, int margin=5)
Definition: Rtabmap.cpp:1022
rtabmap::graph::findLink
std::multimap< int, Link >::iterator RTABMAP_CORE_EXPORT findLink(std::multimap< int, Link > &links, int from, int to, bool checkBothWays=true, Link::Type type=Link::kUndef)
Definition: Graph.cpp:1050
rtabmap::Transform::inverse
Transform inverse() const
Definition: Transform.cpp:178
rtabmap::Statistics::setOdomCachePoses
void setOdomCachePoses(const std::map< int, Transform > &poses)
Definition: Statistics.h:259
rtabmap::graph::findNearestNodes
std::map< int, float > RTABMAP_CORE_EXPORT findNearestNodes(int nodeId, const std::map< int, Transform > &poses, float radius, float angle=0.0f, int k=0)
Definition: Graph.cpp:2228
rtabmap::Memory::emptyTrash
void emptyTrash()
Definition: Memory.cpp:2249
rtabmap::Memory::isGraphReduced
bool isGraphReduced() const
Definition: Memory.h:222
rtabmap::Memory::isIDsGenerated
bool isIDsGenerated() const
Definition: Memory.h:219
rtabmap::Optimizer::optimize
std::map< int, Transform > optimize(int rootId, const std::map< int, Transform > &poses, const std::multimap< int, Link > &constraints, std::list< std::map< int, Transform > > *intermediateGraphes=0, double *finalError=0, int *iterationsDone=0)
Definition: Optimizer.cpp:399
rtabmap::Statistics::setPoses
void setPoses(const std::map< int, Transform > &poses)
Definition: Statistics.h:245
path
path
rtabmap::Rtabmap::_rgbdLinearUpdate
float _rgbdLinearUpdate
Definition: Rtabmap.h:299
UASSERT_MSG
#define UASSERT_MSG(condition, msg_str)
Definition: ULogger.h:67
UWARN
#define UWARN(...)
rtabmap::compressData2
cv::Mat RTABMAP_CORE_EXPORT compressData2(const cv::Mat &data)
Definition: Compression.cpp:239
rtabmap::Rtabmap::init
void init(const ParametersMap &parameters, const std::string &databasePath="", bool loadDatabaseParameters=false)
Definition: Rtabmap.cpp:320
rtabmap::Optimizer::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Optimizer.cpp:322
rtabmap::Rtabmap::getPose
Transform getPose(int locationId) const
Definition: Rtabmap.cpp:884
f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
rtabmap::Rtabmap::_markerPriors
std::map< int, Transform > _markerPriors
Definition: Rtabmap.h:379
rtabmap::Rtabmap::getTotalMemSize
int getTotalMemSize() const
Definition: Rtabmap.cpp:848
rtabmap::DBDriver
Definition: DBDriver.h:62
rtabmap::Rtabmap::getPaths
std::map< int, std::map< int, Transform > > getPaths(const std::map< int, Transform > &poses, const Transform &target, int maxGraphDepth=0) const
Definition: Rtabmap.cpp:5066
rtabmap::Rtabmap::setOptimizedPoses
void setOptimizedPoses(const std::map< int, Transform > &poses, const std::multimap< int, Link > &constraints)
Definition: Rtabmap.cpp:4926
uFormat
std::string UTILITE_EXPORT uFormat(const char *fmt,...)
Definition: UConversion.cpp:365
nodes
KeyVector nodes
uReplaceChar
std::string UTILITE_EXPORT uReplaceChar(const std::string &str, char before, char after)
Definition: UConversion.cpp:33
M_PI
#define M_PI
Definition: tango-gl/include/tango-gl/util.h:66
rtabmap::Statistics::setLoopClosureTransform
void setLoopClosureTransform(const Transform &loopClosureTransform)
Definition: Statistics.h:248
ULogger::level
static ULogger::Level level()
Definition: ULogger.h:340
rtabmap::Rtabmap::_bufferedLogsF
std::list< std::string > _bufferedLogsF
Definition: Rtabmap.h:359
rtabmap::Rtabmap::getWMSize
int getWMSize() const
Definition: Rtabmap.cpp:810
rtabmap::LaserScan::clear
void clear()
Definition: LaserScan.h:150
rtabmap::Memory::getWorkingMem
const std::map< int, double > & getWorkingMem() const
Definition: Memory.h:149
rtabmap::Signature::getPose
const Transform & getPose() const
Definition: Signature.h:133
rtabmap::Memory::getLoopClosureLinks
std::multimap< int, Link > getLoopClosureLinks(int signatureId, bool lookInDatabase=false) const
Definition: Memory.cpp:1313
rtabmap::SensorData::imageRaw
const cv::Mat & imageRaw() const
Definition: SensorData.h:183
Eigen::Quaternion
ULogger.h
ULogger class and convenient macros.
rtabmap::Rtabmap::_pathAngularVelocity
float _pathAngularVelocity
Definition: Rtabmap.h:328
rtabmap::Memory::isLocalizationDataSaved
bool isLocalizationDataSaved() const
Definition: Memory.h:214
rtabmap::Transform::r22
float r22() const
Definition: Transform.h:66
rtabmap::Rtabmap::_maxLocalRetrieved
unsigned int _maxLocalRetrieved
Definition: Rtabmap.h:292
rtabmap::Transform
Definition: Transform.h:41
Memory.h
empty
UTimer::ticks
double ticks()
Definition: UTimer.cpp:117
rtabmap::graph::computeMaxGraphErrors
void RTABMAP_CORE_EXPORT computeMaxGraphErrors(const std::map< int, Transform > &poses, const std::multimap< int, Link > &links, float &maxLinearErrorRatio, float &maxAngularErrorRatio, float &maxLinearError, float &maxAngularError, const Link **maxLinearErrorLink=0, const Link **maxAngularErrorLink=0, bool for3DoF=false)
Definition: Graph.cpp:910
UDirectory::exists
static bool exists(const std::string &dirPath)
Definition: UDirectory.cpp:249
rtabmap::Rtabmap::_optimizeFromGraphEnd
bool _optimizeFromGraphEnd
Definition: Rtabmap.h:320
uSplit
std::list< std::string > uSplit(const std::string &str, char separator=' ')
Definition: UStl.h:564
rtabmap::EnvSensors
std::map< EnvSensor::Type, EnvSensor > EnvSensors
Definition: EnvSensor.h:81
uStr2Int
int UTILITE_EXPORT uStr2Int(const std::string &str)
Definition: UConversion.cpp:125
glm::rotation
GLM_FUNC_DECL detail::tquat< T, P > rotation(detail::tvec3< T, P > const &orig, detail::tvec3< T, P > const &dest)
rtabmap::Parameters::readINI
static void readINI(const std::string &configFile, ParametersMap &parameters, bool modifiedOnly=false)
Definition: Parameters.cpp:1291
Graph.h
rtabmap::Rtabmap::_pathTransformToGoal
Transform _pathTransformToGoal
Definition: Rtabmap.h:389
rtabmap::Signature::id
int id() const
Definition: Signature.h:70
rtabmap::Statistics::setWmState
void setWmState(const std::vector< int > &state)
Definition: Statistics.h:258
rtabmap::Statistics::setExtended
void setExtended(bool extended)
Definition: Statistics.h:231
rtabmap::Statistics::setCurrentGoalId
void setCurrentGoalId(int goal)
Definition: Statistics.h:256
mean
Point3 mean(const CONTAINER &points)
values
leaf::MyValues values
rtabmap::Rtabmap::_proximityByTime
bool _proximityByTime
Definition: Rtabmap.h:305
rtabmap::Rtabmap::_rgbdLinearSpeedUpdate
float _rgbdLinearSpeedUpdate
Definition: Rtabmap.h:301
rtabmap::BayesFilter::generatePrediction
cv::Mat generatePrediction(const Memory *memory, const std::vector< int > &ids)
Definition: BayesFilter.cpp:273
rtabmap::Rtabmap::_statisticLoggedHeaders
bool _statisticLoggedHeaders
Definition: Rtabmap.h:297
rtabmap::Memory::incrementMapId
int incrementMapId(std::map< int, int > *reducedIds=0)
Definition: Memory.cpp:1696
iter
iterator iter(handle obj)
rtabmap::Rtabmap::statistics_
Statistics statistics_
Definition: Rtabmap.h:362
rtabmap::graph::findNearestPoses
std::map< int, Transform > RTABMAP_CORE_EXPORT findNearestPoses(int nodeId, const std::map< int, Transform > &poses, float radius, float angle=0.0f, int k=0)
Definition: Graph.cpp:2317
rtabmap::Memory::dumpMemory
virtual void dumpMemory(std::string directory) const
Definition: Memory.cpp:3621
rtabmap::Transform::rotation
Transform rotation() const
Definition: Transform.cpp:195
ULOGGER_ERROR
#define ULOGGER_ERROR(...)
Definition: ULogger.h:56
rtabmap::Rtabmap::detectMoreLoopClosures
int detectMoreLoopClosures(float clusterRadiusMax=0.5f, float clusterAngle=M_PI/6.0f, int iterations=1, bool intraSession=true, bool interSession=true, const ProgressState *state=0, float clusterRadiusMin=0.0f)
Definition: Rtabmap.cpp:5622
rtabmap::BayesFilter::reset
void reset()
Definition: BayesFilter.cpp:138
rtabmap::Rtabmap::_path
std::vector< std::pair< int, Transform > > _path
Definition: Rtabmap.h:385
rtabmap::Rtabmap::_localRadius
float _localRadius
Definition: Rtabmap.h:309
rtabmap::graph::filterLinks
std::multimap< int, Link > RTABMAP_CORE_EXPORT filterLinks(const std::multimap< int, Link > &links, Link::Type filteredType, bool inverted=false)
Definition: Graph.cpp:1278
rtabmap::Rtabmap::isIDsGenerated
bool isIDsGenerated() const
Definition: Rtabmap.cpp:870
rtabmap::Rtabmap::getPathNextNodes
std::vector< int > getPathNextNodes() const
Definition: Rtabmap.cpp:6824
rtabmap::Rtabmap::_markerPriorsAngularVariance
float _markerPriorsAngularVariance
Definition: Rtabmap.h:338
rtabmap::Rtabmap::_proximityMaxNeighbors
int _proximityMaxNeighbors
Definition: Rtabmap.h:313
rtabmap::Transform::isIdentity
bool isIdentity() const
Definition: Transform.cpp:136
rtabmap::Rtabmap::parseParameters
void parseParameters(const ParametersMap &parameters)
Definition: Rtabmap.cpp:545
rtabmap::Rtabmap::_loopThr
float _loopThr
Definition: Rtabmap.h:285
id
id
rtabmap::Rtabmap::process
bool process(const SensorData &data, Transform odomPose, const cv::Mat &odomCovariance=cv::Mat::eye(6, 6, CV_64FC1), const std::vector< float > &odomVelocity=std::vector< float >(), const std::map< std::string, float > &externalStats=std::map< std::string, float >())
Main loop of rtabmap.
Definition: Rtabmap.cpp:1207
c_str
const char * c_str(Args &&...args)
rtabmap::Memory::getMemoryUsed
unsigned long getMemoryUsed() const
Definition: Memory.cpp:3748
rtabmap::Rtabmap::_loopGPS
bool _loopGPS
Definition: Rtabmap.h:332
rtabmap::Rtabmap::flushStatisticLogs
void flushStatisticLogs()
Definition: Rtabmap.cpp:298
rtabmap::Memory::forget
std::list< int > forget(const std::set< int > &ignoredIds=std::set< int >())
Definition: Memory.cpp:2045
rtabmap::Rtabmap::_newMapOdomChangeDistance
float _newMapOdomChangeDistance
Definition: Rtabmap.h:303
rtabmap::Memory::getVWDictionary
const VWDictionary * getVWDictionary() const
Definition: Memory.cpp:1267
rtabmap::Rtabmap::_optimizeFromGraphEndChanged
bool _optimizeFromGraphEndChanged
Definition: Rtabmap.h:346
rtabmap::LaserScan::empty
bool empty() const
Definition: LaserScan.h:129
rtabmap::Rtabmap::close
void close(bool databaseSaved=true, const std::string &ouputDatabasePath="")
Definition: Rtabmap.cpp:463
rtabmap::Rtabmap::_saveWMState
bool _saveWMState
Definition: Rtabmap.h:282
rtabmap::Memory::getLinks
std::multimap< int, Link > getLinks(int signatureId, bool lookInDatabase=false, bool withLandmarks=false) const
Definition: Memory.cpp:1353
rtabmap::Memory::getAllSignatureIds
std::set< int > getAllSignatureIds(bool ignoreChildren=true) const
Definition: Memory.cpp:1764
v
Array< int, Dynamic, 1 > v
UDEBUG
#define UDEBUG(...)
rtabmap::Transform::normalizeRotation
void normalizeRotation()
Definition: Transform.cpp:316
rtabmap::Rtabmap::Rtabmap
Rtabmap()
Definition: Rtabmap.cpp:94
rtabmap::Statistics::setProximityDetectionMapId
void setProximityDetectionMapId(int id)
Definition: Statistics.h:237
rtabmap::Statistics::reducedIds
const std::map< int, int > & reducedIds() const
Definition: Statistics.h:287
rtabmap::Statistics::setStamp
void setStamp(double stamp)
Definition: Statistics.h:238
rtabmap::Memory::setUserData
bool setUserData(int id, const cv::Mat &data)
Definition: Memory.cpp:2723
rtabmap::Rtabmap::_rgbdAngularUpdate
float _rgbdAngularUpdate
Definition: Rtabmap.h:300
rtabmap::Memory::getNodeWordsAndGlobalDescriptors
void getNodeWordsAndGlobalDescriptors(int nodeId, std::multimap< int, int > &words, std::vector< cv::KeyPoint > &wordsKpts, std::vector< cv::Point3f > &words3, cv::Mat &wordsDescriptors, std::vector< GlobalDescriptor > &globalDescriptors) const
Definition: Memory.cpp:4181
UTimer
Definition: UTimer.h:46
epsilon
double epsilon
rtabmap::BayesFilter::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: BayesFilter.cpp:56
rtabmap::Rtabmap::_databasePath
std::string _databasePath
Definition: Rtabmap.h:319
rtabmap::Statistics::addStatistic
void addStatistic(const std::string &name, float value)
Definition: Statistics.cpp:93
rtabmap::Memory
Definition: Memory.h:64
rtabmap::Statistics::setLoopClosureMapId
void setLoopClosureMapId(int id)
Definition: Statistics.h:235
rtabmap::NearestPathKey::id
int id
Definition: Rtabmap.cpp:1171
scan_step::second
@ second
float
float
rtabmap::Memory::getMapId
int getMapId(int id, bool lookInDatabase=false) const
Definition: Memory.cpp:4006
prior
const auto prior
distance
Double_ distance(const OrientedPlane3_ &p)
rtabmap::GPS::toGeodeticCoords
GeodeticCoords toGeodeticCoords() const
Definition: GPS.h:66
uNormSquared
T uNormSquared(const std::vector< T > &v)
Definition: UMath.h:558
rtabmap::Statistics::setOdomCacheConstraints
void setOdomCacheConstraints(const std::multimap< int, Link > &constraints)
Definition: Statistics.h:260
rtabmap::Rtabmap::dumpPrediction
void dumpPrediction() const
Definition: Rtabmap.cpp:5358
rtabmap::Rtabmap::setMemoryThreshold
void setMemoryThreshold(int maxMemoryAllowed)
Definition: Rtabmap.cpp:4779
rtabmap::Transform::r23
float r23() const
Definition: Transform.h:67
rtabmap::Memory::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Memory.cpp:558
rtabmap::Rtabmap::_proximityMaxGraphDepth
int _proximityMaxGraphDepth
Definition: Rtabmap.h:311
rtabmap::SensorData::gps
const GPS & gps() const
Definition: SensorData.h:291
rtabmap::Optimizer::iterations
int iterations() const
Definition: Optimizer.h:90
rtabmap::Rtabmap::_publishRAMUsage
bool _publishRAMUsage
Definition: Rtabmap.h:280
false
#define false
Definition: ConvertUTF.c:56
transform
EIGEN_DONT_INLINE void transform(const Quaternion< Scalar > &t, Data &data)
rtabmap::EpipolarGeometry
Definition: EpipolarGeometry.h:45
uIsDigit
bool uIsDigit(const char c)
Definition: UStl.h:620
rtabmap::Memory::labelSignature
bool labelSignature(int id, const std::string &label)
Definition: Memory.cpp:2645
rtabmap::SensorData::depthOrRightRaw
const cv::Mat & depthOrRightRaw() const
Definition: SensorData.h:184
rtabmap::Transform::to3DoF
Transform to3DoF() const
Definition: Transform.cpp:210
rtabmap::Optimizer::isRobust
bool isRobust() const
Definition: Optimizer.h:94
rtabmap::Rtabmap::_markerPriorsLinearVariance
float _markerPriorsLinearVariance
Definition: Rtabmap.h:337
rtabmap::Memory::updateLink
void updateLink(const Link &link, bool updateInDatabase=false)
Definition: Memory.cpp:3522
rtabmap::Memory::computeIcpTransformMulti
Transform computeIcpTransformMulti(int newId, int oldId, const std::map< int, Transform > &poses, RegistrationInfo *info=0)
Definition: Memory.cpp:3236
rtabmap::Transform::r12
float r12() const
Definition: Transform.h:63
dist
dist
rtabmap::Optimizer::kTypeUndef
@ kTypeUndef
Definition: Optimizer.h:65
rtabmap::graph::radiusPosesFiltering
std::map< int, Transform > RTABMAP_CORE_EXPORT radiusPosesFiltering(const std::map< int, Transform > &poses, float radius, float angle, bool keepLatest=true)
Definition: Graph.cpp:1377
t
Point2 t(10, 10)
rtabmap::Signature::sensorData
SensorData & sensorData()
Definition: Signature.h:138
rtabmap::Rtabmap::_proximityBySpace
bool _proximityBySpace
Definition: Rtabmap.h:306
rtabmap::SensorData::clearRawData
void clearRawData(bool images=true, bool scan=true, bool userData=true)
Definition: SensorData.cpp:849
UFile.h
rtabmap::Optimizer::setPriorsIgnored
void setPriorsIgnored(bool enabled)
Definition: Optimizer.h:105
rtabmap
Definition: CameraARCore.cpp:35
rtabmap::Rtabmap::_publishPdf
bool _publishPdf
Definition: Rtabmap.h:278
UFile::exists
bool exists()
Definition: UFile.h:104
rtabmap::Rtabmap::_scanMatchingIdsSavedInLinks
bool _scanMatchingIdsSavedInLinks
Definition: Rtabmap.h:307
rtabmap::Rtabmap::deleteLastLocation
void deleteLastLocation()
Definition: Rtabmap.cpp:4876
rtabmap::Transform::r32
float r32() const
Definition: Transform.h:69
rtabmap::Transform::getQuaterniond
Eigen::Quaterniond getQuaterniond() const
Definition: Transform.cpp:406
UERROR
#define UERROR(...)
rtabmap::Rtabmap::getPathCurrentGoalId
int getPathCurrentGoalId() const
Definition: Rtabmap.cpp:6849
rtabmap::graph::computePath
std::list< std::pair< int, Transform > > RTABMAP_CORE_EXPORT computePath(const std::map< int, rtabmap::Transform > &poses, const std::multimap< int, int > &links, int from, int to, bool updateNewCosts=false)
Definition: Graph.cpp:1782
UProcessInfo::getMemoryUsage
static long int getMemoryUsage()
Definition: UProcessInfo.cpp:38
rtabmap::Statistics::setConstraints
void setConstraints(const std::multimap< int, Link > &constraints)
Definition: Statistics.h:246
rtabmap::Rtabmap::_aggressiveLoopThr
float _aggressiveLoopThr
Definition: Rtabmap.h:287
glm::inverse
GLM_FUNC_DECL matType< T, P > inverse(matType< T, P > const &m)
rtabmap::VWDictionary::getIndexedWordsCount
unsigned int getIndexedWordsCount() const
Definition: VWDictionary.cpp:359
value
value
rtabmap::BayesFilter
Definition: BayesFilter.h:44
rtabmap::VWDictionary::getIndexMemoryUsed
unsigned int getIndexMemoryUsed() const
Definition: VWDictionary.cpp:364
i
int i
rtabmap::Statistics::setRefImageId
void setRefImageId(int id)
Definition: Statistics.h:232
rtabmap::Rtabmap::labelLocation
bool labelLocation(int id, const std::string &label)
Definition: Rtabmap.cpp:966
ULOGGER_WARN
#define ULOGGER_WARN(...)
Definition: ULogger.h:55
rtabmap::Rtabmap::getInformation
cv::Mat getInformation(const cv::Mat &covariance) const
Definition: Rtabmap.cpp:6467
rtabmap::Rtabmap::getSTM
std::set< int > getSTM() const
Definition: Rtabmap.cpp:830
rtabmap::Rtabmap::resetMemory
void resetMemory()
Definition: Rtabmap.cpp:1093
rtabmap::Memory::removeLink
void removeLink(int idA, int idB)
Definition: Memory.cpp:2767
rtabmap::Memory::computeLikelihood
std::map< int, float > computeLikelihood(const Signature *signature, const std::list< int > &ids)
Definition: Memory.cpp:1905
glm::roll
GLM_FUNC_DECL T roll(detail::tquat< T, P > const &x)
rtabmap::Registration::COVARIANCE_ANGULAR_EPSILON
static double COVARIANCE_ANGULAR_EPSILON
Definition: Registration.h:49
rtabmap::Memory::allNodesInWM
bool allNodesInWM() const
Definition: Memory.h:170
rtabmap::Rtabmap::_statisticLogged
bool _statisticLogged
Definition: Rtabmap.h:296
rtabmap::Rtabmap::_loopCovLimited
bool _loopCovLimited
Definition: Rtabmap.h:331
rtabmap::NearestPathKey::operator<
bool operator<(const NearestPathKey &k) const
Definition: Rtabmap.cpp:1151
rtabmap::Rtabmap::getWM
std::list< int > getWM() const
Definition: Rtabmap.cpp:799
rtabmap::Signature
Definition: Signature.h:48
rtabmap::Statistics::setLocalizationCovariance
void setLocalizationCovariance(const cv::Mat &covariance)
Definition: Statistics.h:249
rtabmap::Optimizer::getConnectedGraph
void getConnectedGraph(int fromId, const std::map< int, Transform > &posesIn, const std::multimap< int, Link > &linksIn, std::map< int, Transform > &posesOut, std::multimap< int, Link > &linksOut) const
Definition: Optimizer.cpp:188
rtabmap::Rtabmap::_loopRatio
float _loopRatio
Definition: Rtabmap.h:286
newDatabase
static int newDatabase(BtShared *pBt)
Definition: sqlite3.c:52930
rtabmap::Rtabmap::optimizeGraph
std::map< int, Transform > optimizeGraph(int fromId, const std::set< int > &ids, const std::map< int, Transform > &guessPoses, bool lookInDatabase, cv::Mat &covariance, std::multimap< int, Link > *constraints=0, double *error=0, int *iterationsDone=0) const
Definition: Rtabmap.cpp:5194
ULOGGER_INFO
#define ULOGGER_INFO(...)
Definition: ULogger.h:54
rtabmap::NearestPathKey::likelihood
float likelihood
Definition: Rtabmap.cpp:1170
msg
msg
rtabmap::Signature::isSaved
bool isSaved() const
Definition: Signature.h:102
rtabmap::DBDriver::create
static DBDriver * create(const ParametersMap &parameters=ParametersMap())
Definition: DBDriver.cpp:41
rtabmap::Rtabmap::getForwardWMPoses
std::map< int, Transform > getForwardWMPoses(int fromId, int maxNearestNeighbors, float radius, int maxDiffID) const
Definition: Rtabmap.cpp:4950
rtabmap::Transform::r11
float r11() const
Definition: Transform.h:62
rtabmap::GeodeticCoords::Geocentric_WGS84ToENU_WGS84
static cv::Point3d Geocentric_WGS84ToENU_WGS84(const cv::Point3d &geocentric_WGS84, const cv::Point3d &origin_geocentric_WGS84, const GeodeticCoords &origin)
Definition: GeodeticCoords.cpp:119


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:45:59