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 rejectedGlobalLoopClosure = 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  rejectedGlobalLoopClosure = 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  rejectedGlobalLoopClosure = 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  rejectedGlobalLoopClosure = 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  rejectedGlobalLoopClosure = transform.isNull();
3065  if(rejectedGlobalLoopClosure)
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  rejectedGlobalLoopClosure = 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(!rejectedGlobalLoopClosure)
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  rejectedGlobalLoopClosure = !_memory->addLink(Link(signature->id(), _loopClosureHypothesis.first, Link::kGlobalClosure, transform, information));
3090  if(!rejectedGlobalLoopClosure)
3091  {
3092  loopClosureLinksAdded.push_back(std::make_pair(signature->id(), _loopClosureHypothesis.first));
3093  }
3094  }
3095 
3096  if(rejectedGlobalLoopClosure)
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  rejectedGlobalLoopClosure = 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 rejectedLandmark = false;
3184  bool delayedLocalization = false;
3185  UDEBUG("RGB-D SLAM mode: %d", _rgbdSlamMode?1:0);
3186  UDEBUG("Incremental: %d", _memory->isIncremental());
3187  UDEBUG("Loop hyp: %d", _loopClosureHypothesis.first);
3188  UDEBUG("Last prox: %d", lastProximitySpaceClosureId);
3189  UDEBUG("Reduced ids: %d", (int)statistics_.reducedIds().size());
3190  UDEBUG("Has prior: %d (prior ignored=%d)", signature->hasLink(signature->id(), Link::kPosePrior)?1:0, _graphOptimizer->priorsIgnored()?1:0);
3191  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);
3192  UDEBUG("Has virtual link: %d", (int)graph::filterLinks(signature->getLinks(), Link::kVirtualClosure, true).size());
3193  UDEBUG("Prox Time: %d", proximityDetectionsInTimeFound);
3194  UDEBUG("Landmarks: %d", (int)landmarksDetected.size());
3195  UDEBUG("Retrieved: %d", (int)signaturesRetrieved.size());
3196  UDEBUG("Not self ref links: %d", (int)graph::filterLinks(signature->getLinks(), Link::kSelfRefLink).size());
3197 
3198  if(_rgbdSlamMode
3199  &&
3200  (_loopClosureHypothesis.first>0 ||
3201  lastProximitySpaceClosureId>0 || // can be different map of the current one
3202  statistics_.reducedIds().size() ||
3203  (signature->hasLink(signature->id(), Link::kPosePrior) && !_graphOptimizer->priorsIgnored()) || // prior edge
3204  (signature->hasLink(signature->id(), Link::kGravity) && _graphOptimizer->gravitySigma()>0.0f && (!_memory->isOdomGravityUsed() || neighborLinkRefined)) || // gravity edge
3205  proximityDetectionsInTimeFound>0 ||
3206  !landmarksDetected.empty() ||
3207  signaturesRetrieved.size()) // can be different map of the current one
3208  &&
3209  (_memory->isIncremental() ||
3210  // In localization mode, the new node should be linked to another node or a landmark already in the working memory
3212  !landmarksDetected.empty()))
3213  {
3214  UASSERT(uContains(_optimizedPoses, signature->id()));
3215 
3216  //used in localization mode: filter virtual links
3217  std::multimap<int, Link> localizationLinks = graph::filterLinks(signature->getLinks(), Link::kVirtualClosure);
3218  localizationLinks = graph::filterLinks(localizationLinks, Link::kSelfRefLink);
3219  if(!landmarksDetected.empty() && !_memory->isIncremental())
3220  {
3221  for(std::map<int, std::set<int> >::iterator iter=landmarksDetected.begin(); iter!=landmarksDetected.end(); ++iter)
3222  {
3223  if(_optimizedPoses.find(iter->first)!=_optimizedPoses.end())
3224  {
3225  UASSERT(uContains(signature->getLandmarks(), iter->first));
3226  localizationLinks.insert(std::make_pair(iter->first, signature->getLandmarks().at(iter->first)));
3227  }
3228  }
3229  }
3230 
3231  bool allLocalizationLinksInGraph = !localizationLinks.empty();
3232  for(std::multimap<int, Link>::iterator iter=localizationLinks.begin(); iter!=localizationLinks.end(); ++iter)
3233  {
3234  if(!uContains(_optimizedPoses, iter->first))
3235  {
3236  allLocalizationLinksInGraph = false;
3237  break;
3238  }
3239  }
3240 
3241  // Note that in localization mode, we don't re-optimize the graph
3242  // if:
3243  // 1- there are no signatures retrieved,
3244  // 2- we are relocalizing on a node already in the optimized graph
3245  if(!_memory->isIncremental() &&
3246  signaturesRetrieved.empty() &&
3247  !localizationLinks.empty() &&
3248  allLocalizationLinksInGraph)
3249  {
3250  bool rejectLocalization = _odomCachePoses.empty();
3251  if(!_odomCachePoses.empty())
3252  {
3253  // Verify if the new localization is valid by checking if there is
3254  // not too much deformation using current odometry poses
3255  // This will also refine localization links
3256 
3257  std::map<int, Transform> poses = _odomCachePoses;
3258  std::multimap<int, Link> constraints = _odomCacheConstraints;
3259  // add self referring links (e.g., gravity)
3260  std::multimap<int, Link> selfLinks = graph::filterLinks(signature->getLinks(), Link::kSelfRefLink, true);
3262  {
3263  selfLinks = graph::filterLinks(selfLinks, Link::kPosePrior);
3264  }
3265  constraints.insert(selfLinks.begin(), selfLinks.end());
3266  for(std::multimap<int, Link>::iterator iter=localizationLinks.begin(); iter!=localizationLinks.end(); ++iter)
3267  {
3268  constraints.insert(std::make_pair(iter->second.from(), iter->second));
3269  }
3270  cv::Mat priorInfMat = cv::Mat::eye(6,6, CV_64FC1)*_localizationPriorInf;
3271  for(std::multimap<int, Link>::iterator iter=constraints.begin(); iter!=constraints.end(); ++iter)
3272  {
3273  std::map<int, Transform>::iterator iterPose = _optimizedPoses.find(iter->second.to());
3274  if(iterPose != _optimizedPoses.end() && poses.find(iterPose->first) == poses.end())
3275  {
3276  poses.insert(*iterPose);
3277  // make the poses in the map fixed
3278  constraints.insert(std::make_pair(iterPose->first, Link(iterPose->first, iterPose->first, Link::kPosePrior, iterPose->second, priorInfMat)));
3279  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);
3280  }
3281  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());
3282  }
3283 
3284  std::map<int, Transform> posesOut;
3285  std::multimap<int, Link> edgeConstraintsOut;
3286  bool priorsIgnored = _graphOptimizer->priorsIgnored();
3287  UDEBUG("priorsIgnored was %s", priorsIgnored?"true":"false");
3288  _graphOptimizer->setPriorsIgnored(false); //temporary set false to use priors above to fix nodes of the map
3289  // If slam2d: get connected graph while keeping original roll,pitch,z values.
3290  _graphOptimizer->getConnectedGraph(signature->id(), poses, constraints, posesOut, edgeConstraintsOut);
3292  {
3293  for(std::map<int, Transform>::iterator iter=posesOut.begin(); iter!=posesOut.end(); ++iter)
3294  {
3295  UDEBUG("Pose %d %s", iter->first, iter->second.prettyPrint().c_str());
3296  }
3297  }
3298  cv::Mat locOptCovariance;
3299  std::map<int, Transform> optPoses;
3300  if(!posesOut.empty() &&
3301  posesOut.begin()->first < _odomCachePoses.begin()->first)
3302  {
3303  optPoses = _graphOptimizer->optimize(posesOut.begin()->first, posesOut, edgeConstraintsOut, locOptCovariance);
3304  }
3305  else
3306  {
3307  UERROR("Invalid localization constraints");
3308  }
3309  _graphOptimizer->setPriorsIgnored(priorsIgnored); // set back
3310  for(std::map<int, Transform>::iterator iter=optPoses.begin(); iter!=optPoses.end(); ++iter)
3311  {
3312  UDEBUG("Opt %d %s", iter->first, iter->second.prettyPrint().c_str());
3313  }
3314 
3315  if(optPoses.empty())
3316  {
3317  UWARN("Optimization failed, rejecting localization!");
3318  rejectLocalization = true;
3319  }
3320  else
3321  {
3322  UINFO("Compute max graph errors...");
3323  const Link * maxLinearLink = 0;
3324  const Link * maxAngularLink = 0;
3326  optPoses,
3327  edgeConstraintsOut,
3328  maxLinearErrorRatio,
3329  maxAngularErrorRatio,
3330  maxLinearError,
3331  maxAngularError,
3332  &maxLinearLink,
3333  &maxAngularLink,
3335  if(maxLinearLink == 0 && maxAngularLink==0)
3336  {
3337  UWARN("Could not compute graph errors! Rejecting localization!");
3338  rejectLocalization = true;
3339  }
3340 
3341  if(maxLinearLink)
3342  {
3343  UINFO("Max optimization linear error = %f m (link %d->%d, var=%f, ratio error/std=%f, thr=%f)",
3344  maxLinearError,
3345  maxLinearLink->from(),
3346  maxLinearLink->to(),
3347  maxLinearLink->transVariance(),
3348  maxLinearError/sqrt(maxLinearLink->transVariance()),
3350  if(_optimizationMaxError > 0.0f && maxLinearErrorRatio > _optimizationMaxError)
3351  {
3352  UWARN("Rejecting localization (%d <-> %d) in this "
3353  "iteration because a wrong loop closure has been "
3354  "detected after graph optimization, resulting in "
3355  "a maximum graph error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). The "
3356  "maximum error ratio parameter \"%s\" is %f of std deviation.",
3357  localizationLinks.rbegin()->second.from(),
3358  localizationLinks.rbegin()->second.to(),
3359  maxLinearErrorRatio,
3360  maxLinearLink->from(),
3361  maxLinearLink->to(),
3362  maxLinearLink->type(),
3363  maxLinearError,
3364  sqrt(maxLinearLink->transVariance()),
3365  Parameters::kRGBDOptimizeMaxError().c_str(),
3367  rejectLocalization = true;
3368  }
3369  else if(_optimizationMaxError == 0.0f && maxLinearErrorRatio>100 && !_graphOptimizer->isRobust())
3370  {
3371  UERROR("Huge optimization error detected!"
3372  "Linear error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). You may consider "
3373  "enabling \"%s\" to reject those bad optimizations by setting it to a non null value!",
3374  maxLinearErrorRatio,
3375  maxLinearLink->from(),
3376  maxLinearLink->to(),
3377  maxLinearLink->type(),
3378  maxLinearError,
3379  sqrt(maxLinearLink->transVariance()),
3380  Parameters::kRGBDOptimizeMaxError().c_str());
3381  }
3382  }
3383  if(maxAngularLink)
3384  {
3385  UINFO("Max optimization angular error = %f deg (link %d->%d, var=%f, ratio error/std=%f, thr=%f)",
3386  maxAngularError*180.0f/CV_PI,
3387  maxAngularLink->from(),
3388  maxAngularLink->to(),
3389  maxAngularLink->rotVariance(),
3390  maxAngularError/sqrt(maxAngularLink->rotVariance()),
3392  if(_optimizationMaxError > 0.0f && maxAngularErrorRatio > _optimizationMaxError)
3393  {
3394  UWARN("Rejecting localization (%d <-> %d) in this "
3395  "iteration because a wrong loop closure has been "
3396  "detected after graph optimization, resulting in "
3397  "a maximum graph error ratio of %f (edge %d->%d, type=%d, abs error=%f deg, stddev=%f). The "
3398  "maximum error ratio parameter \"%s\" is %f of std deviation.",
3399  localizationLinks.rbegin()->second.from(),
3400  localizationLinks.rbegin()->second.to(),
3401  maxAngularErrorRatio,
3402  maxAngularLink->from(),
3403  maxAngularLink->to(),
3404  maxAngularLink->type(),
3405  maxAngularError*180.0f/CV_PI,
3406  sqrt(maxAngularLink->rotVariance()),
3407  Parameters::kRGBDOptimizeMaxError().c_str(),
3409  rejectLocalization = true;
3410  }
3411  else if(_optimizationMaxError == 0.0f && maxAngularErrorRatio>100 && !_graphOptimizer->isRobust())
3412  {
3413  UERROR("Huge optimization error detected!"
3414  "Angular error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). You may consider "
3415  "enabling \"%s\" to reject those bad optimizations by setting it to a non null value!",
3416  maxAngularErrorRatio,
3417  maxAngularLink->from(),
3418  maxAngularLink->to(),
3419  maxAngularLink->type(),
3420  maxAngularError*180.0f/CV_PI,
3421  sqrt(maxAngularLink->rotVariance()),
3422  Parameters::kRGBDOptimizeMaxError().c_str());
3423  }
3424  }
3425  }
3426 
3427  bool hasGlobalLoopClosuresOrLandmarks = false;
3428  if(rejectLocalization && !graph::filterLinks(constraints, Link::kLocalSpaceClosure, true).empty())
3429  {
3430  // Let's try again without local loop closures
3431  localizationLinks = graph::filterLinks(localizationLinks, Link::kLocalSpaceClosure);
3432  constraints = graph::filterLinks(constraints, Link::kLocalSpaceClosure);
3433  for(std::multimap<int, Link>::iterator iter=constraints.begin(); iter!=constraints.end() && !hasGlobalLoopClosuresOrLandmarks; ++iter)
3434  {
3435  hasGlobalLoopClosuresOrLandmarks =
3436  iter->second.type() == Link::kGlobalClosure ||
3437  iter->second.type() == Link::kLandmark;
3438  }
3439  if(hasGlobalLoopClosuresOrLandmarks && !localizationLinks.empty())
3440  {
3441  rejectLocalization = false;
3442  UWARN("Global and loop closures seem not tallying together, try again to optimize without local loop closures...");
3443  priorsIgnored = _graphOptimizer->priorsIgnored();
3444  UDEBUG("priorsIgnored was %s", priorsIgnored?"true":"false");
3445  _graphOptimizer->setPriorsIgnored(false); //temporary set false to use priors above to fix nodes of the map
3446  // If slam2d: get connected graph while keeping original roll,pitch,z values.
3447  _graphOptimizer->getConnectedGraph(signature->id(), poses, constraints, posesOut, edgeConstraintsOut);
3448  optPoses.clear();
3449  if(!posesOut.empty() &&
3450  posesOut.begin()->first < _odomCachePoses.begin()->first)
3451  {
3452  optPoses = _graphOptimizer->optimize(posesOut.begin()->first, posesOut, edgeConstraintsOut, locOptCovariance);
3453  }
3454  else
3455  {
3456  UERROR("Invalid localization constraints");
3457  }
3458  _graphOptimizer->setPriorsIgnored(priorsIgnored); // set back
3459  for(std::map<int, Transform>::iterator iter=optPoses.begin(); iter!=optPoses.end(); ++iter)
3460  {
3461  UDEBUG("Opt2 %d %s", iter->first, iter->second.prettyPrint().c_str());
3462  }
3463 
3464  if(optPoses.empty())
3465  {
3466  UWARN("Optimization failed, rejecting localization!");
3467  rejectLocalization = true;
3468  }
3469  else
3470  {
3471  UINFO("Compute max graph errors...");
3472  const Link * maxLinearLink = 0;
3473  const Link * maxAngularLink = 0;
3475  optPoses,
3476  edgeConstraintsOut,
3477  maxLinearErrorRatio,
3478  maxAngularErrorRatio,
3479  maxLinearError,
3480  maxAngularError,
3481  &maxLinearLink,
3482  &maxAngularLink,
3484  if(maxLinearLink == 0 && maxAngularLink==0)
3485  {
3486  UWARN("Could not compute graph errors! Rejecting localization!");
3487  rejectLocalization = true;
3488  }
3489 
3490  if(maxLinearLink)
3491  {
3492  UINFO("Max optimization linear error = %f m (link %d->%d, var=%f, ratio error/std=%f, thr=%f)",
3493  maxLinearError,
3494  maxLinearLink->from(),
3495  maxLinearLink->to(),
3496  maxLinearLink->transVariance(),
3497  maxLinearError/sqrt(maxLinearLink->transVariance()),
3499  if(_optimizationMaxError > 0.0f && maxLinearErrorRatio > _optimizationMaxError)
3500  {
3501  UWARN("Rejecting localization (%d <-> %d) in this "
3502  "iteration because a wrong loop closure has been "
3503  "detected after graph optimization, resulting in "
3504  "a maximum graph error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). The "
3505  "maximum error ratio parameter \"%s\" is %f of std deviation.",
3506  localizationLinks.rbegin()->second.from(),
3507  localizationLinks.rbegin()->second.to(),
3508  maxLinearErrorRatio,
3509  maxLinearLink->from(),
3510  maxLinearLink->to(),
3511  maxLinearLink->type(),
3512  maxLinearError,
3513  sqrt(maxLinearLink->transVariance()),
3514  Parameters::kRGBDOptimizeMaxError().c_str(),
3516  rejectLocalization = true;
3517  }
3518  else if(_optimizationMaxError == 0.0f && maxLinearErrorRatio>100 && !_graphOptimizer->isRobust())
3519  {
3520  UERROR("Huge optimization error detected!"
3521  "Linear error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). You may consider "
3522  "enabling \"%s\" to reject those bad optimizations by setting it to a non null value!",
3523  maxLinearErrorRatio,
3524  maxLinearLink->from(),
3525  maxLinearLink->to(),
3526  maxLinearLink->type(),
3527  maxLinearError,
3528  sqrt(maxLinearLink->transVariance()),
3529  Parameters::kRGBDOptimizeMaxError().c_str());
3530  }
3531  }
3532  if(maxAngularLink)
3533  {
3534  UINFO("Max optimization angular error = %f deg (link %d->%d, var=%f, ratio error/std=%f, thr=%f)",
3535  maxAngularError*180.0f/CV_PI,
3536  maxAngularLink->from(),
3537  maxAngularLink->to(),
3538  maxAngularLink->rotVariance(),
3539  maxAngularError/sqrt(maxAngularLink->rotVariance()),
3541  if(_optimizationMaxError > 0.0f && maxAngularErrorRatio > _optimizationMaxError)
3542  {
3543  UWARN("Rejecting localization (%d <-> %d) in this "
3544  "iteration because a wrong loop closure has been "
3545  "detected after graph optimization, resulting in "
3546  "a maximum graph error ratio of %f (edge %d->%d, type=%d, abs error=%f deg, stddev=%f). The "
3547  "maximum error ratio parameter \"%s\" is %f of std deviation.",
3548  localizationLinks.rbegin()->second.from(),
3549  localizationLinks.rbegin()->second.to(),
3550  maxAngularErrorRatio,
3551  maxAngularLink->from(),
3552  maxAngularLink->to(),
3553  maxAngularLink->type(),
3554  maxAngularError*180.0f/CV_PI,
3555  sqrt(maxAngularLink->rotVariance()),
3556  Parameters::kRGBDOptimizeMaxError().c_str(),
3558  rejectLocalization = true;
3559  }
3560  else if(_optimizationMaxError == 0.0f && maxAngularErrorRatio>100 && !_graphOptimizer->isRobust())
3561  {
3562  UERROR("Huge optimization error detected!"
3563  "Angular error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). You may consider "
3564  "enabling \"%s\" to reject those bad optimizations by setting it to a non null value!",
3565  maxAngularErrorRatio,
3566  maxAngularLink->from(),
3567  maxAngularLink->to(),
3568  maxAngularLink->type(),
3569  maxAngularError*180.0f/CV_PI,
3570  sqrt(maxAngularLink->rotVariance()),
3571  Parameters::kRGBDOptimizeMaxError().c_str());
3572  }
3573  }
3574  }
3575  }
3576  }
3577 
3578  if(!rejectLocalization)
3579  {
3580  if(hasGlobalLoopClosuresOrLandmarks)
3581  {
3582  // We successfully optimize the graph without local loop closures,
3583  // clear them as some of them may be wrong.
3584  size_t before = _odomCacheConstraints.size();
3586  if(before != _odomCacheConstraints.size())
3587  {
3588  UWARN("Successfully optimized without local loop closures! Clear them from local odometry cache. %ld/%ld have been removed.",
3589  before - _odomCacheConstraints.size(), before);
3590  }
3591  else
3592  {
3593  UWARN("Successfully optimized without local loop closures!");
3594  }
3595  }
3596 
3597  // Count how many localization links are in the constraints
3598  bool hadAlreadyLocalizationLinks = false;
3599  for(std::multimap<int, Link>::iterator iter=_odomCacheConstraints.begin();
3600  iter!=_odomCacheConstraints.end(); ++iter)
3601  {
3602  if(iter->second.type() == Link::kGlobalClosure ||
3603  iter->second.type() == Link::kLocalSpaceClosure ||
3604  iter->second.type() == Link::kLocalTimeClosure ||
3605  iter->second.type() == Link::kUserClosure ||
3606  iter->second.type() == Link::kNeighborMerged ||
3607  iter->second.type() == Link::kLandmark)
3608  {
3609  hadAlreadyLocalizationLinks = true;
3610  break;
3611  }
3612  }
3613 
3614  // update localization links
3615  UASSERT(uContains(optPoses, signature->id()));
3616  Transform newOptPoseInv = optPoses.at(signature->id()).inverse();
3617  for(std::multimap<int, Link>::iterator iter=localizationLinks.begin(); iter!=localizationLinks.end(); ++iter)
3618  {
3620  {
3621  // Add original link without optimization
3622  UDEBUG("Adding new odom cache constraint %d->%d (%s)",
3623  iter->second.from(), iter->second.to(), iter->second.transform().prettyPrint().c_str());
3624  }
3625  else
3626  {
3627  // Adjust with optimized poses, this will smooth the localization
3628  UASSERT(uContains(optPoses, iter->first));
3629  Transform newT = newOptPoseInv * optPoses.at(iter->first);
3630  UDEBUG("Adjusted localization link %d->%d after optimization", iter->second.from(), iter->second.to());
3631  UDEBUG("from %s", iter->second.transform().prettyPrint().c_str());
3632  UDEBUG(" to %s", newT.prettyPrint().c_str());
3633  iter->second.setTransform(newT);
3634 
3635  // Update link in the referred signatures
3636  if(iter->first > 0)
3637  _memory->updateLink(iter->second, false);
3638  }
3639 
3640  _odomCacheConstraints.insert(std::make_pair(signature->id(), iter->second));
3641  }
3642 
3643  _odomCacheConstraints.insert(selfLinks.begin(), selfLinks.end());
3644 
3645  // At least 2 localizations at 2 different time required
3646  if(hadAlreadyLocalizationLinks || _maxOdomCacheSize == 0)
3647  {
3648  UINFO("Update localization");
3650  {
3651  // update all previous nodes
3652  // Normally _mapCorrection should be identity, but if _optimizeFromGraphEnd
3653  // parameters just changed state, we should put back all poses without map correction.
3654  Transform oldPose = _optimizedPoses.at(localizationLinks.rbegin()->first);
3655  Transform mapCorrectionInv = _mapCorrection.inverse();
3656  Transform u = signature->getPose() * localizationLinks.rbegin()->second.transform();
3657  if(_graphOptimizer->gravitySigma() > 0)
3658  {
3659  // Adjust transform with gravity
3660  Transform transform = localizationLinks.rbegin()->second.transform();
3661  int loopId = localizationLinks.rbegin()->first;
3662  int landmarkId = 0;
3663  if(loopId<0)
3664  {
3665  //For landmarks, use transform against other node looking the landmark
3666  // (because we don't assume that landmarks are aligned with gravity)
3667  landmarkId = loopId;
3668  UASSERT(landmarksDetected.find(landmarkId) != landmarksDetected.end() &&
3669  !landmarksDetected.at(landmarkId).empty());
3670  loopId = *landmarksDetected.at(landmarkId).begin();
3671  }
3672 
3673  const Signature * loopS = _memory->getSignature(loopId);
3674  UASSERT(loopS !=0);
3675  std::multimap<int, Link>::const_iterator iterGravityLoop = graph::findLink(loopS->getLinks(), loopS->id(), loopS->id(), false, Link::kGravity);
3676  std::multimap<int, Link>::const_iterator iterGravitySign = graph::findLink(signature->getLinks(), signature->id(), signature->id(), false, Link::kGravity);
3677  if(iterGravityLoop!=loopS->getLinks().end() &&
3678  iterGravitySign!=signature->getLinks().end())
3679  {
3680  float roll,pitch,yaw;
3681  if(landmarkId < 0)
3682  {
3683  iterGravityLoop->second.transform().getEulerAngles(roll, pitch, yaw);
3684  Transform gravityCorr = Transform(_optimizedPoses.at(loopS->id()).x(),
3685  _optimizedPoses.at(loopS->id()).y(),
3686  _optimizedPoses.at(loopS->id()).z(),
3687  roll, pitch, _optimizedPoses.at(loopS->id()).theta()) * _optimizedPoses.at(loopS->id()).inverse();
3688  (gravityCorr * _optimizedPoses.at(landmarkId)).getEulerAngles(roll,pitch,yaw);
3689  }
3690  else
3691  {
3692  iterGravityLoop->second.transform().getEulerAngles(roll, pitch, yaw);
3693  }
3694  Transform targetRotation = iterGravitySign->second.transform().rotation()*transform.rotation();
3695  targetRotation = Transform(0,0,0,roll,pitch,targetRotation.theta());
3696  Transform error = transform.rotation().inverse() * iterGravitySign->second.transform().rotation().inverse() * targetRotation;
3697  transform *= error;
3698  u = signature->getPose() * transform;
3699  }
3700  else if(iterGravityLoop!=loopS->getLinks().end() ||
3701  iterGravitySign!=signature->getLinks().end())
3702  {
3703  UWARN("Gravity link not found for %d or %d, localization won't be corrected with gravity.", loopId, signature->id());
3704  }
3705  }
3706  Transform up = u * oldPose.inverse();
3707  if(_graphOptimizer->isSlam2d())
3708  {
3709  // in case of 3d landmarks, transform constraint to 2D
3710  up.to3DoF();
3711  }
3712  for(std::map<int, Transform>::iterator iter=_optimizedPoses.begin(); iter!=_optimizedPoses.end(); ++iter)
3713  {
3714  iter->second = mapCorrectionInv * up * iter->second;
3715  }
3716  _optimizedPoses.at(signature->id()) = signature->getPose();
3717  }
3718  else
3719  {
3720  Transform newPose = _optimizedPoses.at(localizationLinks.rbegin()->first) * localizationLinks.rbegin()->second.transform().inverse();
3721  UDEBUG("newPose=%s", newPose.prettyPrint().c_str());
3722  if(_graphOptimizer->isSlam2d() && signature->getPose().is3DoF())
3723  {
3724  // in case of 3d landmarks, transform constraint to 2D
3725  newPose = newPose.to3DoF();
3726  UDEBUG("newPose 2D=%s", newPose.prettyPrint().c_str());
3727  }
3728  else if(_graphOptimizer->gravitySigma() > 0)
3729  {
3730  // Adjust transform with gravity
3731  std::multimap<int, Link>::const_iterator iterGravitySign = graph::findLink(signature->getLinks(), signature->id(), signature->id(), false, Link::kGravity);
3732  if(iterGravitySign!=signature->getLinks().end())
3733  {
3734  Transform transform = localizationLinks.rbegin()->second.transform();
3735  float roll,pitch,yaw;
3736  float tmp1,tmp2;
3737  UDEBUG("Gravity link = %s", iterGravitySign->second.transform().prettyPrint().c_str());
3738  _optimizedPoses.at(localizationLinks.rbegin()->first).getEulerAngles(roll, pitch, yaw);
3739  Transform targetRotation = iterGravitySign->second.transform().rotation()*transform.rotation();
3740  targetRotation = Transform(0,0,0,roll,pitch,targetRotation.theta());
3741  Transform error = transform.rotation().inverse() * iterGravitySign->second.transform().rotation().inverse() * targetRotation;
3742  transform *= error;
3743  newPose = _optimizedPoses.at(localizationLinks.rbegin()->first) * transform.inverse();
3744  iterGravitySign->second.transform().getEulerAngles(roll, pitch, tmp1);
3745  newPose.getEulerAngles(tmp1, tmp2, yaw);
3746  newPose = Transform(newPose.x(), newPose.y(), newPose.z(), roll, pitch, yaw);
3747  UDEBUG("newPose gravity=%s", newPose.prettyPrint().c_str());
3748  }
3749  else if(iterGravitySign!=signature->getLinks().end())
3750  {
3751  UWARN("Gravity link not found for %d, localization won't be corrected with gravity.", signature->id());
3752  }
3753  }
3754  _optimizedPoses.at(signature->id()) = newPose;
3755  }
3756  _localizationCovariance = locOptCovariance.empty()?localizationLinks.rbegin()->second.infMatrix().inv():locOptCovariance;
3757  }
3758  else //delayed localization (wait for more than 1 link)
3759  {
3760  UWARN("Localization was good, but waiting for another one to be more accurate (%s>0)", Parameters::kRGBDMaxOdomCacheSize().c_str());
3761  delayedLocalization = true;
3762  rejectLocalization = true;
3763  }
3764  }
3765  }
3766 
3767  if(rejectLocalization)
3768  {
3769  _loopClosureHypothesis.first = 0;
3770  lastProximitySpaceClosureId = 0;
3771  rejectedGlobalLoopClosure = true;
3772  rejectedLandmark = true;
3773  }
3774  }
3775  else
3776  {
3777  UINFO("Update map correction");
3778  std::map<int, Transform> poses = _optimizedPoses;
3779 
3780  // if _optimizeFromGraphEnd parameter just changed state, don't use optimized poses as guess
3782  {
3783  UWARN("Optimization: clearing guess poses as %s has changed state, now %s",
3784  Parameters::kRGBDOptimizeFromGraphEnd().c_str(), _optimizeFromGraphEnd?"true":"false");
3785  poses.clear();
3787  }
3788 
3789  std::multimap<int, Link> constraints;
3790  cv::Mat covariance;
3791  optimizeCurrentMap(signature->id(), false, poses, covariance, &constraints, &optimizationError, &optimizationIterations);
3792 
3793  // Check added loop closures have broken the graph
3794  // (in case of wrong loop closures).
3795  bool updateConstraints = true;
3796  if(poses.empty())
3797  {
3798  UWARN("Graph optimization failed! Rejecting last loop closures added.");
3799  for(std::list<std::pair<int, int> >::iterator iter=loopClosureLinksAdded.begin(); iter!=loopClosureLinksAdded.end(); ++iter)
3800  {
3801  _memory->removeLink(iter->first, iter->second);
3802  UWARN("Loop closure %d->%d rejected!", iter->first, iter->second);
3803  }
3804  updateConstraints = false;
3805  _loopClosureHypothesis.first = 0;
3806  lastProximitySpaceClosureId = 0;
3807  rejectedGlobalLoopClosure = true;
3808  rejectedLandmark = true;
3809  }
3810  else if(_memory->isIncremental() &&
3811  loopClosureLinksAdded.size() &&
3812  optimizationIterations > 0 &&
3813  constraints.size())
3814  {
3815  UINFO("Compute max graph errors...");
3816  const Link * maxLinearLink = 0;
3817  const Link * maxAngularLink = 0;
3819  poses,
3820  constraints,
3821  maxLinearErrorRatio,
3822  maxAngularErrorRatio,
3823  maxLinearError,
3824  maxAngularError,
3825  &maxLinearLink,
3826  &maxAngularLink);
3827  if(maxLinearLink == 0 && maxAngularLink==0)
3828  {
3829  UWARN("Could not compute graph errors! Wrong loop closures could be accepted!");
3830  }
3831 
3832  bool reject = false;
3833  if(maxLinearLink)
3834  {
3835  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()));
3836  if(_optimizationMaxError > 0.0f && maxLinearErrorRatio > _optimizationMaxError)
3837  {
3838  UWARN("Rejecting all added loop closures (%d, first is %d <-> %d) in this "
3839  "iteration because a wrong loop closure has been "
3840  "detected after graph optimization, resulting in "
3841  "a maximum graph error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). The "
3842  "maximum error ratio parameter \"%s\" is %f of std deviation.",
3843  (int)loopClosureLinksAdded.size(),
3844  loopClosureLinksAdded.front().first,
3845  loopClosureLinksAdded.front().second,
3846  maxLinearErrorRatio,
3847  maxLinearLink->from(),
3848  maxLinearLink->to(),
3849  maxLinearLink->type(),
3850  maxLinearError,
3851  sqrt(maxLinearLink->transVariance()),
3852  Parameters::kRGBDOptimizeMaxError().c_str(),
3854  reject = true;
3855  }
3856  else if(_optimizationMaxError == 0.0f && maxLinearErrorRatio>100 && !_graphOptimizer->isRobust())
3857  {
3858  UERROR("Huge optimization error detected!"
3859  "Linear error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). You may consider "
3860  "enabling \"%s\" to reject those bad optimizations by setting it to a non null value!",
3861  maxLinearErrorRatio,
3862  maxLinearLink->from(),
3863  maxLinearLink->to(),
3864  maxLinearLink->type(),
3865  maxLinearError,
3866  sqrt(maxLinearLink->transVariance()),
3867  Parameters::kRGBDOptimizeMaxError().c_str());
3868  }
3869  }
3870  if(maxAngularLink)
3871  {
3872  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()));
3873  if(_optimizationMaxError > 0.0f && maxAngularErrorRatio > _optimizationMaxError)
3874  {
3875  UWARN("Rejecting all added loop closures (%d, first is %d <-> %d) in this "
3876  "iteration because a wrong loop closure has been "
3877  "detected after graph optimization, resulting in "
3878  "a maximum graph error ratio of %f (edge %d->%d, type=%d, abs error=%f deg, stddev=%f). The "
3879  "maximum error ratio parameter \"%s\" is %f of std deviation.",
3880  (int)loopClosureLinksAdded.size(),
3881  loopClosureLinksAdded.front().first,
3882  loopClosureLinksAdded.front().second,
3883  maxAngularErrorRatio,
3884  maxAngularLink->from(),
3885  maxAngularLink->to(),
3886  maxAngularLink->type(),
3887  maxAngularError*180.0f/CV_PI,
3888  sqrt(maxAngularLink->rotVariance()),
3889  Parameters::kRGBDOptimizeMaxError().c_str(),
3891  reject = true;
3892  }
3893  else if(_optimizationMaxError == 0.0f && maxAngularErrorRatio>100 && !_graphOptimizer->isRobust())
3894  {
3895  UERROR("Huge optimization error detected!"
3896  "Angular error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). You may consider "
3897  "enabling \"%s\" to reject those bad optimizations by setting it to a non null value!",
3898  maxAngularErrorRatio,
3899  maxAngularLink->from(),
3900  maxAngularLink->to(),
3901  maxAngularLink->type(),
3902  maxAngularError*180.0f/CV_PI,
3903  sqrt(maxAngularLink->rotVariance()),
3904  Parameters::kRGBDOptimizeMaxError().c_str());
3905  }
3906  }
3907 
3908  if(reject)
3909  {
3910  for(std::list<std::pair<int, int> >::iterator iter=loopClosureLinksAdded.begin(); iter!=loopClosureLinksAdded.end(); ++iter)
3911  {
3912  _memory->removeLink(iter->first, iter->second);
3913  UWARN("Loop closure %d->%d rejected!", iter->first, iter->second);
3914  }
3915  updateConstraints = false;
3916  _loopClosureHypothesis.first = 0;
3917  lastProximitySpaceClosureId = 0;
3918  rejectedGlobalLoopClosure = true;
3919  rejectedLandmark = true;
3920  }
3921  }
3922 
3923  if(updateConstraints)
3924  {
3925  UINFO("Updated local map (old size=%d, new size=%d)", (int)_optimizedPoses.size(), (int)poses.size());
3926  _optimizedPoses = poses;
3927  _constraints = constraints;
3928  _localizationCovariance = covariance;
3929  }
3930  }
3931 
3932  // Update map correction, it should be identify when optimizing from the last node
3933  UASSERT(_optimizedPoses.find(signature->id()) != _optimizedPoses.end());
3934  if(fakeOdom && _mapCorrectionBackup.isNull())
3935  {
3937  }
3938  previousMapCorrection = _mapCorrection;
3939  _mapCorrection = _optimizedPoses.at(signature->id()) * signature->getPose().inverse();
3940  // Update statistics about the closest node in the graph using the actual loop closure
3942  {
3943  int closestNode = _loopClosureHypothesis.first>0?_loopClosureHypothesis.first:lastProximitySpaceClosureId;
3944  if(closestNode>0)
3945  {
3946  distanceToClosestNodeInTheGraph = _lastLocalizationPose.getDistance(_optimizedPoses.at(closestNode));
3947  UDEBUG("Last localization pose = %s, updated closest node=%d (%f m)", _lastLocalizationPose.prettyPrint().c_str(), closestNode, distanceToClosestNodeInTheGraph);
3948  angleToClosestNodeInTheGraph = (_lastLocalizationPose.inverse() * _optimizedPoses.at(closestNode)).getAngle();
3949  }
3950  }
3951  _lastLocalizationPose = _optimizedPoses.at(signature->id()); // update
3953  {
3954  bool hasPrior = signature->hasLink(signature->id());
3956  {
3957  for(std::multimap<int, Link>::reverse_iterator iter=_constraints.rbegin(); !hasPrior && iter!=_constraints.rend(); ++iter)
3958  {
3959  if(iter->second.type() == Link::kPosePrior)
3960  {
3961  hasPrior = true;
3962  }
3963  }
3964  }
3965  if((!hasPrior || _graphOptimizer->priorsIgnored()) && _graphOptimizer->gravitySigma()==0.0f)
3966  {
3967  UERROR("Map correction should be identity when optimizing from the last node. T=%s", _mapCorrection.prettyPrint().c_str());
3968  }
3969  }
3970  }
3971  int newLocId = _loopClosureHypothesis.first>0?_loopClosureHypothesis.first:lastProximitySpaceClosureId>0?lastProximitySpaceClosureId:0;
3972  _lastLocalizationNodeId = newLocId!=0?newLocId:_lastLocalizationNodeId;
3973  if(newLocId==0 && !landmarksDetected.empty())
3974  {
3975  std::map<int, std::set<int> >::const_iterator iter = _memory->getLandmarksIndex().find(landmarksDetected.begin()->first);
3976  if(iter!=_memory->getLandmarksIndex().end())
3977  {
3978  if(iter->second.size() && *iter->second.begin()!=signature->id())
3979  {
3980  _lastLocalizationNodeId = *iter->second.begin();
3981  }
3982  }
3983  }
3984 
3985  timeMapOptimization = timer.ticks();
3986  ULOGGER_INFO("timeMapOptimization=%fs", timeMapOptimization);
3987 
3988  //============================================================
3989  // Prepare statistics
3990  //============================================================
3991  // Data used for the statistics event and for the log files
3992  int dictionarySize = 0;
3993  int refWordsCount = 0;
3994  int refUniqueWordsCount = 0;
3995  int lcHypothesisReactivated = 0;
3996  float rehearsalValue = uValue(statistics_.data(), Statistics::kMemoryRehearsal_sim(), 0.0f);
3997  int rehearsalMaxId = (int)uValue(statistics_.data(), Statistics::kMemoryRehearsal_merged(), 0.0f);
3998  sLoop = _memory->getSignature(_loopClosureHypothesis.first?_loopClosureHypothesis.first:lastProximitySpaceClosureId?lastProximitySpaceClosureId:_highestHypothesis.first);
3999  if(sLoop)
4000  {
4001  lcHypothesisReactivated = sLoop->isSaved()?1.0f:0.0f;
4002  }
4003  dictionarySize = (int)_memory->getVWDictionary()->getVisualWords().size();
4004  refWordsCount = (int)signature->getWords().size();
4005  refUniqueWordsCount = (int)uUniqueKeys(signature->getWords()).size();
4006 
4007  if(_graphOptimizer->isSlam2d() && _localizationCovariance.total() == 36)
4008  {
4009  // set very small
4013  }
4014 
4015  // Posterior is empty if a bad signature is detected
4016  float vpHypothesis = posterior.size()?posterior.at(Memory::kIdVirtual):0.0f;
4017  int loopId = _loopClosureHypothesis.first>0?_loopClosureHypothesis.first:lastProximitySpaceClosureId;
4018 
4019  // prepare statistics
4021  {
4022  ULOGGER_INFO("sending stats...");
4023  statistics_.setRefImageId(_memory->getLastSignatureId()); // Use last id from Memory (in case of rehearsal)
4024  statistics_.setRefImageMapId(signature->mapId());
4025  statistics_.setStamp(data.stamp());
4027  {
4030  ULOGGER_INFO("Loop closure detected! With id=%d", _loopClosureHypothesis.first);
4031  }
4032 
4033  if(_publishStats)
4034  {
4035  ULOGGER_INFO("send all stats...");
4037 
4038  statistics_.addStatistic(Statistics::kLoopAccepted_hypothesis_id(), _loopClosureHypothesis.first);
4039  statistics_.addStatistic(Statistics::kLoopSuppressed_hypothesis_id(), loopIdSuppressedByProximity);
4040  statistics_.addStatistic(Statistics::kLoopHighest_hypothesis_id(), _highestHypothesis.first);
4041  statistics_.addStatistic(Statistics::kLoopHighest_hypothesis_value(), _highestHypothesis.second);
4042  statistics_.addStatistic(Statistics::kLoopHypothesis_reactivated(), lcHypothesisReactivated);
4043  statistics_.addStatistic(Statistics::kLoopVp_hypothesis(), vpHypothesis);
4044  statistics_.addStatistic(Statistics::kLoopReactivate_id(), retrievalId);
4045  statistics_.addStatistic(Statistics::kLoopHypothesis_ratio(), hypothesisRatio);
4046  statistics_.addStatistic(Statistics::kLoopVisual_inliers(), loopClosureVisualInliers);
4047  statistics_.addStatistic(Statistics::kLoopVisual_inliers_ratio(), loopClosureVisualInliersRatio);
4048  statistics_.addStatistic(Statistics::kLoopVisual_matches(), loopClosureVisualMatches);
4049  statistics_.addStatistic(Statistics::kLoopLinear_variance(), loopClosureLinearVariance);
4050  statistics_.addStatistic(Statistics::kLoopAngular_variance(), loopClosureAngularVariance);
4051  statistics_.addStatistic(Statistics::kLoopLast_id(), _memory->getLastGlobalLoopClosureId());
4052  statistics_.addStatistic(Statistics::kLoopOptimization_max_error(), maxLinearError);
4053  statistics_.addStatistic(Statistics::kLoopOptimization_max_error_ratio(), maxLinearErrorRatio);
4054  statistics_.addStatistic(Statistics::kLoopOptimization_max_ang_error(), maxAngularError*180.0f/M_PI);
4055  statistics_.addStatistic(Statistics::kLoopOptimization_max_ang_error_ratio(), maxAngularErrorRatio);
4056  statistics_.addStatistic(Statistics::kLoopOptimization_error(), optimizationError);
4057  statistics_.addStatistic(Statistics::kLoopOptimization_iterations(), optimizationIterations);
4058  statistics_.addStatistic(Statistics::kLoopLandmark_detected(), landmarksDetected.empty()?0:-landmarksDetected.begin()->first);
4059  statistics_.addStatistic(Statistics::kLoopLandmark_detected_node_ref(), landmarksDetected.empty() || landmarksDetected.begin()->second.empty()?0:*landmarksDetected.begin()->second.begin());
4060  statistics_.addStatistic(Statistics::kLoopVisual_inliers_mean_dist(), loopClosureVisualInliersMeanDist);
4061  statistics_.addStatistic(Statistics::kLoopVisual_inliers_distribution(), loopClosureVisualInliersDistribution);
4062 
4063  statistics_.addStatistic(Statistics::kProximityTime_detections(), proximityDetectionsInTimeFound);
4064  statistics_.addStatistic(Statistics::kProximitySpace_detections_added_visually(), proximityDetectionsAddedVisually);
4065  statistics_.addStatistic(Statistics::kProximitySpace_detections_added_icp_multi(), proximityDetectionsAddedByICPMulti);
4066  statistics_.addStatistic(Statistics::kProximitySpace_detections_added_icp_global(), proximityDetectionsAddedByICPGlobal);
4067  statistics_.addStatistic(Statistics::kProximitySpace_paths(), proximitySpacePaths);
4068  statistics_.addStatistic(Statistics::kProximitySpace_visual_paths_checked(), localVisualPathsChecked);
4069  statistics_.addStatistic(Statistics::kProximitySpace_scan_paths_checked(), localScanPathsChecked);
4070  statistics_.addStatistic(Statistics::kProximitySpace_last_detection_id(), lastProximitySpaceClosureId);
4071  statistics_.setProximityDetectionId(lastProximitySpaceClosureId);
4072  statistics_.setProximityDetectionMapId(_memory->getMapId(lastProximitySpaceClosureId));
4073 
4074  statistics_.addStatistic(Statistics::kLoopId(), loopId);
4075  statistics_.addStatistic(Statistics::kLoopMap_id(), (loopId>0 && sLoop)?sLoop->mapId():-1);
4076 
4077  statistics_.addStatistic(Statistics::kLoopDistance_since_last_loc(), _distanceTravelledSinceLastLocalization);
4078 
4079  float x,y,z,roll,pitch,yaw;
4080  if(_loopClosureHypothesis.first || lastProximitySpaceClosureId || (!rejectedLandmark && !landmarksDetected.empty()))
4081  {
4082  if(_loopClosureHypothesis.first || lastProximitySpaceClosureId)
4083  {
4084  // Loop closure transform
4085  UASSERT(sLoop);
4086  std::multimap<int, Link>::const_iterator loopIter = sLoop->getLinks().find(signature->id());
4087  UASSERT(loopIter!=sLoop->getLinks().end());
4088  UINFO("Set loop closure transform = %s", loopIter->second.transform().prettyPrint().c_str());
4089  statistics_.setLoopClosureTransform(loopIter->second.transform());
4090 
4091  statistics_.addStatistic(Statistics::kLoopVisual_words(), sLoop->getWords().size());
4092 
4093  // if ground truth exists, compute localization error
4094  if(!sLoop->getGroundTruthPose().isNull() && !signature->getGroundTruthPose().isNull())
4095  {
4096  Transform transformGT = sLoop->getGroundTruthPose().inverse() * signature->getGroundTruthPose();
4097  Transform error = loopIter->second.transform().inverse() * transformGT;
4098  statistics_.addStatistic(Statistics::kGtLocalization_linear_error(), error.getNorm());
4099  statistics_.addStatistic(Statistics::kGtLocalization_angular_error(), error.getAngle(1,0,0)*180/M_PI);
4100  }
4101  }
4102 
4104 
4105  statistics_.addStatistic(Statistics::kLoopMapToOdom_norm(), _mapCorrection.getNorm());
4106  statistics_.addStatistic(Statistics::kLoopMapToOdom_angle(), _mapCorrection.getAngle()*180.0f/M_PI);
4108  statistics_.addStatistic(Statistics::kLoopMapToOdom_x(), x);
4109  statistics_.addStatistic(Statistics::kLoopMapToOdom_y(), y);
4110  statistics_.addStatistic(Statistics::kLoopMapToOdom_z(), z);
4111  statistics_.addStatistic(Statistics::kLoopMapToOdom_roll(), roll*180.0f/M_PI);
4112  statistics_.addStatistic(Statistics::kLoopMapToOdom_pitch(), pitch*180.0f/M_PI);
4113  statistics_.addStatistic(Statistics::kLoopMapToOdom_yaw(), yaw*180.0f/M_PI);
4114 
4115  // Odom correction (actual odometry pose change), ignore correction from first localization
4116  if(!odomPose.isNull() && !previousMapCorrection.isNull() && !previousMapCorrection.isIdentity())
4117  {
4118  Transform odomCorrection = (previousMapCorrection*odomPose).inverse()*_mapCorrection*odomPose;
4119  statistics_.addStatistic(Statistics::kLoopOdom_correction_norm(), odomCorrection.getNorm());
4120  statistics_.addStatistic(Statistics::kLoopOdom_correction_angle(), odomCorrection.getAngle()*180.0f/M_PI);
4121  odomCorrection.getTranslationAndEulerAngles(x, y, z, roll, pitch, yaw);
4122  statistics_.addStatistic(Statistics::kLoopOdom_correction_x(), x);
4123  statistics_.addStatistic(Statistics::kLoopOdom_correction_y(), y);
4124  statistics_.addStatistic(Statistics::kLoopOdom_correction_z(), z);
4125  statistics_.addStatistic(Statistics::kLoopOdom_correction_roll(), roll*180.0f/M_PI);
4126  statistics_.addStatistic(Statistics::kLoopOdom_correction_pitch(), pitch*180.0f/M_PI);
4127  statistics_.addStatistic(Statistics::kLoopOdom_correction_yaw(), yaw*180.0f/M_PI);
4128  }
4129  }
4131  {
4133  statistics_.addStatistic(Statistics::kLoopMapToBase_x(), x);
4134  statistics_.addStatistic(Statistics::kLoopMapToBase_y(), y);
4135  statistics_.addStatistic(Statistics::kLoopMapToBase_z(), z);
4136  statistics_.addStatistic(Statistics::kLoopMapToBase_roll(), roll*180.0f/M_PI);
4137  statistics_.addStatistic(Statistics::kLoopMapToBase_pitch(), pitch*180.0f/M_PI);
4138  statistics_.addStatistic(Statistics::kLoopMapToBase_yaw(), yaw*180.0f/M_PI);
4139  UINFO("Localization pose = %s", _lastLocalizationPose.prettyPrint().c_str());
4140 
4141  if(_localizationCovariance.total()==36)
4142  {
4143  double varLin = _graphOptimizer->isSlam2d()?
4144  std::max(_localizationCovariance.at<double>(0,0), _localizationCovariance.at<double>(1,1)):
4145  uMax3(_localizationCovariance.at<double>(0,0), _localizationCovariance.at<double>(1,1), _localizationCovariance.at<double>(2,2));
4146 
4147  statistics_.addStatistic(Statistics::kLoopMapToBase_lin_std(), sqrt(varLin));
4148  statistics_.addStatistic(Statistics::kLoopMapToBase_lin_var(), varLin);
4149  }
4150  }
4151 
4153  UINFO("Set map correction = %s", _mapCorrection.prettyPrint().c_str());
4155 
4156  // timings...
4157  statistics_.addStatistic(Statistics::kTimingMemory_update(), timeMemoryUpdate*1000);
4158  statistics_.addStatistic(Statistics::kTimingNeighbor_link_refining(), timeNeighborLinkRefining*1000);
4159  statistics_.addStatistic(Statistics::kTimingProximity_by_time(), timeProximityByTimeDetection*1000);
4160  statistics_.addStatistic(Statistics::kTimingProximity_by_space_search(), timeProximityBySpaceSearch*1000);
4161  statistics_.addStatistic(Statistics::kTimingProximity_by_space_visual(), timeProximityBySpaceVisualDetection*1000);
4162  statistics_.addStatistic(Statistics::kTimingProximity_by_space(), timeProximityBySpaceDetection*1000);
4163  statistics_.addStatistic(Statistics::kTimingReactivation(), timeReactivations*1000);
4164  statistics_.addStatistic(Statistics::kTimingAdd_loop_closure_link(), timeAddLoopClosureLink*1000);
4165  statistics_.addStatistic(Statistics::kTimingMap_optimization(), timeMapOptimization*1000);
4166  statistics_.addStatistic(Statistics::kTimingLikelihood_computation(), timeLikelihoodCalculation*1000);
4167  statistics_.addStatistic(Statistics::kTimingPosterior_computation(), timePosteriorCalculation*1000);
4168  statistics_.addStatistic(Statistics::kTimingHypotheses_creation(), timeHypothesesCreation*1000);
4169  statistics_.addStatistic(Statistics::kTimingHypotheses_validation(), timeHypothesesValidation*1000);
4170  statistics_.addStatistic(Statistics::kTimingCleaning_neighbors(), timeCleaningNeighbors*1000);
4171 
4172  // retrieval
4173  statistics_.addStatistic(Statistics::kMemorySignatures_retrieved(), (float)signaturesRetrieved.size());
4174 
4175  // Feature specific parameters
4176  statistics_.addStatistic(Statistics::kKeypointDictionary_size(), dictionarySize);
4177  statistics_.addStatistic(Statistics::kKeypointCurrent_frame(), refWordsCount);
4178  statistics_.addStatistic(Statistics::kKeypointIndexed_words(), _memory->getVWDictionary()->getIndexedWordsCount());
4179  statistics_.addStatistic(Statistics::kKeypointIndex_memory_usage(), _memory->getVWDictionary()->getIndexMemoryUsed());
4180 
4181  //Epipolar geometry constraint
4182  statistics_.addStatistic(Statistics::kLoopRejectedHypothesis(), rejectedGlobalLoopClosure?1.0f:0);
4183 
4184  statistics_.addStatistic(Statistics::kMemorySmall_movement(), smallDisplacement?1.0f:0);
4185  statistics_.addStatistic(Statistics::kMemoryDistance_travelled(), _distanceTravelled);
4186  statistics_.addStatistic(Statistics::kMemoryFast_movement(), tooFastMovement?1.0f:0);
4187  statistics_.addStatistic(Statistics::kMemoryNew_landmark(), addedNewLandmark?1.0f:0);
4188 
4189  if(distanceToClosestNodeInTheGraph>0.0)
4190  {
4191  statistics_.addStatistic(Statistics::kMemoryClosest_node_distance(), distanceToClosestNodeInTheGraph);
4192  statistics_.addStatistic(Statistics::kMemoryClosest_node_angle(), angleToClosestNodeInTheGraph);
4193  }
4194 
4195  if(_publishRAMUsage)
4196  {
4197  UTimer ramTimer;
4198  statistics_.addStatistic(Statistics::kMemoryRAM_usage(), UProcessInfo::getMemoryUsage()/(1024*1024));
4199  long estimatedMemoryUsage = sizeof(Rtabmap);
4200  estimatedMemoryUsage += _optimizedPoses.size() * (sizeof(int) + sizeof(Transform) + 12 * sizeof(float) + sizeof(std::map<int, Transform>::iterator)) + sizeof(std::map<int, Transform>);
4201  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>);
4202  estimatedMemoryUsage += _memory->getMemoryUsed();
4203  estimatedMemoryUsage += _bayesFilter->getMemoryUsed();
4204  estimatedMemoryUsage += _parameters.size()*(sizeof(std::string)*2+sizeof(ParametersMap::iterator)) + sizeof(ParametersMap);
4205  statistics_.addStatistic(Statistics::kMemoryRAM_estimated(), (float)(estimatedMemoryUsage/(1024*1024)));//MB
4206  statistics_.addStatistic(Statistics::kTimingRAM_estimation(), ramTimer.ticks()*1000);
4207  }
4208 
4210  {
4211  // Child count by parent signature on the root of the memory ... for statistics
4212  statistics_.setWeights(weights);
4213  if(_publishPdf)
4214  {
4215  statistics_.setPosterior(posterior);
4216  }
4217  if(_publishLikelihood)
4218  {
4219  statistics_.setLikelihood(likelihood);
4220  statistics_.setRawLikelihood(rawLikelihood);
4221  }
4222  }
4223 
4225 
4226  // Path
4227  if(_path.size())
4228  {
4231  }
4232  }
4233 
4234  timeStatsCreation = timer.ticks();
4235  ULOGGER_INFO("Time creating stats = %f...", timeStatsCreation);
4236  }
4237 
4238  Signature lastSignatureData = *signature;
4239  Transform lastSignatureLocalizedPose;
4240  if(_optimizedPoses.find(signature->id()) != _optimizedPoses.end())
4241  {
4242  lastSignatureLocalizedPose = _optimizedPoses.at(signature->id());
4243  }
4245  {
4246  lastSignatureData.sensorData().clearCompressedData();
4247  lastSignatureData.sensorData().clearRawData();
4248  }
4249  if(!_rawDataKept)
4250  {
4251  _memory->removeRawData(signature->id(), true, !_neighborLinkRefining && !_proximityBySpace, true);
4252  }
4253 
4254  // Localization mode and saving localization data: save odometry covariance in a prior link
4255  // so that DBReader can republish the covariance of localization data
4256  if(!_memory->isIncremental() && _memory->isLocalizationDataSaved() && !odomCovariance.empty())
4257  {
4258  _memory->addLink(Link(signature->id(), signature->id(), Link::kPosePrior, odomPose, odomCovariance.inv()));
4259  }
4260 
4261  // remove last signature if the memory is not incremental or is a bad signature (if bad signatures are ignored)
4262  int signatureRemoved = _memory->cleanup();
4263  if(signatureRemoved)
4264  {
4265  signaturesRemoved.push_back(signatureRemoved);
4266  }
4267 
4268  // If this option activated, add new nodes only if there are linked with a previous map.
4269  // Used when rtabmap is first started, it will wait a
4270  // global loop closure detection before starting the new map,
4271  // otherwise it deletes the current node.
4272  if(signatureRemoved != lastSignatureData.id())
4273  {
4275  _memory->isIncremental() && // only in mapping mode
4276  graph::filterLinks(signature->getLinks(), Link::kSelfRefLink).size() == 0 && // alone in the current map
4277  (landmarksDetected.empty() || rejectedLandmark) && // if we re not seeing a landmark from a previous map
4278  _memory->getWorkingMem().size()>=2) // The working memory should not be empty (beside virtual signature)
4279  {
4280  UWARN("Ignoring location %d because a global loop closure is required before starting a new map!",
4281  signature->id());
4282  signaturesRemoved.push_back(signature->id());
4283  _memory->deleteLocation(signature->id());
4284  }
4285  else if(_startNewMapOnGoodSignature &&
4286  (signature->getLandmarks().empty() && signature->isBadSignature()) &&
4287  graph::filterLinks(signature->getLinks(), Link::kSelfRefLink).size() == 0) // alone in the current map
4288  {
4289  UWARN("Ignoring location %d because a good signature (with enough features or with a landmark detected) is required before starting a new map!",
4290  signature->id());
4291  signaturesRemoved.push_back(signature->id());
4292  _memory->deleteLocation(signature->id());
4293  }
4294  else if((smallDisplacement || tooFastMovement) &&
4295  _loopClosureHypothesis.first == 0 &&
4296  lastProximitySpaceClosureId == 0 &&
4297  (rejectedLandmark || landmarksDetected.empty()) &&
4298  !addedNewLandmark)
4299  {
4300  // Don't delete the location if a loop closure is detected
4301  UINFO("Ignoring location %d because the displacement is too small! (d=%f a=%f)",
4302  signature->id(), _rgbdLinearUpdate, _rgbdAngularUpdate);
4303  // If there is a too small displacement, remove the node
4304  signaturesRemoved.push_back(signature->id());
4305  _memory->deleteLocation(signature->id());
4306  }
4307  else
4308  {
4309  _memory->saveLocationData(signature->id());
4310  }
4311  }
4312  else if(!_memory->isIncremental() &&
4313  (smallDisplacement || tooFastMovement) &&
4314  _loopClosureHypothesis.first == 0 &&
4315  lastProximitySpaceClosureId == 0 &&
4316  !delayedLocalization &&
4317  (rejectedLandmark || landmarksDetected.empty()))
4318  {
4319  _odomCachePoses.erase(signatureRemoved);
4320  for(std::multimap<int, Link>::iterator iter=_odomCacheConstraints.begin(); iter!=_odomCacheConstraints.end();)
4321  {
4322  if(iter->second.from() == signatureRemoved || iter->second.to() == signatureRemoved)
4323  {
4324  _odomCacheConstraints.erase(iter++);
4325  }
4326  else
4327  {
4328  ++iter;
4329  }
4330  }
4331  }
4332 
4333  // Pass this point signature should not be used, since it could have been transferred...
4334  signature = 0;
4335 
4336  timeMemoryCleanup = timer.ticks();
4337  ULOGGER_INFO("timeMemoryCleanup = %fs... %d signatures removed", timeMemoryCleanup, (int)signaturesRemoved.size());
4338 
4339 
4340 
4341  //============================================================
4342  // TRANSFER
4343  //============================================================
4344  // If time allowed for the detection exceeds the limit of
4345  // real-time, move the oldest signature with less frequency
4346  // entry (from X oldest) from the short term memory to the
4347  // long term memory.
4348  //============================================================
4349  double totalTime = timerTotal.ticks();
4350  ULOGGER_INFO("Total time processing = %fs...", totalTime);
4351  if((_maxTimeAllowed != 0 && totalTime*1000>_maxTimeAllowed) ||
4353  {
4354  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);
4355  immunizedLocations.insert(_lastLocalizationNodeId); // keep the latest localization in working memory
4356  std::list<int> transferred = _memory->forget(immunizedLocations);
4357  signaturesRemoved.insert(signaturesRemoved.end(), transferred.begin(), transferred.end());
4358  if(!_someNodesHaveBeenTransferred && transferred.size())
4359  {
4360  _someNodesHaveBeenTransferred = true; // only used to hide a warning on close nodes immunization
4361  }
4362  }
4363  _lastProcessTime = totalTime;
4364 
4365  // cleanup cached gps values
4366  for(std::list<int>::iterator iter=signaturesRemoved.begin(); iter!=signaturesRemoved.end() && _gpsGeocentricCache.size(); ++iter)
4367  {
4368  _gpsGeocentricCache.erase(*iter);
4369  }
4370 
4371  //Remove optimized poses from signatures transferred
4372  if(signaturesRemoved.size() && (_optimizedPoses.size() || _constraints.size()))
4373  {
4374  //refresh the local map because some transferred nodes may have broken the tree
4375  int id = 0;
4376  if(!_memory->isIncremental() && (_lastLocalizationNodeId > 0 || _path.size()))
4377  {
4378  if(_path.size())
4379  {
4380  // priority on node on the path
4381  UASSERT(_pathCurrentIndex < _path.size());
4382  UASSERT_MSG(uContains(_optimizedPoses, _path.at(_pathCurrentIndex).first), uFormat("id=%d", _path.at(_pathCurrentIndex).first).c_str());
4383  id = _path.at(_pathCurrentIndex).first;
4384  UDEBUG("Refresh local map from %d", id);
4385  }
4386  else
4387  {
4389  {
4391  UDEBUG("Refresh local map from %d", id);
4392  }
4393  else
4394  {
4395  UDEBUG("Clearing _lastLocalizationNodeId(%d)", _lastLocalizationNodeId);
4397  }
4398  }
4399  }
4400  else if(_memory->isIncremental() &&
4401  _optimizedPoses.size() &&
4403  {
4404  id = _memory->getLastWorkingSignature()->id();
4405  UDEBUG("Refresh local map from %d", id);
4406  }
4407  UDEBUG("id=%d _optimizedPoses=%d", id, (int)_optimizedPoses.size());
4408  if(id > 0)
4409  {
4410  if(_lastLocalizationNodeId != 0)
4411  {
4413  }
4414  UASSERT_MSG(_memory->getSignature(id) != 0, uFormat("id=%d", id).c_str());
4415 
4416  if(signaturesRemoved.size() == 1 && signaturesRemoved.front() == lastSignatureData.id())
4417  {
4418  int lastId = signaturesRemoved.front();
4419  UDEBUG("Detected that only last signature has been removed (lastId=%d)", lastId);
4420  _optimizedPoses.erase(lastId);
4421  for(std::multimap<int, Link>::iterator iter=_constraints.find(lastId); iter!=_constraints.end() && iter->first==lastId;++iter)
4422  {
4423  if(iter->second.to() != iter->second.from())
4424  {
4425  std::multimap<int, Link>::iterator jter = graph::findLink(_constraints, iter->second.to(), iter->second.from(), false);
4426  if(jter != _constraints.end())
4427  {
4428  _constraints.erase(jter);
4429  }
4430  }
4431  }
4432  _constraints.erase(lastId);
4433  }
4434  else
4435  {
4436 
4437  std::map<int, int> ids = _memory->getNeighborsId(id, 0, 0, true);
4438  for(std::map<int, Transform>::iterator iter=_optimizedPoses.begin(); iter!=_optimizedPoses.end();)
4439  {
4440  if(iter->first > 0 && !uContains(ids, iter->first))
4441  {
4442  UDEBUG("Removed %d from local map", iter->first);
4444  _optimizedPoses.erase(iter++);
4445 
4446  if(!_globalScanMap.empty())
4447  {
4448  UWARN("optimized poses have been modified, clearing global scan map...");
4450  _globalScanMapPoses.clear();
4451  }
4452  }
4453  else
4454  {
4455  ++iter;
4456  }
4457  }
4458  for(std::multimap<int, Link>::iterator iter=_constraints.begin(); iter!=_constraints.end();)
4459  {
4460  if(iter->first > 0 && (!uContains(ids, iter->second.from()) || !uContains(ids, iter->second.to())))
4461  {
4462  _constraints.erase(iter++);
4463  }
4464  else
4465  {
4466  ++iter;
4467  }
4468  }
4469  }
4470  }
4471  else
4472  {
4473  if(!_optimizedPoses.empty())
4474  UDEBUG("Optimized poses cleared!");
4475  _optimizedPoses.clear();
4476  _constraints.clear();
4477  }
4478  }
4479  // just some verifications to make sure that planning path is still in the local map!
4480  if(_path.size())
4481  {
4482  UASSERT(_pathCurrentIndex < _path.size());
4483  UASSERT(_pathGoalIndex < _path.size());
4484  UASSERT_MSG(uContains(_optimizedPoses, _path.at(_pathCurrentIndex).first), uFormat("local map size=%d, id=%d", (int)_optimizedPoses.size(), _path.at(_pathCurrentIndex).first).c_str());
4485  UASSERT_MSG(uContains(_optimizedPoses, _path.at(_pathGoalIndex).first), uFormat("local map size=%d, id=%d", (int)_optimizedPoses.size(), _path.at(_pathGoalIndex).first).c_str());
4486  }
4487 
4488 
4489  timeRealTimeLimitReachedProcess = timer.ticks();
4490  ULOGGER_INFO("Time limit reached processing = %f...", timeRealTimeLimitReachedProcess);
4491 
4492  //==============================================================
4493  // Finalize statistics and log files
4494  //==============================================================
4495  int localGraphSize = 0;
4496  if(_publishStats)
4497  {
4498  statistics_.addStatistic(Statistics::kTimingStatistics_creation(), timeStatsCreation*1000);
4499  statistics_.addStatistic(Statistics::kTimingTotal(), totalTime*1000);
4500  statistics_.addStatistic(Statistics::kTimingForgetting(), timeRealTimeLimitReachedProcess*1000);
4501  statistics_.addStatistic(Statistics::kTimingJoining_trash(), timeJoiningTrash*1000);
4502  statistics_.addStatistic(Statistics::kTimingEmptying_trash(), timeEmptyingTrash*1000);
4503  statistics_.addStatistic(Statistics::kTimingMemory_cleanup(), timeMemoryCleanup*1000);
4504 
4505  // Transfer
4506  statistics_.addStatistic(Statistics::kMemorySignatures_removed(), signaturesRemoved.size());
4507  statistics_.addStatistic(Statistics::kMemoryImmunized_globally(), immunizedGlobally);
4508  statistics_.addStatistic(Statistics::kMemoryImmunized_locally(), immunizedLocally);
4509  statistics_.addStatistic(Statistics::kMemoryImmunized_locally_max(), maxLocalLocationsImmunized);
4510 
4511  // place after transfer because the memory/local graph may have changed
4512  statistics_.addStatistic(Statistics::kMemoryWorking_memory_size(), _memory->getWorkingMem().size());
4513  statistics_.addStatistic(Statistics::kMemoryShort_time_memory_size(), _memory->getStMem().size());
4514  statistics_.addStatistic(Statistics::kMemoryDatabase_memory_used(), _memory->getDatabaseMemoryUsed());
4515 
4516  // Set local graph
4517  std::map<int, Transform> poses;
4518  std::multimap<int, Link> constraints;
4519  if(!_rgbdSlamMode)
4520  {
4521  UDEBUG("");
4522  // no optimization on appearance-only mode, create a local graph
4523  std::map<int, int> ids = _memory->getNeighborsId(lastSignatureData.id(), 0, 0, true);
4524  _memory->getMetricConstraints(uKeysSet(ids), poses, constraints, false);
4525  }
4526  else // RGBD-SLAM mode
4527  {
4528  poses = _optimizedPoses;
4529  constraints = _constraints;
4530  }
4531  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);
4532  statistics_.addSignatureData(lastSignatureData);
4533 
4534  if(_nodesToRepublish.size())
4535  {
4536  std::multimap<int, int> missingIds;
4537 
4538  // priority to loopId
4539  int tmpId = loopId>0?loopId:_highestHypothesis.first;
4540  if(tmpId>0 && _nodesToRepublish.find(tmpId) != _nodesToRepublish.end())
4541  {
4542  missingIds.insert(std::make_pair(-1, tmpId));
4543  }
4544 
4546  {
4547  // Republish data from closest nodes of the current localization
4548  std::map<int, Transform> nodesOnly(_optimizedPoses.lower_bound(1), _optimizedPoses.end());
4550  if(id>0)
4551  {
4552  std::map<int, int> ids = _memory->getNeighborsId(id, 0, 0, true, false, true);
4553  for(std::map<int, int>::iterator iter=ids.begin(); iter!=ids.end(); ++iter)
4554  {
4555  if(iter->first != loopId &&
4556  _nodesToRepublish.find(iter->first) != _nodesToRepublish.end())
4557  {
4558  missingIds.insert(std::make_pair(iter->second, iter->first));
4559  }
4560  }
4561 
4562  if(_nodesToRepublish.size() != missingIds.size())
4563  {
4564  // remove requested nodes not anymore in the graph
4565  for(std::set<int>::iterator iter=_nodesToRepublish.begin(); iter!=_nodesToRepublish.end();)
4566  {
4567  if(ids.find(*iter) == ids.end())
4568  {
4569  iter = _nodesToRepublish.erase(iter);
4570  }
4571  else
4572  {
4573  ++iter;
4574  }
4575  }
4576  }
4577  }
4578  }
4579 
4580  int loaded = 0;
4581  std::stringstream stream;
4582  for(std::multimap<int, int>::iterator iter=missingIds.begin(); iter!=missingIds.end() && loaded<(int)_maxRepublished; ++iter)
4583  {
4584  statistics_.addSignatureData(getSignatureCopy(iter->second, true, true, true, true, true, true));
4585  _nodesToRepublish.erase(iter->second);
4586  ++loaded;
4587  stream << iter->second << " ";
4588  }
4589  if(loaded)
4590  {
4591  UWARN("Republishing data of requested node(s) %s(%s=%d)",
4592  stream.str().c_str(),
4593  Parameters::kRtabmapMaxRepublished().c_str(),
4594  _maxRepublished);
4595  }
4596  }
4597 
4598  UDEBUG("");
4599  localGraphSize = (int)poses.size();
4600  if(!lastSignatureLocalizedPose.isNull())
4601  {
4602  poses.insert(std::make_pair(lastSignatureData.id(), lastSignatureLocalizedPose)); // in case we are in localization
4603  }
4604  statistics_.setPoses(poses);
4605  statistics_.setConstraints(constraints);
4606 
4607  statistics_.addStatistic(Statistics::kMemoryLocal_graph_size(), poses.size());
4608 
4611  statistics_.addStatistic(Statistics::kMemoryOdom_cache_poses(), _odomCachePoses.size());
4612  statistics_.addStatistic(Statistics::kMemoryOdom_cache_links(), _odomCacheConstraints.size());
4613 
4614  if(_computeRMSE && _memory->getGroundTruths().size())
4615  {
4616  UDEBUG("Computing RMSE...");
4617  float translational_rmse = 0.0f;
4618  float translational_mean = 0.0f;
4619  float translational_median = 0.0f;
4620  float translational_std = 0.0f;
4621  float translational_min = 0.0f;
4622  float translational_max = 0.0f;
4623  float rotational_rmse = 0.0f;
4624  float rotational_mean = 0.0f;
4625  float rotational_median = 0.0f;
4626  float rotational_std = 0.0f;
4627  float rotational_min = 0.0f;
4628  float rotational_max = 0.0f;
4629 
4632  poses,
4633  translational_rmse,
4634  translational_mean,
4635  translational_median,
4636  translational_std,
4637  translational_min,
4638  translational_max,
4639  rotational_rmse,
4640  rotational_mean,
4641  rotational_median,
4642  rotational_std,
4643  rotational_min,
4644  rotational_max);
4645 
4646  statistics_.addStatistic(Statistics::kGtTranslational_rmse(), translational_rmse);
4647  statistics_.addStatistic(Statistics::kGtTranslational_mean(), translational_mean);
4648  statistics_.addStatistic(Statistics::kGtTranslational_median(), translational_median);
4649  statistics_.addStatistic(Statistics::kGtTranslational_std(), translational_std);
4650  statistics_.addStatistic(Statistics::kGtTranslational_min(), translational_min);
4651  statistics_.addStatistic(Statistics::kGtTranslational_max(), translational_max);
4652  statistics_.addStatistic(Statistics::kGtRotational_rmse(), rotational_rmse);
4653  statistics_.addStatistic(Statistics::kGtRotational_mean(), rotational_mean);
4654  statistics_.addStatistic(Statistics::kGtRotational_median(), rotational_median);
4655  statistics_.addStatistic(Statistics::kGtRotational_std(), rotational_std);
4656  statistics_.addStatistic(Statistics::kGtRotational_min(), rotational_min);
4657  statistics_.addStatistic(Statistics::kGtRotational_max(), rotational_max);
4658  UDEBUG("Computing RMSE...done!");
4659  }
4660 
4661  std::vector<int> ids;
4662  ids.reserve(_memory->getWorkingMem().size() + _memory->getStMem().size());
4663  for(std::set<int>::const_iterator iter=_memory->getStMem().begin(); iter!=_memory->getStMem().end(); ++iter)
4664  {
4665  ids.push_back(*iter);
4666  }
4667  for(std::map<int, double>::const_iterator iter=_memory->getWorkingMem().lower_bound(0); iter!=_memory->getWorkingMem().end(); ++iter)
4668  {
4669  ids.push_back(iter->first);
4670  }
4671  statistics_.setWmState(ids);
4672  UDEBUG("wmState=%d", (int)ids.size());
4673  }
4674 
4675  //Save statistics to database
4677  {
4679  }
4680 
4681  //Start trashing
4682  UDEBUG("Empty trash...");
4683  _memory->emptyTrash();
4684 
4685  // Log info...
4686  // TODO : use a specific class which will handle the RtabmapEvent
4687  if(_foutFloat && _foutInt)
4688  {
4689  UDEBUG("Logging...");
4690  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",
4691  totalTime,
4692  timeMemoryUpdate,
4693  timeReactivations,
4694  timeLikelihoodCalculation,
4695  timePosteriorCalculation,
4696  timeHypothesesCreation,
4697  timeHypothesesValidation,
4698  timeRealTimeLimitReachedProcess,
4699  timeStatsCreation,
4700  _highestHypothesis.second,
4701  0.0f,
4702  0.0f,
4703  0.0f,
4704  0.0f,
4705  0.0f,
4706  vpHypothesis,
4707  timeJoiningTrash,
4708  rehearsalValue,
4709  timeEmptyingTrash,
4710  timeRetrievalDbAccess,
4711  timeAddLoopClosureLink,
4712  timeMemoryCleanup,
4713  timeNeighborLinkRefining,
4714  timeProximityByTimeDetection,
4715  timeProximityBySpaceDetection,
4716  timeMapOptimization);
4717  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",
4718  _loopClosureHypothesis.first,
4719  _highestHypothesis.first,
4720  (int)signaturesRemoved.size(),
4721  0,
4722  refWordsCount,
4723  dictionarySize,
4724  int(_memory->getWorkingMem().size()),
4725  rejectedGlobalLoopClosure?1:0,
4726  0,
4727  0,
4728  int(signaturesRetrieved.size()),
4729  lcHypothesisReactivated,
4730  refUniqueWordsCount,
4731  retrievalId,
4732  0,
4733  rehearsalMaxId,
4734  rehearsalMaxId>0?1:0,
4735  localGraphSize,
4736  data.id(),
4740  {
4741  _bufferedLogsF.push_back(logF);
4742  _bufferedLogsI.push_back(logI);
4743  }
4744  else
4745  {
4746  if(_foutFloat)
4747  {
4748  fprintf(_foutFloat, "%s", logF.c_str());
4749  }
4750  if(_foutInt)
4751  {
4752  fprintf(_foutInt, "%s", logI.c_str());
4753  }
4754  }
4755  UINFO("Time logging = %f...", timer.ticks());
4756  //ULogger::flush();
4757  }
4758  timeFinalizingStatistics = timer.ticks();
4759  UDEBUG("End process, timeFinalizingStatistics=%fs", timeFinalizingStatistics);
4760  if(_publishStats)
4761  {
4762  statistics_.addStatistic(Statistics::kTimingFinalizing_statistics(), timeFinalizingStatistics*1000);
4763  }
4764 
4765  return true;
4766 }
4767 
4768 // SETTERS
4769 void Rtabmap::setTimeThreshold(float maxTimeAllowed)
4770 {
4771  //must be positive, 0 mean inf time allowed (no time limit)
4772  _maxTimeAllowed = maxTimeAllowed;
4773  if(_maxTimeAllowed < 0)
4774  {
4775  ULOGGER_WARN("maxTimeAllowed < 0, then setting it to 0 (inf).");
4776  _maxTimeAllowed = 0;
4777  }
4778  else if(_maxTimeAllowed > 0.0f && _maxTimeAllowed < 1.0f)
4779  {
4780  ULOGGER_WARN("Time threshold set to %fms, it is not in seconds!", _maxTimeAllowed);
4781  }
4782 }
4783 void Rtabmap::setMemoryThreshold(int maxMemoryAllowed)
4784 {
4785  //must be positive, 0 mean inf memory allowed (no memory limit)
4786  _maxMemoryAllowed = maxMemoryAllowed;
4787  if(maxMemoryAllowed < 0)
4788  {
4789  ULOGGER_WARN("maxMemoryAllowed < 0, then setting it to 0 (inf).");
4790  _maxMemoryAllowed = 0;
4791  }
4792 }
4793 
4794 void Rtabmap::setWorkingDirectory(std::string path)
4795 {
4797  if(!path.empty() && UDirectory::exists(path))
4798  {
4799  ULOGGER_DEBUG("Comparing new working directory path \"%s\" with \"%s\"", path.c_str(), _wDir.c_str());
4800  if(path.compare(_wDir) != 0)
4801  {
4802  if (_foutFloat || _foutInt)
4803  {
4804  UWARN("Working directory has been changed from \"%s\" with \"%s\", new log files will be created.",
4805  path.c_str(), _wDir.c_str());
4806  }
4807  _wDir = path;
4808  setupLogFiles();
4809  }
4810  }
4811  else if(path.empty())
4812  {
4813  _wDir.clear();
4814  setupLogFiles();
4815  }
4816  else
4817  {
4818  ULOGGER_ERROR("Directory \"%s\" doesn't exist!", path.c_str());
4819  }
4820 }
4821 
4823 {
4824  if(_memory && _memory->getStMem().find(getLastLocationId())!=_memory->getStMem().end())
4825  {
4826  std::multimap<int, Link> links = _memory->getLinks(getLastLocationId(), false);
4827  bool linksRemoved = false;
4828  for(std::multimap<int, Link>::iterator iter = links.begin(); iter!=links.end(); ++iter)
4829  {
4830  if(iter->second.type() == Link::kGlobalClosure ||
4831  iter->second.type() == Link::kLocalSpaceClosure ||
4832  iter->second.type() == Link::kLocalTimeClosure ||
4833  iter->second.type() == Link::kUserClosure)
4834  {
4835  _memory->removeLink(iter->second.from(), iter->second.to());
4836  std::multimap<int, Link>::iterator jter = graph::findLink(_constraints, iter->second.from(), iter->second.to(), true);
4837  if(jter!=_constraints.end())
4838  {
4839  _constraints.erase(jter);
4840  // second time if link is also inverted
4841  jter = graph::findLink(_constraints, iter->second.from(), iter->second.to(), true);
4842  if(jter!=_constraints.end())
4843  {
4844  _constraints.erase(jter);
4845  }
4846  }
4847  linksRemoved = true;
4848  }
4849  }
4850 
4851  if(linksRemoved)
4852  {
4853  _loopClosureHypothesis.first = 0;
4854 
4855  // we have to re-optimize the graph without the rejected links
4856  if(_memory->isIncremental() && _optimizedPoses.size())
4857  {
4858  UINFO("Update graph");
4859  std::map<int, Transform> poses = _optimizedPoses;
4860  std::multimap<int, Link> constraints;
4861  cv::Mat covariance;
4862  optimizeCurrentMap(getLastLocationId(), false, poses, covariance, &constraints);
4863 
4864  if(poses.empty())
4865  {
4866  UWARN("Graph optimization failed after removing loop closure links from last location!");
4867  }
4868  else
4869  {
4870  UINFO("Updated local map (old size=%d, new size=%d)", (int)_optimizedPoses.size(), (int)poses.size());
4871  _optimizedPoses = poses;
4872  _constraints = constraints;
4874  }
4875  }
4876  }
4877  }
4878 }
4879 
4881 {
4882  if(_memory && _memory->getStMem().size())
4883  {
4884  int lastId = *_memory->getStMem().rbegin();
4885  _memory->deleteLocation(lastId);
4886  // we have to re-optimize the graph without the deleted location
4887  if(_memory->isIncremental() && _optimizedPoses.size())
4888  {
4889  UINFO("Update graph");
4890  _optimizedPoses.erase(lastId);
4891  std::map<int, Transform> poses = _optimizedPoses;
4892  //remove all constraints with last localization id
4893  for(std::multimap<int, Link>::iterator iter=_constraints.begin(); iter!=_constraints.end();)
4894  {
4895  if(iter->second.from() == lastId || iter->second.to() == lastId)
4896  {
4897  _constraints.erase(iter++);
4898  }
4899  else
4900  {
4901  ++iter;
4902  }
4903  }
4904 
4905  if(poses.empty())
4906  {
4908  }
4909  else
4910  {
4911  std::multimap<int, Link> constraints;
4912  cv::Mat covariance;
4913  optimizeCurrentMap(_memory->getLastWorkingSignature()->id(), false, poses, covariance, &constraints);
4914 
4915  if(poses.empty())
4916  {
4917  UWARN("Graph optimization failed after deleting the last location!");
4918  }
4919  else
4920  {
4921  _optimizedPoses = poses;
4922  _constraints = constraints;
4924  }
4925  }
4926  }
4927  }
4928 }
4929 
4930 void Rtabmap::setOptimizedPoses(const std::map<int, Transform> & poses, const std::multimap<int, Link> & constraints)
4931 {
4932  _optimizedPoses = poses;
4933  _constraints = constraints;
4934 }
4935 
4936 void Rtabmap::dumpData() const
4937 {
4938  UDEBUG("");
4939  if(_memory)
4940  {
4941  if(this->getWorkingDir().empty())
4942  {
4943  UERROR("Working directory not set.");
4944  }
4945  else
4946  {
4947  _memory->dumpMemory(this->getWorkingDir());
4948  }
4949  }
4950 }
4951 
4952 // fromId must be in _memory and in _optimizedPoses
4953 // Get poses in front of the robot, return optimized poses
4954 std::map<int, Transform> Rtabmap::getForwardWMPoses(
4955  int fromId,
4956  int maxNearestNeighbors,
4957  float radius,
4958  int maxGraphDepth // 0 means ignore
4959  ) const
4960 {
4961  std::map<int, Transform> poses;
4962  if(_memory && fromId > 0)
4963  {
4964  UDEBUG("");
4965  const Signature * fromS = _memory->getSignature(fromId);
4966  UASSERT(fromS != 0);
4967  UASSERT(_optimizedPoses.find(fromId) != _optimizedPoses.end());
4968 
4969  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
4970  cloud->resize(_optimizedPoses.size());
4971  std::vector<int> ids(_optimizedPoses.size());
4972  int oi = 0;
4973  const std::set<int> & stm = _memory->getStMem();
4974  //get distances
4975  std::map<int, float> foundIds;
4976  if(_memory->isIncremental())
4977  {
4978  foundIds = _memory->getNeighborsIdRadius(fromId, radius, _optimizedPoses, maxGraphDepth);
4979  }
4980  else
4981  {
4982  foundIds = graph::findNearestNodes(fromId, _optimizedPoses, radius);
4983  }
4984 
4985  float radiusSqrd = radius * radius;
4986  for(std::map<int, Transform>::const_iterator iter = _optimizedPoses.begin(); iter!=_optimizedPoses.end(); ++iter)
4987  {
4988  if(iter->first != fromId)
4989  {
4990  if(stm.find(iter->first) == stm.end() &&
4991  uContains(foundIds, iter->first) &&
4992  (radiusSqrd==0 || foundIds.at(iter->first) <= radiusSqrd))
4993  {
4994  (*cloud)[oi] = pcl::PointXYZ(iter->second.x(), iter->second.y(), iter->second.z());
4995  ids[oi++] = iter->first;
4996  }
4997  }
4998  }
4999 
5000  cloud->resize(oi);
5001  ids.resize(oi);
5002 
5003  Transform fromT = _optimizedPoses.at(fromId);
5004 
5005  if(cloud->size())
5006  {
5007  //if(cloud->size())
5008  //{
5009  // pcl::io::savePCDFile("radiusPoses.pcd", *cloud);
5010  // UWARN("Saved radiusPoses.pcd");
5011  //}
5012 
5013  //filter poses in front of the fromId
5014  float x,y,z, roll,pitch,yaw;
5016 
5017  pcl::CropBox<pcl::PointXYZ> cropbox;
5018  cropbox.setInputCloud(cloud);
5019  cropbox.setMin(Eigen::Vector4f(-1, -radius, -999999, 0));
5020  cropbox.setMax(Eigen::Vector4f(radius, radius, 999999, 0));
5021  cropbox.setRotation(Eigen::Vector3f(roll, pitch, yaw));
5022  cropbox.setTranslation(Eigen::Vector3f(x, y, z));
5023  cropbox.setRotation(Eigen::Vector3f(roll,pitch,yaw));
5024  pcl::IndicesPtr indices(new std::vector<int>());
5025  cropbox.filter(*indices);
5026 
5027  //if(indices->size())
5028  //{
5029  // pcl::io::savePCDFile("radiusCrop.pcd", *cloud, *indices);
5030  // UWARN("Saved radiusCrop.pcd");
5031  //}
5032 
5033  if(indices->size())
5034  {
5035  pcl::search::KdTree<pcl::PointXYZ>::Ptr kdTree(new pcl::search::KdTree<pcl::PointXYZ>);
5036  kdTree->setInputCloud(cloud, indices);
5037  std::vector<int> ind;
5038  std::vector<float> dist;
5039  pcl::PointXYZ pt(fromT.x(), fromT.y(), fromT.z());
5040  kdTree->radiusSearch(pt, radius, ind, dist, maxNearestNeighbors);
5041  //pcl::PointCloud<pcl::PointXYZ> inliers;
5042  for(unsigned int i=0; i<ind.size(); ++i)
5043  {
5044  if(ind[i] >=0)
5045  {
5046  Transform tmp = _optimizedPoses.find(ids[ind[i]])->second;
5047  //inliers.push_back(pcl::PointXYZ(tmp.x(), tmp.y(), tmp.z()));
5048  UDEBUG("Inlier %d: %s", ids[ind[i]], tmp.prettyPrint().c_str());
5049  poses.insert(std::make_pair(ids[ind[i]], tmp));
5050  }
5051  }
5052 
5053  //if(inliers.size())
5054  //{
5055  // pcl::io::savePCDFile("radiusInliers.pcd", inliers);
5056  //}
5057  //if(nearestId >0)
5058  //{
5059  // pcl::PointCloud<pcl::PointXYZ> c;
5060  // Transform ct = _optimizedPoses.find(nearestId)->second;
5061  // c.push_back(pcl::PointXYZ(ct.x(), ct.y(), ct.z()));
5062  // pcl::io::savePCDFile("radiusNearestPt.pcd", c);
5063  //}
5064  }
5065  }
5066  }
5067  return poses;
5068 }
5069 
5070 std::map<int, std::map<int, Transform> > Rtabmap::getPaths(const std::map<int, Transform> & posesIn, const Transform & target, int maxGraphDepth) const
5071 {
5072  std::map<int, std::map<int, Transform> > paths;
5073  std::set<int> nodesSet;
5074  std::map<int, Transform> poses;
5075  for(std::map<int, Transform>::const_iterator iter=posesIn.lower_bound(1); iter!=posesIn.end(); ++iter)
5076  {
5077  nodesSet.insert(iter->first);
5078  poses.insert(*iter);
5079  }
5080  if(_memory && nodesSet.size() && !target.isNull())
5081  {
5082  double e0=0,e1=0,e2=0,e3=0,e4=0;
5083  UTimer t;
5084  e0 = t.ticks();
5085  // Segment poses connected only by neighbor links
5086  while(poses.size())
5087  {
5088  std::map<int, Transform> path;
5089  // select nearest pose and iterate neighbors from there
5090  int nearestId = rtabmap::graph::findNearestNode(poses, target);
5091 
5092  e1+=t.ticks();
5093 
5094  if(nearestId == 0)
5095  {
5096  UWARN("Nearest id of %s in %d poses is 0 !? Returning empty path.", target.prettyPrint().c_str(), (int)poses.size());
5097  break;
5098  }
5099  std::map<int, int> ids = _memory->getNeighborsId(nearestId, maxGraphDepth, 0, true, true, true, true, nodesSet);
5100 
5101  e2+=t.ticks();
5102 
5103  for(std::map<int, int>::iterator iter=ids.begin(); iter!=ids.end(); ++iter)
5104  {
5105  std::map<int, Transform>::iterator jter = poses.find(iter->first);
5106  if(jter != poses.end())
5107  {
5108  bool valid = path.empty();
5109  if(!valid)
5110  {
5111  // make sure it has a neighbor added to path
5112  std::multimap<int, Link> links = _memory->getNeighborLinks(iter->first);
5113  for(std::multimap<int, Link>::iterator kter=links.begin(); kter!=links.end() && !valid; ++kter)
5114  {
5115  valid = path.find(kter->first) != path.end();
5116  }
5117  }
5118 
5119  if(valid)
5120  {
5121  //UDEBUG("%d <- %d", nearestId, jter->first);
5122  path.insert(*jter);
5123  poses.erase(jter);
5124  }
5125  }
5126  }
5127 
5128  e3+=t.ticks();
5129 
5130  if (path.size())
5131  {
5132  if (maxGraphDepth > 0 && !_memory->isGraphReduced() && (int)path.size() > maxGraphDepth * 2 + 1)
5133  {
5134  UWARN("%s=Off but path(%d) > maxGraphDepth(%d)*2+1, nearestId=%d ids=%d. Is reduce graph activated before?",
5135  Parameters::kMemReduceGraph().c_str(), (int)path.size(), maxGraphDepth, nearestId, (int)ids.size());
5136  }
5137  paths.insert(std::make_pair(nearestId, path));
5138  }
5139  else
5140  {
5141  UWARN("path.size()=0!? nearestId=%d ids=%d, aborting...", nearestId, (int)ids.size());
5142  break;
5143  }
5144 
5145  e4+=t.ticks();
5146  }
5147  UDEBUG("e0=%fs e1=%fs e2=%fs e3=%fs e4=%fs", e0, e1, e2, e3, e4);
5148  }
5149  return paths;
5150 }
5151 
5153  int id,
5154  bool lookInDatabase,
5155  std::map<int, Transform> & optimizedPoses,
5156  cv::Mat & covariance,
5157  std::multimap<int, Link> * constraints,
5158  double * error,
5159  int * iterationsDone) const
5160 {
5161  //Optimize the map
5162  UINFO("Optimize map: around location %d (lookInDatabase=%s)", id, lookInDatabase?"true":"false");
5163  if(_memory && id > 0)
5164  {
5165  UTimer timer;
5166  std::map<int, int> ids = _memory->getNeighborsId(id, 0, lookInDatabase?-1:0, true, false);
5167  if(!_optimizeFromGraphEnd && ids.size() > 1)
5168  {
5169  id = ids.begin()->first;
5170  }
5171  UINFO("get %d ids time %f s", (int)ids.size(), timer.ticks());
5172 
5173  std::map<int, Transform> poses = Rtabmap::optimizeGraph(id, uKeysSet(ids), optimizedPoses, lookInDatabase, covariance, constraints, error, iterationsDone);
5174  UINFO("optimize time %f s", timer.ticks());
5175 
5176  if(poses.size())
5177  {
5178  optimizedPoses = poses;
5179 
5180  if(_memory->getSignature(id) && uContains(optimizedPoses, id))
5181  {
5182  Transform t = optimizedPoses.at(id) * _memory->getSignature(id)->getPose().inverse();
5183  UINFO("Correction (from node %d) %s", id, t.prettyPrint().c_str());
5184  }
5185  }
5186  else
5187  {
5188  UWARN("Failed to optimize the graph! returning empty optimized poses...");
5189  optimizedPoses.clear();
5190  if(constraints)
5191  {
5192  constraints->clear();
5193  }
5194  }
5195  }
5196 }
5197 
5198 std::map<int, Transform> Rtabmap::optimizeGraph(
5199  int fromId,
5200  const std::set<int> & ids,
5201  const std::map<int, Transform> & guessPoses,
5202  bool lookInDatabase,
5203  cv::Mat & covariance,
5204  std::multimap<int, Link> * constraints,
5205  double * error,
5206  int * iterationsDone) const
5207 {
5208  UTimer timer;
5209  std::map<int, Transform> optimizedPoses;
5210  std::map<int, Transform> poses;
5211  std::multimap<int, Link> edgeConstraints;
5212  UDEBUG("ids=%d", (int)ids.size());
5213  _memory->getMetricConstraints(ids, poses, edgeConstraints, lookInDatabase, !_graphOptimizer->landmarksIgnored());
5214  UINFO("get constraints (ids=%d, %d poses, %d edges) time %f s", (int)ids.size(), (int)poses.size(), (int)edgeConstraints.size(), timer.ticks());
5215 
5216  // add landmark priors if there are some
5217  for(std::map<int, Transform>::iterator iter=poses.begin(); iter!=poses.end() && iter->first < 0; ++iter)
5218  {
5219  if(_markerPriors.find(iter->first) != _markerPriors.end())
5220  {
5221  cv::Mat infMatrix = cv::Mat::eye(6, 6, CV_64FC1);
5222  infMatrix(cv::Range(0,3), cv::Range(0,3)) /= _markerPriorsLinearVariance;
5223  infMatrix(cv::Range(3,6), cv::Range(3,6)) /= _markerPriorsAngularVariance;
5224  edgeConstraints.insert(std::make_pair(iter->first, Link(iter->first, iter->first, Link::kPosePrior, _markerPriors.at(iter->first), infMatrix)));
5225  UDEBUG("Added prior %d : %s (variance: lin=%f ang=%f)", iter->first, _markerPriors.at(iter->first).prettyPrint().c_str(),
5227  }
5228  }
5229 
5230  if(_graphOptimizer->iterations() > 0)
5231  {
5232  for(std::map<int, Transform>::iterator iter=poses.begin(); iter!=poses.end(); ++iter)
5233  {
5234  // Apply guess poses (if some), ignore for rootid to avoid origin drifting
5235  std::map<int, Transform>::const_iterator foundGuess = guessPoses.find(iter->first);
5236  if(foundGuess!=guessPoses.end() && iter->first != fromId)
5237  {
5238  iter->second = foundGuess->second;
5239  }
5240  }
5241  }
5242 
5243 
5245  if(_graphOptimizer->iterations() == 0)
5246  {
5247  // Optimization disabled! Return not optimized poses.
5248  optimizedPoses = poses;
5249  if(constraints)
5250  {
5251  *constraints = edgeConstraints;
5252  }
5253  }
5254  else
5255  {
5256  bool hasLandmarks = !edgeConstraints.empty() && edgeConstraints.begin()->first < 0;
5257  if(poses.size() != guessPoses.size() || hasLandmarks)
5258  {
5259  UDEBUG("recompute poses using only links (robust to multi-session)");
5260  std::map<int, Transform> posesOut;
5261  std::multimap<int, Link> edgeConstraintsOut;
5262  _graphOptimizer->getConnectedGraph(fromId, poses, edgeConstraints, posesOut, edgeConstraintsOut);
5263  optimizedPoses = _graphOptimizer->optimize(fromId, posesOut, edgeConstraintsOut, covariance, 0, error, iterationsDone);
5264  if(constraints)
5265  {
5266  *constraints = edgeConstraintsOut;
5267  }
5268  }
5269  else
5270  {
5271  UDEBUG("use input guess poses");
5272  optimizedPoses = _graphOptimizer->optimize(fromId, poses, edgeConstraints, covariance, 0, error, iterationsDone);
5273  if(constraints)
5274  {
5275  *constraints = edgeConstraints;
5276  }
5277  }
5278 
5279  if(!poses.empty() && optimizedPoses.empty())
5280  {
5281  UWARN("Optimization has failed (poses=%d, guess=%d, links=%d)...",
5282  (int)poses.size(), (int)guessPoses.size(), (int)edgeConstraints.size());
5283  }
5284  }
5285 
5286  UINFO("Optimization time %f s", timer.ticks());
5287 
5288  return optimizedPoses;
5289 }
5290 
5291 void Rtabmap::adjustLikelihood(std::map<int, float> & likelihood) const
5292 {
5293  ULOGGER_DEBUG("likelihood.size()=%d", likelihood.size());
5294  UTimer timer;
5295  timer.start();
5296  if(likelihood.size()==0)
5297  {
5298  return;
5299  }
5300 
5301  // Use only non-null values (ignore virtual place)
5302  std::list<float> values;
5303  bool likelihoodNullValuesIgnored = true;
5304  for(std::map<int, float>::iterator iter = ++likelihood.begin(); iter!=likelihood.end(); ++iter)
5305  {
5306  if((iter->second >= 0 && !likelihoodNullValuesIgnored) ||
5307  (iter->second > 0 && likelihoodNullValuesIgnored))
5308  {
5309  values.push_back(iter->second);
5310  }
5311  }
5312  UDEBUG("values.size=%d", values.size());
5313 
5314  float mean = uMean(values);
5315  float stdDev = std::sqrt(uVariance(values, mean));
5316 
5317 
5318  //Adjust likelihood with mean and standard deviation (see Angeli phd)
5319  float epsilon = 0.0001;
5320  float max = 0.0f;
5321  int maxId = 0;
5322  for(std::map<int, float>::iterator iter=++likelihood.begin(); iter!= likelihood.end(); ++iter)
5323  {
5324  float value = iter->second;
5325  iter->second = 1.0f;
5326  if(value > mean+stdDev)
5327  {
5329  {
5330  iter->second = (value-(stdDev-epsilon))/mean;
5331  }
5332  else if(_virtualPlaceLikelihoodRatio!=0 && stdDev)
5333  {
5334  iter->second = (value-mean)/stdDev;
5335  }
5336  }
5337 
5338  if(value > max)
5339  {
5340  max = value;
5341  maxId = iter->first;
5342  }
5343  }
5344 
5345  if(_virtualPlaceLikelihoodRatio==0 && stdDev > epsilon && max)
5346  {
5347  likelihood.begin()->second = mean/stdDev + 1.0f;
5348  }
5349  else if(_virtualPlaceLikelihoodRatio!=0 && max > mean)
5350  {
5351  likelihood.begin()->second = stdDev/(max-mean) + 1.0f;
5352  }
5353  else
5354  {
5355  likelihood.begin()->second = 2.0f; //2 * std dev
5356  }
5357 
5358  double time = timer.ticks();
5359  UDEBUG("mean=%f, stdDev=%f, max=%f, maxId=%d, time=%fs", mean, stdDev, max, maxId, time);
5360 }
5361 
5363 {
5364  if(_memory && _bayesFilter)
5365  {
5366  if(this->getWorkingDir().empty())
5367  {
5368  UERROR("Working directory not set.");
5369  return;
5370  }
5371  std::list<int> signaturesToCompare;
5372  for(std::map<int, double>::const_iterator iter=_memory->getWorkingMem().begin();
5373  iter!=_memory->getWorkingMem().end();
5374  ++iter)
5375  {
5376  if(iter->first > 0)
5377  {
5378  const Signature * s = _memory->getSignature(iter->first);
5379  UASSERT(s!=0);
5380  if(s->getWeight() != -1) // ignore intermediate nodes
5381  {
5382  signaturesToCompare.push_back(iter->first);
5383  }
5384  }
5385  else
5386  {
5387  // virtual signature should be added
5388  signaturesToCompare.push_back(iter->first);
5389  }
5390  }
5391  cv::Mat prediction = _bayesFilter->generatePrediction(_memory, uListToVector(signaturesToCompare));
5392 
5393  FILE* fout = 0;
5394  std::string fileName = this->getWorkingDir() + "/DumpPrediction.txt";
5395  #ifdef _MSC_VER
5396  fopen_s(&fout, fileName.c_str(), "w");
5397  #else
5398  fout = fopen(fileName.c_str(), "w");
5399  #endif
5400 
5401  if(fout)
5402  {
5403  for(int i=0; i<prediction.rows; ++i)
5404  {
5405  for(int j=0; j<prediction.cols; ++j)
5406  {
5407  fprintf(fout, "%f ",((float*)prediction.data)[j + i*prediction.cols]);
5408  }
5409  fprintf(fout, "\n");
5410  }
5411  fclose(fout);
5412  }
5413  }
5414  else
5415  {
5416  UWARN("Memory and/or the Bayes filter are not created");
5417  }
5418 }
5419 
5420 Signature Rtabmap::getSignatureCopy(int id, bool images, bool scan, bool userData, bool occupancyGrid, bool withWords, bool withGlobalDescriptors) const
5421 {
5422  Signature s;
5423  if(_memory)
5424  {
5425  Transform odomPoseLocal;
5426  int weight = -1;
5427  int mapId = -1;
5428  std::string label;
5429  double stamp = 0;
5430  Transform groundTruth;
5431  std::vector<float> velocity;
5432  GPS gps;
5433  EnvSensors sensors;
5434  _memory->getNodeInfo(id, odomPoseLocal, mapId, weight, label, stamp, groundTruth, velocity, gps, sensors, true);
5435  SensorData data;
5436  data.setId(id);
5437  if(images || scan || userData || occupancyGrid)
5438  {
5439  data = _memory->getNodeData(id, images, scan, userData, occupancyGrid);
5440  }
5441  if(!images && withWords)
5442  {
5443  std::vector<CameraModel> models;
5444  std::vector<StereoCameraModel> stereoModels;
5445  _memory->getNodeCalibration(id, models, stereoModels);
5446  data.setCameraModels(models);
5447  data.setStereoCameraModels(stereoModels);
5448  }
5449 
5450  s=Signature(id,
5451  mapId,
5452  weight,
5453  stamp,
5454  label,
5455  odomPoseLocal,
5456  groundTruth,
5457  data);
5458 
5459  std::multimap<int, Link> links = _memory->getLinks(id, true, true);
5460  for(std::multimap<int, Link>::iterator iter=links.begin(); iter!=links.end(); ++iter)
5461  {
5462  if(iter->second.type() == Link::kLandmark)
5463  {
5464  s.addLandmark(iter->second);
5465  }
5466  else
5467  {
5468  s.addLink(iter->second);
5469  }
5470  }
5471 
5472  if(withWords || withGlobalDescriptors)
5473  {
5474  std::multimap<int, int> words;
5475  std::vector<cv::KeyPoint> wordsKpts;
5476  std::vector<cv::Point3f> words3;
5477  cv::Mat wordsDescriptors;
5478  std::vector<rtabmap::GlobalDescriptor> globalDescriptors;
5479  _memory->getNodeWordsAndGlobalDescriptors(id, words, wordsKpts, words3, wordsDescriptors, globalDescriptors);
5480  if(withWords)
5481  {
5482  s.setWords(words, wordsKpts, words3, wordsDescriptors);
5483  }
5484  if(withGlobalDescriptors)
5485  {
5486  s.sensorData().setGlobalDescriptors(globalDescriptors);
5487  }
5488  }
5489  if(velocity.size()==6)
5490  {
5491  s.setVelocity(velocity[0], velocity[1], velocity[2], velocity[3], velocity[4], velocity[5]);
5492  }
5493  s.sensorData().setGPS(gps);
5494  s.sensorData().setEnvSensors(sensors);
5495  }
5496  return s;
5497 }
5498 
5500  std::map<int, Signature> & signatures,
5501  std::map<int, Transform> & poses,
5502  std::multimap<int, Link> & constraints,
5503  bool optimized,
5504  bool global) const
5505 {
5506  UDEBUG("");
5507  return getGraph(poses, constraints, optimized, global, &signatures, true, true, true, true);
5508 }
5509 
5511  std::map<int, Transform> & poses,
5512  std::multimap<int, Link> & constraints,
5513  bool optimized,
5514  bool global,
5515  std::map<int, Signature> * signatures,
5516  bool withImages,
5517  bool withScan,
5518  bool withUserData,
5519  bool withGrid,
5520  bool withWords,
5521  bool withGlobalDescriptors) const
5522 {
5524  {
5525  if(_rgbdSlamMode)
5526  {
5527  if(optimized)
5528  {
5529  poses = _optimizedPoses; // guess
5530  cv::Mat covariance;
5531  this->optimizeCurrentMap(_memory->getLastWorkingSignature()->id(), global, poses, covariance, &constraints);
5532  if(!global && !_optimizedPoses.empty())
5533  {
5534  // We send directly the already optimized poses if they are set
5535  UDEBUG("_optimizedPoses=%ld poses=%ld", _optimizedPoses.size(), poses.size());
5536  poses = _optimizedPoses;
5537  }
5538  }
5539  else
5540  {
5541  std::map<int, int> ids = _memory->getNeighborsId(_memory->getLastWorkingSignature()->id(), 0, global?-1:0, true);
5542  _memory->getMetricConstraints(uKeysSet(ids), poses, constraints, global);
5543  }
5544  }
5545  else
5546  {
5547  // no optimization on appearance-only mode
5548  std::map<int, int> ids = _memory->getNeighborsId(_memory->getLastWorkingSignature()->id(), 0, global?-1:0, true);
5549  _memory->getMetricConstraints(uKeysSet(ids), poses, constraints, global);
5550  }
5551 
5552  if(signatures)
5553  {
5554  // Get data
5555  std::set<int> ids = uKeysSet(_memory->getWorkingMem()); // WM
5556 
5557  //remove virtual signature
5558  ids.erase(Memory::kIdVirtual);
5559 
5560  ids.insert(_memory->getStMem().begin(), _memory->getStMem().end()); // STM + WM
5561  if(global)
5562  {
5563  ids = _memory->getAllSignatureIds(); // STM + WM + LTM, ignoreChildren=true
5564  }
5565 
5566  for(std::set<int>::iterator iter = ids.begin(); iter!=ids.end(); ++iter)
5567  {
5568  signatures->insert(std::make_pair(*iter, getSignatureCopy(*iter, withImages, withScan, withUserData, withGrid, withWords, withGlobalDescriptors)));
5569  }
5570  }
5571  }
5572  else if(_memory && (_memory->getStMem().size() || _memory->getWorkingMem().size() > 1))
5573  {
5574  UERROR("Last working signature is null!?");
5575  }
5576  else if(_memory == 0)
5577  {
5578  UWARN("Memory not initialized...");
5579  }
5580 }
5581 
5582 std::map<int, Transform> Rtabmap::getNodesInRadius(const Transform & pose, float radius, int k, std::map<int, float> * distsSqr)
5583 {
5584  std::map<int, float> nearestNodesTmp;
5585  std::map<int, float> * nearestNodesPtr = distsSqr == 0? &nearestNodesTmp : distsSqr;
5586  *nearestNodesPtr = graph::findNearestNodes(pose, _optimizedPoses, radius<=0?_localRadius:radius, 0, k);
5587  std::map<int, Transform> nearestPoses;
5588  for(std::map<int, float>::iterator iter=nearestNodesPtr->begin(); iter!=nearestNodesPtr->end(); ++iter)
5589  {
5590  nearestPoses.insert(*_optimizedPoses.find(iter->first));
5591  }
5592  return nearestPoses;
5593 }
5594 
5595 std::map<int, Transform> Rtabmap::getNodesInRadius(int nodeId, float radius, int k, std::map<int, float> * distsSqr)
5596 {
5597  UDEBUG("nodeId=%d, radius=%f", nodeId, radius);
5598  std::map<int, float> nearestNodesTmp;
5599  std::map<int, float> * nearestNodesPtr = distsSqr == 0? &nearestNodesTmp : distsSqr;
5601  {
5602  *nearestNodesPtr = graph::findNearestNodes(_lastLocalizationPose, _optimizedPoses, radius<=0?_localRadius:radius, 0, k);
5603  }
5604  else
5605  {
5606  if(nodeId==0 && !_optimizedPoses.empty())
5607  {
5608  nodeId = _optimizedPoses.rbegin()->first;
5609  }
5610 
5611  if(_optimizedPoses.find(nodeId) != _optimizedPoses.end())
5612  {
5613  *nearestNodesPtr = graph::findNearestNodes(nodeId, _optimizedPoses, radius<=0?_localRadius:radius, 0, k);
5614  }
5615  }
5616 
5617  std::map<int, Transform> nearestPoses;
5618  for(std::map<int, float>::iterator iter=nearestNodesPtr->begin(); iter!=nearestNodesPtr->end(); ++iter)
5619  {
5620  nearestPoses.insert(*_optimizedPoses.find(iter->first));
5621  }
5622 
5623  return nearestPoses;
5624 }
5625 
5627  float clusterRadiusMax,
5628  float clusterAngle,
5629  int iterations,
5630  bool intraSession,
5631  bool interSession,
5632  const ProgressState * processState,
5633  float clusterRadiusMin)
5634 {
5635  UASSERT(iterations>0);
5636 
5637  if(_graphOptimizer->iterations() <= 0)
5638  {
5639  UERROR("Cannot detect more loop closures if graph optimization iterations = 0");
5640  return -1;
5641  }
5642  if(!_rgbdSlamMode)
5643  {
5644  UERROR("Detecting more loop closures can be done only in RGBD-SLAM mode.");
5645  return -1;
5646  }
5647  if(!intraSession && !interSession)
5648  {
5649  UERROR("Intra and/or inter session argument should be true.");
5650  return -1;
5651  }
5652 
5653  std::list<Link> loopClosuresAdded;
5654  std::multimap<int, int> checkedLoopClosures;
5655 
5656  std::map<int, Transform> posesToCheckLoopClosures;
5657  std::map<int, Transform> poses;
5658  std::multimap<int, Link> links;
5659  std::map<int, Signature> signatures; // some signatures may be in LTM, get them all
5660  this->getGraph(poses, links, true, true, &signatures);
5661 
5662  std::map<int, int> mapIds;
5663  UDEBUG("remove all invalid or intermediate nodes, fill mapIds");
5664  for(std::map<int, Transform>::iterator iter=poses.upper_bound(0); iter!=poses.end();++iter)
5665  {
5666  if(signatures.at(iter->first).getWeight() >= 0)
5667  {
5668  posesToCheckLoopClosures.insert(*iter);
5669  mapIds.insert(std::make_pair(iter->first, signatures.at(iter->first).mapId()));
5670  }
5671  }
5672 
5673  for(int n=0; n<iterations; ++n)
5674  {
5675  UINFO("Looking for more loop closures, clustering poses... (iteration=%d/%d, radius=%f m angle=%f rad)",
5676  n+1, iterations, clusterRadiusMax, clusterAngle);
5677 
5678  std::multimap<int, int> clusters = graph::radiusPosesClustering(
5679  posesToCheckLoopClosures,
5680  clusterRadiusMax,
5681  clusterAngle);
5682 
5683  UINFO("Looking for more loop closures, clustering poses... found %d clusters.", (int)clusters.size());
5684 
5685  int i=0;
5686  std::set<int> addedLinks;
5687  for(std::multimap<int, int>::iterator iter=clusters.begin(); iter!= clusters.end(); ++iter, ++i)
5688  {
5689  if(processState && processState->isCanceled())
5690  {
5691  return -1;
5692  break;
5693  }
5694 
5695  int from = iter->first;
5696  int to = iter->second;
5697  if(from > to)
5698  {
5699  from = iter->second;
5700  to = iter->first;
5701  }
5702 
5703  int mapIdFrom = uValue(mapIds, from, 0);
5704  int mapIdTo = uValue(mapIds, to, 0);
5705 
5706  if((interSession && mapIdFrom != mapIdTo) ||
5707  (intraSession && mapIdFrom == mapIdTo))
5708  {
5709 
5710  bool alreadyChecked = false;
5711  for(std::multimap<int, int>::iterator jter = checkedLoopClosures.lower_bound(from);
5712  !alreadyChecked && jter!=checkedLoopClosures.end() && jter->first == from;
5713  ++jter)
5714  {
5715  if(to == jter->second)
5716  {
5717  alreadyChecked = true;
5718  }
5719  }
5720 
5721  if(!alreadyChecked)
5722  {
5723  // only add new links and one per cluster per iteration
5724  if(addedLinks.find(from) == addedLinks.end() &&
5725  addedLinks.find(to) == addedLinks.end() &&
5726  rtabmap::graph::findLink(links, from, to) == links.end())
5727  {
5728  // Reverify if in the bounds with the current optimized graph
5729  Transform delta = poses.at(from).inverse() * poses.at(to);
5730  if(delta.getNorm() < clusterRadiusMax &&
5731  delta.getNorm() >= clusterRadiusMin)
5732  {
5733  checkedLoopClosures.insert(std::make_pair(from, to));
5734 
5735  UASSERT(signatures.find(from) != signatures.end());
5736  UASSERT(signatures.find(to) != signatures.end());
5737 
5738  Transform guess;
5739  if(_proximityBySpace && uContains(poses, from) && uContains(poses, to))
5740  {
5741  guess = poses.at(from).inverse() * poses.at(to);
5742  }
5743 
5745  // use signatures instead of IDs because some signatures may not be in WM
5746  Transform t = _memory->computeTransform(signatures.at(from), signatures.at(to), guess, &info);
5747 
5748  if(!t.isNull())
5749  {
5750  bool updateConstraints = true;
5751 
5752  //optimize the graph to see if the new constraint is globally valid
5753 
5754  int fromId = from;
5755  int mapId = signatures.at(from).mapId();
5756  // use first node of the map containing from
5757  for(std::map<int, Signature>::iterator ster=signatures.begin(); ster!=signatures.end(); ++ster)
5758  {
5759  if(ster->second.mapId() == mapId)
5760  {
5761  fromId = ster->first;
5762  break;
5763  }
5764  }
5765  std::multimap<int, Link> linksIn = links;
5766  linksIn.insert(std::make_pair(from, Link(from, to, Link::kUserClosure, t, getInformation(info.covariance))));
5767  const Link * maxLinearLink = 0;
5768  const Link * maxAngularLink = 0;
5769  float maxLinearError = 0.0f;
5770  float maxAngularError = 0.0f;
5771  float maxLinearErrorRatio = 0.0f;
5772  float maxAngularErrorRatio = 0.0f;
5773  std::map<int, Transform> optimizedPoses;
5774  std::multimap<int, Link> links;
5775  UASSERT(poses.find(fromId) != poses.end());
5776  UASSERT_MSG(poses.find(from) != poses.end(), uFormat("id=%d poses=%d links=%d", from, (int)poses.size(), (int)links.size()).c_str());
5777  UASSERT_MSG(poses.find(to) != poses.end(), uFormat("id=%d poses=%d links=%d", to, (int)poses.size(), (int)links.size()).c_str());
5778  _graphOptimizer->getConnectedGraph(fromId, poses, linksIn, optimizedPoses, links);
5779  UASSERT(optimizedPoses.find(fromId) != optimizedPoses.end());
5780  UASSERT_MSG(optimizedPoses.find(from) != optimizedPoses.end(), uFormat("id=%d poses=%d links=%d", from, (int)optimizedPoses.size(), (int)links.size()).c_str());
5781  UASSERT_MSG(optimizedPoses.find(to) != optimizedPoses.end(), uFormat("id=%d poses=%d links=%d", to, (int)optimizedPoses.size(), (int)links.size()).c_str());
5782  UASSERT(graph::findLink(links, from, to) != links.end());
5783  optimizedPoses = _graphOptimizer->optimize(fromId, optimizedPoses, links);
5784  std::string msg;
5785  if(optimizedPoses.size())
5786  {
5788  optimizedPoses,
5789  links,
5790  maxLinearErrorRatio,
5791  maxAngularErrorRatio,
5792  maxLinearError,
5793  maxAngularError,
5794  &maxLinearLink,
5795  &maxAngularLink);
5796  if(maxLinearLink)
5797  {
5798  UINFO("Max optimization linear error = %f m (link %d->%d)", maxLinearError, maxLinearLink->from(), maxLinearLink->to());
5799  if(_optimizationMaxError > 0.0f && maxLinearErrorRatio > _optimizationMaxError)
5800  {
5801  msg = uFormat("Rejecting edge %d->%d because "
5802  "graph error is too large after optimization (%f m for edge %d->%d with ratio %f > std=%f m). "
5803  "\"%s\" is %f.",
5804  from,
5805  to,
5806  maxLinearError,
5807  maxLinearLink->from(),
5808  maxLinearLink->to(),
5809  maxLinearErrorRatio,
5810  sqrt(maxLinearLink->transVariance()),
5811  Parameters::kRGBDOptimizeMaxError().c_str(),
5813  }
5814  else if(_optimizationMaxError == 0.0f && maxLinearErrorRatio>100 && !_graphOptimizer->isRobust())
5815  {
5816  UERROR("Huge optimization error detected!"
5817  "Linear error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). You may consider "
5818  "enabling \"%s\" to reject those bad optimizations by setting it to a non null value!",
5819  maxLinearErrorRatio,
5820  maxLinearLink->from(),
5821  maxLinearLink->to(),
5822  maxLinearLink->type(),
5823  maxLinearError,
5824  sqrt(maxLinearLink->transVariance()),
5825  Parameters::kRGBDOptimizeMaxError().c_str());
5826  }
5827  }
5828  else if(maxAngularLink)
5829  {
5830  UINFO("Max optimization angular error = %f deg (link %d->%d)", maxAngularError*180.0f/M_PI, maxAngularLink->from(), maxAngularLink->to());
5831  if(_optimizationMaxError > 0.0f && maxAngularErrorRatio > _optimizationMaxError)
5832  {
5833  msg = uFormat("Rejecting edge %d->%d because "
5834  "graph error is too large after optimization (%f deg for edge %d->%d with ratio %f > std=%f deg). "
5835  "\"%s\" is %f m.",
5836  from,
5837  to,
5838  maxAngularError*180.0f/M_PI,
5839  maxAngularLink->from(),
5840  maxAngularLink->to(),
5841  maxAngularErrorRatio,
5842  sqrt(maxAngularLink->rotVariance()),
5843  Parameters::kRGBDOptimizeMaxError().c_str(),
5845  }
5846  else if(_optimizationMaxError == 0.0f && maxAngularErrorRatio>100 && !_graphOptimizer->isRobust())
5847  {
5848  UERROR("Huge optimization error detected!"
5849  "Angular error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). You may consider "
5850  "enabling \"%s\" to reject those bad optimizations by setting it to a non null value!",
5851  maxAngularErrorRatio,
5852  maxAngularLink->from(),
5853  maxAngularLink->to(),
5854  maxAngularLink->type(),
5855  maxAngularError*180.0f/CV_PI,
5856  sqrt(maxAngularLink->rotVariance()),
5857  Parameters::kRGBDOptimizeMaxError().c_str());
5858  }
5859  }
5860  }
5861  else
5862  {
5863  msg = uFormat("Rejecting edge %d->%d because graph optimization has failed!",
5864  from,
5865  to);
5866  }
5867  if(!msg.empty())
5868  {
5869  UWARN("%s", msg.c_str());
5870  updateConstraints = false;
5871  }
5872  else
5873  {
5874  poses = optimizedPoses;
5875  }
5876 
5877  if(updateConstraints)
5878  {
5879  addedLinks.insert(from);
5880  addedLinks.insert(to);
5881  cv::Mat inf = getInformation(info.covariance);
5882  links.insert(std::make_pair(from, Link(from, to, Link::kUserClosure, t, inf)));
5883  loopClosuresAdded.push_back(Link(from, to, Link::kUserClosure, t, inf));
5884  std::string msg = uFormat("Iteration %d/%d: Added loop closure %d->%d! (%d/%d)", n+1, iterations, from, to, i+1, (int)clusters.size());
5885  UINFO(msg.c_str());
5886 
5887  if(processState)
5888  {
5889  UINFO(msg.c_str());
5890  if(!processState->callback(msg))
5891  {
5892  return -1;
5893  }
5894  }
5895  }
5896  }
5897  }
5898  }
5899  }
5900  }
5901  }
5902 
5903  if(processState)
5904  {
5905  std::string msg = uFormat("Iteration %d/%d: Detected %d total loop closures!", n+1, iterations, (int)addedLinks.size()/2);
5906  UINFO(msg.c_str());
5907  if(!processState->callback(msg))
5908  {
5909  return -1;
5910  }
5911  }
5912  else
5913  {
5914  UINFO("Iteration %d/%d: Detected %d total loop closures!", n+1, iterations, (int)addedLinks.size()/2);
5915  }
5916 
5917  if(addedLinks.size() == 0)
5918  {
5919  break;
5920  }
5921 
5922  UINFO("Optimizing graph with new links (%d nodes, %d constraints)...",
5923  (int)poses.size(), (int)links.size());
5924  int fromId = _optimizeFromGraphEnd?poses.rbegin()->first:poses.begin()->first;
5925  poses = _graphOptimizer->optimize(fromId, poses, links, 0);
5926  if(poses.size() == 0)
5927  {
5928  UERROR("Optimization failed! Rejecting all loop closures...");
5929  loopClosuresAdded.clear();
5930  return -1;
5931  }
5932  UINFO("Optimizing graph with new links... done!");
5933  }
5934  UINFO("Total added %d loop closures.", (int)loopClosuresAdded.size());
5935 
5936  if(loopClosuresAdded.size())
5937  {
5938  for(std::list<Link>::iterator iter=loopClosuresAdded.begin(); iter!=loopClosuresAdded.end(); ++iter)
5939  {
5940  _memory->addLink(*iter, true);
5941  }
5942  // Update optimized poses
5943  for(std::map<int, Transform>::iterator iter=_optimizedPoses.begin(); iter!=_optimizedPoses.end(); ++iter)
5944  {
5945  std::map<int, Transform>::iterator jter = poses.find(iter->first);
5946  if(jter != poses.end())
5947  {
5948  iter->second = jter->second;
5949  }
5950  }
5951  std::map<int, Transform> tmp;
5952  // Update also the links if some have been added in WM
5954  // This will force rtabmap_ros to regenerate the global occupancy grid if there was one
5955  _memory->save2DMap(cv::Mat(), 0, 0, 0);
5956  }
5957  return (int)loopClosuresAdded.size();
5958 }
5959 
5961  int optimizerType,
5962  bool rematchFeatures,
5963  int iterations,
5964  float pixelVariance)
5965 {
5966  if(!_optimizedPoses.empty() && !_constraints.empty())
5967  {
5968  int iterations = Parameters::defaultOptimizerIterations();
5969  float pixelVariance = Parameters::defaultg2oPixelVariance();
5971  Parameters::parse(params, Parameters::kOptimizerIterations(), iterations);
5972  Parameters::parse(params, Parameters::kg2oPixelVariance(), pixelVariance);
5973  if(iterations > 0)
5974  {
5975  uInsert(params, ParametersPair(Parameters::kOptimizerIterations(), uNumber2Str(iterations)));
5976  }
5977  if(pixelVariance > 0.0f)
5978  {
5979  uInsert(params, ParametersPair(Parameters::kg2oPixelVariance(), uNumber2Str(pixelVariance)));
5980  }
5981 
5982  std::map<int, Signature> signatures;
5983  for(std::map<int, Transform>::iterator iter=_optimizedPoses.lower_bound(1); iter!=_optimizedPoses.end(); ++iter)
5984  {
5985  if(_memory->getSignature(iter->first))
5986  {
5987  signatures.insert(std::make_pair(iter->first, *_memory->getSignature(iter->first)));
5988  }
5989  }
5990 
5991  Optimizer * optimizer = Optimizer::create((Optimizer::Type)optimizerType, params);
5992  std::map<int, Transform> poses = optimizer->optimizeBA(
5993  _optimizeFromGraphEnd?_optimizedPoses.lower_bound(1)->first:_optimizedPoses.rbegin()->first,
5995  _constraints,
5996  signatures,
5997  rematchFeatures);
5998  delete optimizer;
5999 
6000  if(poses.empty())
6001  {
6002  UERROR("Optimization failed!");
6003  }
6004  else
6005  {
6006  _optimizedPoses = poses;
6007  // This will force rtabmap_ros to regenerate the global occupancy grid if there was one
6008  _memory->save2DMap(cv::Mat(), 0, 0, 0);
6009  return true;
6010  }
6011  }
6012  else
6013  {
6014  UERROR("Optimized poses (%ld) or constraints (%ld) are empty!", _optimizedPoses.size(), _constraints.size());
6015  }
6016  return false;
6017 }
6018 
6020  const std::map<int, Transform> & poses,
6021  const cv::Mat & map,
6022  float xMin,
6023  float yMin,
6024  float cellSize,
6025  int cropRadius,
6026  bool filterScans)
6027 {
6028  if(_memory)
6029  {
6030  return _memory->cleanupLocalGrids(
6031  poses,
6032  map,
6033  xMin,
6034  yMin,
6035  cellSize,
6036  cropRadius,
6037  filterScans);
6038  }
6039  return -1;
6040 }
6041 
6043 {
6044  if(!_rgbdSlamMode)
6045  {
6046  UERROR("Refining links can be done only in RGBD-SLAM mode.");
6047  return -1;
6048  }
6049 
6050  std::list<Link> linksRefined;
6051 
6052  std::map<int, Transform> poses;
6053  std::multimap<int, Link> links;
6054  std::map<int, Signature> signatures;
6055  this->getGraph(poses, links, false, true, &signatures);
6056 
6057  int i=0;
6058  for(std::multimap<int, Link>::iterator iter=links.lower_bound(1); iter!= links.end(); ++iter)
6059  {
6060  int from = iter->second.from();
6061  int to = iter->second.to();
6062 
6063  UASSERT(signatures.find(from) != signatures.end());
6064  UASSERT(signatures.find(to) != signatures.end());
6065 
6067  // use signatures instead of IDs because some signatures may not be in WM
6068  Transform t = _memory->computeTransform(signatures.at(from), signatures.at(to), iter->second.transform(), &info);
6069 
6070  if(!t.isNull())
6071  {
6072  linksRefined.push_back(Link(from, to, iter->second.type(), t, info.covariance.inv()));
6073  UINFO("Refined link %d->%d! (%d/%d)", from, to, ++i, (int)links.size());
6074  }
6075  }
6076  UINFO("Total refined %d links.", (int)linksRefined.size());
6077 
6078  if(linksRefined.size())
6079  {
6080  for(std::list<Link>::iterator iter=linksRefined.begin(); iter!=linksRefined.end(); ++iter)
6081  {
6082  _memory->updateLink(*iter, true);
6083  }
6084  }
6085  return (int)linksRefined.size();
6086 }
6087 
6088 bool Rtabmap::addLink(const Link & link)
6089 {
6090  const Transform & t = link.transform();
6091  if(!_rgbdSlamMode)
6092  {
6093  UERROR("Adding new link can be done only in RGBD-SLAM mode.");
6094  return false;
6095  }
6096  if(!_memory)
6097  {
6098  UERROR("Memory is not initialized.");
6099  return false;
6100  }
6101  if(t.isNull())
6102  {
6103  UERROR("Link's transform is null! (%d->%d type=%s)", link.from(), link.to(), link.typeName().c_str());
6104  return false;
6105  }
6106  if(_memory->isIncremental())
6107  {
6108  if(_memory->getSignature(link.from()) == 0)
6109  {
6110  UERROR("Link's \"from id\" %d is not in working memory", link.from());
6111  return false;
6112  }
6113  if(_memory->getSignature(link.to()) == 0)
6114  {
6115  UERROR("Link's \"to id\" %d is not in working memory", link.to());
6116  return false;
6117  }
6118 
6119  if(_optimizedPoses.find(link.from()) == _optimizedPoses.end() &&
6120  _optimizedPoses.find(link.to()) == _optimizedPoses.end())
6121  {
6122  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());
6123  return false;
6124  }
6125 
6126  // add temporary the link
6127  if(!_memory->addLink(link))
6128  {
6129  UERROR("Cannot add new link %d->%d to memory", link.from(), link.to());
6130  return false;
6131  }
6132 
6133  // optimize with new link
6134  std::map<int, Transform> poses = _optimizedPoses;
6135  std::multimap<int, Link> links;
6136  cv::Mat covariance;
6137  optimizeCurrentMap(this->getLastLocationId(), false, poses, covariance, &links);
6138 
6139  if(poses.find(link.from()) == poses.end())
6140  {
6141  UERROR("Link's \"from id\" %d is not in the graph (size=%d)", link.from(), (int)poses.size());
6142  _memory->removeLink(link.from(), link.to());
6143  return false;
6144  }
6145  if(poses.find(link.to()) == poses.end())
6146  {
6147  UERROR("Link's \"to id\" %d is not in the graph (size=%d)", link.to(), (int)poses.size());
6148  _memory->removeLink(link.from(), link.to());
6149  return false;
6150  }
6151 
6152  std::string msg;
6153  if(poses.empty())
6154  {
6155  msg = uFormat("Rejecting edge %d->%d because graph optimization has failed!", link.from(), link.to());
6156  }
6157  else
6158  {
6159  float maxLinearError = 0.0f;
6160  float maxLinearErrorRatio = 0.0f;
6161  float maxAngularError = 0.0f;
6162  float maxAngularErrorRatio = 0.0f;
6163  const Link * maxLinearLink = 0;
6164  const Link * maxAngularLink = 0;
6165 
6167  poses,
6168  links,
6169  maxLinearErrorRatio,
6170  maxAngularErrorRatio,
6171  maxLinearError,
6172  maxAngularError,
6173  &maxLinearLink,
6174  &maxAngularLink);
6175  if(maxLinearLink)
6176  {
6177  UINFO("Max optimization linear error = %f m (link %d->%d)", maxLinearError, maxLinearLink->from(), maxLinearLink->to());
6178  if(_optimizationMaxError > 0.0f && maxLinearErrorRatio > _optimizationMaxError)
6179  {
6180  msg = uFormat("Rejecting edge %d->%d because "
6181  "graph error is too large after optimization (%f m for edge %d->%d with ratio %f > std=%f m). "
6182  "\"%s\" is %f.",
6183  link.from(),
6184  link.to(),
6185  maxLinearError,
6186  maxLinearLink->from(),
6187  maxLinearLink->to(),
6188  maxLinearErrorRatio,
6189  sqrt(maxLinearLink->transVariance()),
6190  Parameters::kRGBDOptimizeMaxError().c_str(),
6192  }
6193  else if(_optimizationMaxError == 0.0f && maxLinearErrorRatio>100 && !_graphOptimizer->isRobust())
6194  {
6195  UERROR("Huge optimization error detected!"
6196  "Linear error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). You may consider "
6197  "enabling \"%s\" to reject those bad optimizations by setting it to a non null value!",
6198  maxLinearErrorRatio,
6199  maxLinearLink->from(),
6200  maxLinearLink->to(),
6201  maxLinearLink->type(),
6202  maxLinearError,
6203  sqrt(maxLinearLink->transVariance()),
6204  Parameters::kRGBDOptimizeMaxError().c_str());
6205  }
6206  }
6207  else if(maxAngularLink)
6208  {
6209  UINFO("Max optimization angular error = %f deg (link %d->%d)", maxAngularError*180.0f/M_PI, maxAngularLink->from(), maxAngularLink->to());
6210  if(_optimizationMaxError > 0.0f && maxAngularErrorRatio > _optimizationMaxError)
6211  {
6212  msg = uFormat("Rejecting edge %d->%d because "
6213  "graph error is too large after optimization (%f deg for edge %d->%d with ratio %f > std=%f deg). "
6214  "\"%s\" is %f m.",
6215  link.from(),
6216  link.to(),
6217  maxAngularError*180.0f/M_PI,
6218  maxAngularLink->from(),
6219  maxAngularLink->to(),
6220  maxAngularErrorRatio,
6221  sqrt(maxAngularLink->rotVariance()),
6222  Parameters::kRGBDOptimizeMaxError().c_str(),
6224  }
6225  else if(_optimizationMaxError == 0.0f && maxAngularErrorRatio>100 && !_graphOptimizer->isRobust())
6226  {
6227  UERROR("Huge optimization error detected!"
6228  "Angular error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). You may consider "
6229  "enabling \"%s\" to reject those bad optimizations by setting it to a non null value!",
6230  maxAngularErrorRatio,
6231  maxAngularLink->from(),
6232  maxAngularLink->to(),
6233  maxAngularLink->type(),
6234  maxAngularError*180.0f/CV_PI,
6235  sqrt(maxAngularLink->rotVariance()),
6236  Parameters::kRGBDOptimizeMaxError().c_str());
6237  }
6238  }
6239  }
6240  if(!msg.empty())
6241  {
6242  UERROR("%s", msg.c_str());
6243  _memory->removeLink(link.from(), link.to());
6244  return false;
6245  }
6246 
6247  // Update optimized poses
6248  for(std::map<int, Transform>::iterator iter=_optimizedPoses.begin(); iter!=_optimizedPoses.end(); ++iter)
6249  {
6250  std::map<int, Transform>::iterator jter = poses.find(iter->first);
6251  if(jter != poses.end())
6252  {
6253  iter->second = jter->second;
6254  }
6255  }
6257  {
6258  _mapCorrection = _optimizedPoses.rbegin()->second * _memory->getSignature(_optimizedPoses.rbegin()->first)->getPose().inverse();
6259  }
6260 
6261  std::map<int, Transform> tmp;
6262  // Update also the links if some have been added in WM
6264  // This will force rtabmap_ros to regenerate the global occupancy grid if there was one
6265  _memory->save2DMap(cv::Mat(), 0, 0, 0);
6266 
6267  return true;
6268  }
6269  else // localization mode
6270  {
6271  int oldestId = link.from()>link.to()?link.to():link.from();
6272  int newestId = link.from()<link.to()?link.to():link.from();
6273 
6274  if(_memory->getSignature(oldestId) == 0)
6275  {
6276  UERROR("Link's id %d is not in working memory", oldestId);
6277  return false;
6278  }
6279  if(_optimizedPoses.find(oldestId) == _optimizedPoses.end())
6280  {
6281  UERROR("Link's id %d is not in the optimized graph (_optimizedPoses=%d)", oldestId, (int)_optimizedPoses.size());
6282  return false;
6283  }
6285  {
6286  UERROR("Adding link with %s=true in localization mode is not supported.", Parameters::kRGBDOptimizeFromGraphEnd().c_str());
6287  return false;
6288  }
6289  if(_odomCachePoses.find(newestId) == _odomCachePoses.end())
6290  {
6291  if(!_odomCachePoses.empty())
6292  {
6293  UERROR("Link's id %d is not in the odometry cache (oldest=%d, newest=%d, %s=%d)",
6294  newestId,
6295  _odomCachePoses.begin()->first,
6296  _odomCachePoses.rbegin()->first,
6297  Parameters::kRGBDMaxOdomCacheSize().c_str(),
6299  }
6300  else
6301  {
6302  UERROR("Link's id %d is not in the odometry cache (%s=%d).",
6303  newestId,
6304  Parameters::kRGBDMaxOdomCacheSize().c_str(),
6306  }
6307  return false;
6308  }
6309 
6310  // Verify if the new localization is valid by checking if there is
6311  // not too much deformation using current odometry poses
6312  // This will also refine localization links
6313 
6314  std::map<int, Transform> poses = _odomCachePoses;
6315  std::multimap<int, Link> constraints = _odomCacheConstraints;
6316  constraints.insert(std::make_pair(link.from(), link));
6317  for(std::multimap<int, Link>::iterator iter=constraints.begin(); iter!=constraints.end(); ++iter)
6318  {
6319  std::map<int, Transform>::iterator iterPose = _optimizedPoses.find(iter->second.to());
6320  if(iterPose != _optimizedPoses.end() && poses.find(iterPose->first) == poses.end())
6321  {
6322  poses.insert(*iterPose);
6323  // make the poses in the map fixed
6324  constraints.insert(std::make_pair(iterPose->first, Link(iterPose->first, iterPose->first, Link::kPosePrior, iterPose->second, cv::Mat::eye(6,6, CV_64FC1)*999999)));
6325  }
6326  }
6327 
6328  std::map<int, Transform> posesOut;
6329  std::multimap<int, Link> edgeConstraintsOut;
6330  bool priorsIgnored = _graphOptimizer->priorsIgnored();
6331  _graphOptimizer->setPriorsIgnored(false); //temporary set false to use priors above to fix nodes of the map
6332  _graphOptimizer->getConnectedGraph(newestId, poses, constraints, posesOut, edgeConstraintsOut);
6333  std::map<int, Transform> optPoses = _graphOptimizer->optimize(poses.begin()->first, posesOut, edgeConstraintsOut);
6334  _graphOptimizer->setPriorsIgnored(priorsIgnored); // set back
6335 
6336  bool rejectLocalization = false;
6337  if(optPoses.empty())
6338  {
6339  UWARN("Optimization failed, rejecting localization!");
6340  rejectLocalization = true;
6341  }
6342  else
6343  {
6344  UINFO("Compute max graph errors...");
6345  float maxLinearError = 0.0f;
6346  float maxLinearErrorRatio = 0.0f;
6347  float maxAngularError = 0.0f;
6348  float maxAngularErrorRatio = 0.0f;
6349  const Link * maxLinearLink = 0;
6350  const Link * maxAngularLink = 0;
6352  optPoses,
6353  edgeConstraintsOut,
6354  maxLinearErrorRatio,
6355  maxAngularErrorRatio,
6356  maxLinearError,
6357  maxAngularError,
6358  &maxLinearLink,
6359  &maxAngularLink,
6361  if(maxLinearLink == 0 && maxAngularLink==0)
6362  {
6363  UWARN("Could not compute graph errors! Wrong loop closures could be accepted!");
6364  }
6365 
6366  if(maxLinearLink)
6367  {
6368  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()));
6369  if(_optimizationMaxError > 0.0f && maxLinearErrorRatio > _optimizationMaxError)
6370  {
6371  UWARN("Rejecting localization (%d <-> %d) in this "
6372  "iteration because a wrong loop closure has been "
6373  "detected after graph optimization, resulting in "
6374  "a maximum graph error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). The "
6375  "maximum error ratio parameter \"%s\" is %f of std deviation.",
6376  link.from(),
6377  link.to(),
6378  maxLinearErrorRatio,
6379  maxLinearLink->from(),
6380  maxLinearLink->to(),
6381  maxLinearLink->type(),
6382  maxLinearError,
6383  sqrt(maxLinearLink->transVariance()),
6384  Parameters::kRGBDOptimizeMaxError().c_str(),
6386  rejectLocalization = true;
6387  }
6388  else if(_optimizationMaxError == 0.0f && maxLinearErrorRatio>100 && !_graphOptimizer->isRobust())
6389  {
6390  UERROR("Huge optimization error detected!"
6391  "Linear error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). You may consider "
6392  "enabling \"%s\" to reject those bad optimizations by setting it to a non null value!",
6393  maxLinearErrorRatio,
6394  maxLinearLink->from(),
6395  maxLinearLink->to(),
6396  maxLinearLink->type(),
6397  maxLinearError,
6398  sqrt(maxLinearLink->transVariance()),
6399  Parameters::kRGBDOptimizeMaxError().c_str());
6400  }
6401  }
6402  if(maxAngularLink)
6403  {
6404  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()));
6405  if(_optimizationMaxError > 0.0f && maxAngularErrorRatio > _optimizationMaxError)
6406  {
6407  UWARN("Rejecting localization (%d <-> %d) in this "
6408  "iteration because a wrong loop closure has been "
6409  "detected after graph optimization, resulting in "
6410  "a maximum graph error ratio of %f (edge %d->%d, type=%d, abs error=%f deg, stddev=%f). The "
6411  "maximum error ratio parameter \"%s\" is %f of std deviation.",
6412  link.from(),
6413  link.to(),
6414  maxAngularErrorRatio,
6415  maxAngularLink->from(),
6416  maxAngularLink->to(),
6417  maxAngularLink->type(),
6418  maxAngularError*180.0f/CV_PI,
6419  sqrt(maxAngularLink->rotVariance()),
6420  Parameters::kRGBDOptimizeMaxError().c_str(),
6422  rejectLocalization = true;
6423  }
6424  else if(_optimizationMaxError == 0.0f && maxAngularErrorRatio>100 && !_graphOptimizer->isRobust())
6425  {
6426  UERROR("Huge optimization error detected!"
6427  "Angular error ratio of %f (edge %d->%d, type=%d, abs error=%f m, stddev=%f). You may consider "
6428  "enabling \"%s\" to reject those bad optimizations by setting it to a non null value!",
6429  maxAngularErrorRatio,
6430  maxAngularLink->from(),
6431  maxAngularLink->to(),
6432  maxAngularLink->type(),
6433  maxAngularError*180.0f/CV_PI,
6434  sqrt(maxAngularLink->rotVariance()),
6435  Parameters::kRGBDOptimizeMaxError().c_str());
6436  }
6437  }
6438  }
6439 
6440  if(!rejectLocalization)
6441  {
6442  Transform newOptPoseInv = optPoses.at(link.from()).inverse();
6443  Transform newT = newOptPoseInv * optPoses.at(link.to());
6444  Link linkTmp = link;
6445  linkTmp.setTransform(newT);
6446  if(oldestId == link.from())
6447  {
6448  _lastLocalizationPose = _optimizedPoses.at(link.from()) * linkTmp.transform();
6449  _odomCacheConstraints.insert(std::make_pair(linkTmp.to(), linkTmp.inverse()));
6450  }
6451  else
6452  {
6453  _lastLocalizationPose = _optimizedPoses.at(link.to()) * linkTmp.transform().inverse();
6454  _odomCacheConstraints.insert(std::make_pair(linkTmp.from(), linkTmp));
6455  }
6456  UINFO("Set _lastLocalizationPose=%s", _lastLocalizationPose.prettyPrint().c_str());
6457  if(_graphOptimizer->isSlam2d())
6458  {
6459  // transform constraint to 2D
6461  }
6462  Transform odomPose = _odomCachePoses.find(newestId)->second;
6464  _lastLocalizationNodeId = oldestId;
6465  return true;
6466  }
6467  }
6468  return false;
6469 }
6470 
6471 cv::Mat Rtabmap::getInformation(const cv::Mat & covariance) const
6472 {
6473  cv::Mat information = covariance.inv();
6474  if(_loopCovLimited)
6475  {
6476  const std::vector<double> & odomMaxInf = _memory->getOdomMaxInf();
6477  if(odomMaxInf.size() == 6)
6478  {
6479  for(int i=0; i<6; ++i)
6480  {
6481  if(information.at<double>(i,i) > odomMaxInf[i])
6482  {
6483  information.at<double>(i,i) = odomMaxInf[i];
6484  }
6485  }
6486  }
6487  }
6488  return information;
6489 }
6490 
6491 void Rtabmap::addNodesToRepublish(const std::vector<int> & ids)
6492 {
6493  if(ids.empty())
6494  {
6495  _nodesToRepublish.clear();
6496  }
6498  {
6499  _nodesToRepublish.insert(ids.begin(), ids.end());
6500  }
6501  else if(_maxRepublished == 0)
6502  {
6503  UWARN("%s=0, so cannot republish the %d requested nodes.", Parameters::kRtabmapMaxRepublished().c_str(), (int)ids.size());
6504  }
6505  else //_publishLastSignatureData=false
6506  {
6507  UWARN("%s=false, so cannot republish the %d requested nodes.", Parameters::kRtabmapPublishLastSignature().c_str(), (int)ids.size());
6508  }
6509 }
6510 
6511 void Rtabmap::clearPath(int status)
6512 {
6513  UINFO("status=%d", status);
6514  _pathStatus = status;
6515  _path.clear();
6517  _pathGoalIndex = 0;
6519  _pathUnreachableNodes.clear();
6520  _pathStuckCount = 0;
6521  _pathStuckDistance = 0.0f;
6522  if(_memory)
6523  {
6525  }
6526 }
6527 
6528 // return true if path is updated
6529 bool Rtabmap::computePath(int targetNode, bool global)
6530 {
6531  this->clearPath(0);
6532 
6533  if(targetNode>0)
6534  {
6535  UINFO("Planning a path to node %d (global=%d)", targetNode, global?1:0);
6536  }
6537  else
6538  {
6539  UINFO("Planning a path to landmark %d (global=%d)", -targetNode, global?1:0);
6540  }
6541 
6542  if(!_rgbdSlamMode)
6543  {
6544  UWARN("A path can only be computed in RGBD-SLAM mode");
6545  return false;
6546  }
6547 
6548  UTimer totalTimer;
6549  UTimer timer;
6550  Transform transformToLandmark = Transform::getIdentity();
6551 
6552  // No need to optimize the graph
6553  if(_memory)
6554  {
6555  int currentNode = 0;
6556  if(_memory->isIncremental())
6557  {
6559  {
6560  UWARN("Working memory is empty... cannot compute a path");
6561  return false;
6562  }
6563  currentNode = _memory->getLastWorkingSignature()->id();
6564  }
6565  else
6566  {
6568  {
6569  UWARN("Last localization pose is null or optimized graph is empty... cannot compute a path");
6570  return false;
6571  }
6572  if(_optimizedPoses.begin()->first < 0)
6573  {
6574  std::map<int, Transform> poses(_optimizedPoses.lower_bound(1), _optimizedPoses.end());
6575  currentNode = graph::findNearestNode(poses, _lastLocalizationPose);
6576  }
6577  else
6578  {
6580  }
6581  }
6582  if(currentNode && targetNode)
6583  {
6584  std::list<std::pair<int, Transform> > path = graph::computePath(
6585  currentNode,
6586  targetNode,
6587  _memory,
6588  global,
6589  false,
6592 
6593  //transform in current referential
6595  _path.resize(path.size());
6596  int oi = 0;
6597  for(std::list<std::pair<int, Transform> >::iterator iter=path.begin(); iter!=path.end();++iter)
6598  {
6599  if(iter->first > 0)
6600  {
6601  // just keep nodes in the path
6602  _path[oi].first = iter->first;
6603  _path[oi++].second = t * iter->second;
6604  }
6605  }
6606  _path.resize(oi);
6607  if(!_path.empty() && !path.empty() && path.rbegin()->first < 0)
6608  {
6609  transformToLandmark = _path.back().second.inverse() * t * path.rbegin()->second;
6610  }
6611  }
6612  else if(currentNode == 0)
6613  {
6614  UWARN("We should be localized before planning.");
6615  }
6616  }
6617  UINFO("Total planning time = %fs (%d nodes, %f m long)", totalTimer.ticks(), (int)_path.size(), graph::computePathLength(_path));
6618 
6619  if(_path.size() == 0)
6620  {
6621  _path.clear();
6622  UWARN("Cannot compute a path!");
6623  return false;
6624  }
6625  else
6626  {
6627  UINFO("Path generated! Size=%d", (int)_path.size());
6629  {
6630  std::stringstream stream;
6631  for(unsigned int i=0; i<_path.size(); ++i)
6632  {
6633  stream << _path[i].first;
6634  if(i+1 < _path.size())
6635  {
6636  stream << " ";
6637  }
6638  }
6639  UINFO("Path = [%s]", stream.str().c_str());
6640  }
6642  {
6643  // set goal to latest signature
6644  std::string goalStr = uFormat("GOAL:%d", targetNode);
6645 
6646  // use label is exist
6647  if(_memory->getSignature(targetNode))
6648  {
6649  if(!_memory->getSignature(targetNode)->getLabel().empty())
6650  {
6651  goalStr = std::string("GOAL:")+_memory->getSignature(targetNode)->getLabel();
6652  }
6653  }
6654  else if(global)
6655  {
6656  std::map<int, std::string> labels = _memory->getAllLabels();
6657  std::map<int, std::string>::iterator iter = labels.find(targetNode);
6658  if(iter != labels.end() && !iter->second.empty())
6659  {
6660  goalStr = std::string("GOAL:")+labels.at(targetNode);
6661  }
6662  }
6663  setUserData(0, cv::Mat(1, int(goalStr.size()+1), CV_8SC1, (void *)goalStr.c_str()).clone());
6664  }
6665  _pathTransformToGoal = transformToLandmark;
6666 
6667  updateGoalIndex();
6668  return _path.size() || _pathStatus > 0;
6669  }
6670 
6671  return false;
6672 }
6673 
6674 bool Rtabmap::computePath(const Transform & targetPose, float tolerance)
6675 {
6676  this->clearPath(0);
6677 
6678  UINFO("Planning a path to pose %s ", targetPose.prettyPrint().c_str());
6679  if(tolerance < 0.0f)
6680  {
6681  tolerance = _localRadius;
6682  }
6683 
6684  std::list<std::pair<int, Transform> > pathPoses;
6685 
6686  if(!_rgbdSlamMode)
6687  {
6688  UWARN("This method can only be used in RGBD-SLAM mode");
6689  return false;
6690  }
6691 
6692  //Find the nearest node
6693  UTimer timer;
6694  std::map<int, Transform> nodes = _optimizedPoses;
6695  std::multimap<int, int> links;
6696  for(std::map<int, Transform>::iterator iter=nodes.upper_bound(0); iter!=nodes.end(); ++iter)
6697  {
6698  const Signature * s = _memory->getSignature(iter->first);
6699  UASSERT(s);
6700  for(std::map<int, Link>::const_iterator jter=s->getLinks().begin(); jter!=s->getLinks().end(); ++jter)
6701  {
6702  // only add links for which poses are in "nodes"
6703  if(jter->second.from() != jter->second.to() && uContains(nodes, jter->second.to()))
6704  {
6705  links.insert(std::make_pair(jter->second.from(), jter->second.to()));
6706  //links.insert(std::make_pair(jter->second.to(), jter->second.from())); // <-> (commented: already added when iterating in nodes)
6707  }
6708  }
6709  }
6710  UINFO("Time getting links = %fs", timer.ticks());
6711 
6712  int currentNode = 0;
6713  if(_memory->isIncremental())
6714  {
6716  {
6717  UWARN("Working memory is empty... cannot compute a path");
6718  return false;
6719  }
6720  currentNode = _memory->getLastWorkingSignature()->id();
6721  }
6722  else
6723  {
6725  {
6726  UWARN("Last localization pose is null... cannot compute a path");
6727  return false;
6728  }
6729  if(_optimizedPoses.begin()->first < 0)
6730  {
6731  std::map<int, Transform> poses(_optimizedPoses.lower_bound(1), _optimizedPoses.end());
6732  currentNode = graph::findNearestNode(poses, _lastLocalizationPose);
6733  }
6734  else
6735  {
6737  }
6738  }
6739 
6740  int nearestId;
6741  if(!_lastLocalizationPose.isNull() && _lastLocalizationPose.getDistance(targetPose) < tolerance)
6742  {
6743  // target can be reached from the current node
6744  nearestId = currentNode;
6745  }
6746  else
6747  {
6748  nearestId = rtabmap::graph::findNearestNode(nodes, targetPose);
6749  }
6750  UINFO("Nearest node found=%d ,%fs", nearestId, timer.ticks());
6751  if(nearestId > 0)
6752  {
6753  if(tolerance != 0.0f && targetPose.getDistance(nodes.at(nearestId)) > tolerance)
6754  {
6755  UWARN("Cannot plan farther than %f m from the graph! (distance=%f m from node %d)",
6756  tolerance, targetPose.getDistance(nodes.at(nearestId)), nearestId);
6757  }
6758  else
6759  {
6760  UINFO("Computing path from location %d to %d", currentNode, nearestId);
6761  UTimer timer;
6762  _path = uListToVector(rtabmap::graph::computePath(nodes, links, currentNode, nearestId));
6763  UINFO("A* time = %fs", timer.ticks());
6764 
6765  if(_path.size() == 0)
6766  {
6767  UWARN("Cannot compute a path!");
6768  }
6769  else
6770  {
6771  UINFO("Path generated! Size=%d", (int)_path.size());
6773  {
6774  std::stringstream stream;
6775  for(unsigned int i=0; i<_path.size(); ++i)
6776  {
6777  stream << _path[i].first;
6778  if(i+1 < _path.size())
6779  {
6780  stream << " ";
6781  }
6782  }
6783  UINFO("Path = [%s]", stream.str().c_str());
6784  }
6785 
6786  UASSERT(uContains(nodes, _path.back().first));
6787  _pathTransformToGoal = nodes.at(_path.back().first).inverse() * targetPose;
6788 
6789  updateGoalIndex();
6790 
6791  return true;
6792  }
6793  }
6794  }
6795  else
6796  {
6797  UWARN("Nearest node not found in graph (size=%d) for pose %s", (int)nodes.size(), targetPose.prettyPrint().c_str());
6798  }
6799 
6800  return false;
6801 }
6802 
6803 std::vector<std::pair<int, Transform> > Rtabmap::getPathNextPoses() const
6804 {
6805  std::vector<std::pair<int, Transform> > poses;
6806  if(_path.size())
6807  {
6808  UASSERT(_pathCurrentIndex < _path.size() && _pathGoalIndex < _path.size());
6809  poses.resize(_pathGoalIndex-_pathCurrentIndex+1);
6810  int oi=0;
6811  for(unsigned int i=_pathCurrentIndex; i<=_pathGoalIndex; ++i)
6812  {
6813  std::map<int, Transform>::const_iterator iter = _optimizedPoses.find(_path[i].first);
6814  if(iter != _optimizedPoses.end())
6815  {
6816  poses[oi++] = *iter;
6817  }
6818  else
6819  {
6820  break;
6821  }
6822  }
6823  poses.resize(oi);
6824  }
6825  return poses;
6826 }
6827 
6828 std::vector<int> Rtabmap::getPathNextNodes() const
6829 {
6830  std::vector<int> ids;
6831  if(_path.size())
6832  {
6833  UASSERT(_pathCurrentIndex < _path.size() && _pathGoalIndex < _path.size());
6834  ids.resize(_pathGoalIndex-_pathCurrentIndex+1);
6835  int oi = 0;
6836  for(unsigned int i=_pathCurrentIndex; i<=_pathGoalIndex; ++i)
6837  {
6838  std::map<int, Transform>::const_iterator iter = _optimizedPoses.find(_path[i].first);
6839  if(iter != _optimizedPoses.end())
6840  {
6841  ids[oi++] = iter->first;
6842  }
6843  else
6844  {
6845  break;
6846  }
6847  }
6848  ids.resize(oi);
6849  }
6850  return ids;
6851 }
6852 
6854 {
6855  if(_path.size())
6856  {
6857  UASSERT(_pathGoalIndex <= _path.size());
6858  return _path[_pathGoalIndex].first;
6859  }
6860  return 0;
6861 }
6862 
6864 {
6865  if(!_rgbdSlamMode)
6866  {
6867  UWARN("This method can on be used in RGBD-SLAM mode!");
6868  return;
6869  }
6870 
6871  if( _memory && _path.size())
6872  {
6873  // remove all previous virtual links
6874  for(unsigned int i=0; i<_pathCurrentIndex && i<_path.size(); ++i)
6875  {
6876  const Signature * s = _memory->getSignature(_path[i].first);
6877  if(s)
6878  {
6879  _memory->removeVirtualLinks(s->id());
6880  }
6881  }
6882 
6883  // for the current index, only keep the newest virtual link
6884  // This will make sure that the path is still connected even
6885  // if the new signature is removed (e.g., because of a small displacement)
6886  UASSERT(_pathCurrentIndex < _path.size());
6887  const Signature * currentIndexS = _memory->getSignature(_path[_pathCurrentIndex].first);
6888  UASSERT_MSG(currentIndexS != 0, uFormat("_path[%d].first=%d", _pathCurrentIndex, _path[_pathCurrentIndex].first).c_str());
6889  std::multimap<int, Link> links = currentIndexS->getLinks(); // make a copy
6890  bool latestVirtualLinkFound = false;
6891  for(std::multimap<int, Link>::reverse_iterator iter=links.rbegin(); iter!=links.rend(); ++iter)
6892  {
6893  if(iter->second.type() == Link::kVirtualClosure)
6894  {
6895  if(latestVirtualLinkFound)
6896  {
6897  _memory->removeLink(currentIndexS->id(), iter->first);
6898  }
6899  else
6900  {
6901  latestVirtualLinkFound = true;
6902  }
6903  }
6904  }
6905 
6906  // Make sure the next signatures on the path are linked together
6907  float distanceSoFar = 0.0f;
6908  for(unsigned int i=_pathCurrentIndex+1;
6909  i<_path.size();
6910  ++i)
6911  {
6912  if(i>0)
6913  {
6914  if(_localRadius > 0.0f)
6915  {
6916  distanceSoFar += _path[i-1].second.getDistance(_path[i].second);
6917  }
6918  if(distanceSoFar <= _localRadius)
6919  {
6920  if(_path[i].first != _path[i-1].first)
6921  {
6922  const Signature * s = _memory->getSignature(_path[i].first);
6923  if(s)
6924  {
6925  if(!s->hasLink(_path[i-1].first) && _memory->getSignature(_path[i-1].first) != 0)
6926  {
6927  Transform virtualLoop = _path[i].second.inverse() * _path[i-1].second;
6928  _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
6929  UINFO("Added Virtual link between %d and %d", _path[i-1].first, _path[i].first);
6930  }
6931  }
6932  }
6933  }
6934  else
6935  {
6936  break;
6937  }
6938  }
6939  }
6940 
6941  UDEBUG("current node = %d current goal = %d", _path[_pathCurrentIndex].first, _path[_pathGoalIndex].first);
6942  Transform currentPose;
6943  if(_memory->isIncremental())
6944  {
6945  if(_memory->getLastWorkingSignature() == 0 ||
6947  {
6948  UERROR("Last node is null in memory or not in optimized poses. Aborting the plan...");
6949  this->clearPath(-1);
6950  return;
6951  }
6952  currentPose = _optimizedPoses.at(_memory->getLastWorkingSignature()->id());
6953  }
6954  else
6955  {
6957  {
6958  UERROR("Last localization pose is null. Aborting the plan...");
6959  this->clearPath(-1);
6960  return;
6961  }
6962  currentPose = _lastLocalizationPose;
6963  }
6964 
6965  int goalId = _path.back().first;
6966  if(uContains(_optimizedPoses, goalId))
6967  {
6968  //use local position to know if the goal is reached
6969  float d = currentPose.getDistance(_optimizedPoses.at(goalId)*_pathTransformToGoal);
6970  if(d < _goalReachedRadius)
6971  {
6972  UINFO("Goal %d reached!", goalId);
6973  this->clearPath(1);
6974  }
6975  }
6976 
6977  if(_path.size())
6978  {
6979  //Always check if the farthest node is accessible in local map (max to local space radius if set)
6980  unsigned int goalIndex = _pathCurrentIndex;
6981  float distanceFromCurrentNode = 0.0f;
6982  bool sameGoalIndex = false;
6983  for(unsigned int i=_pathCurrentIndex+1; i<_path.size(); ++i)
6984  {
6986  {
6987  if(_localRadius > 0.0f)
6988  {
6989  distanceFromCurrentNode = _path[_pathCurrentIndex].second.getDistance(_path[i].second);
6990  }
6991 
6992  if((goalIndex == _pathCurrentIndex && i == _path.size()-1) ||
6994  {
6995  if(distanceFromCurrentNode <= _localRadius)
6996  {
6997  goalIndex = i;
6998  }
6999  else
7000  {
7001  break;
7002  }
7003  }
7004  }
7005  else
7006  {
7007  break;
7008  }
7009  }
7010  UASSERT(_pathGoalIndex < _path.size() && goalIndex < _path.size());
7011  if(_pathGoalIndex != goalIndex)
7012  {
7013  UINFO("Updated current goal from %d to %d (%d/%d)",
7014  (int)_path[_pathGoalIndex].first, _path[goalIndex].first, (int)goalIndex+1, (int)_path.size());
7015  _pathGoalIndex = goalIndex;
7016  }
7017  else
7018  {
7019  sameGoalIndex = true;
7020  }
7021 
7022  // update nearest pose in the path
7023  unsigned int nearestNodeIndex = 0;
7024  float distance = -1.0f;
7025  bool sameCurrentIndex = false;
7026  UASSERT(_pathGoalIndex < _path.size());
7027  for(unsigned int i=_pathCurrentIndex; i<=_pathGoalIndex; ++i)
7028  {
7029  std::map<int, Transform>::iterator iter = _optimizedPoses.find(_path[i].first);
7030  if(iter != _optimizedPoses.end())
7031  {
7032  float d = currentPose.getDistanceSquared(iter->second);
7033  if(distance == -1.0f || distance > d)
7034  {
7035  distance = d;
7036  nearestNodeIndex = i;
7037  }
7038  }
7039  }
7040  if(distance < 0)
7041  {
7042  UERROR("The nearest pose on the path not found! Aborting the plan...");
7043  this->clearPath(-1);
7044  }
7045  else
7046  {
7047  UDEBUG("Nearest node = %d", _path[nearestNodeIndex].first);
7048  }
7049  if(distance >= 0 && nearestNodeIndex != _pathCurrentIndex)
7050  {
7051  _pathCurrentIndex = nearestNodeIndex;
7052  _pathUnreachableNodes.erase(nearestNodeIndex); // if we are on it, it is reachable
7053  }
7054  else
7055  {
7056  sameCurrentIndex = true;
7057  }
7058 
7059  bool isStuck = false;
7060  if(sameGoalIndex && sameCurrentIndex && _pathStuckIterations>0)
7061  {
7062  float distanceToCurrentGoal = 0.0f;
7063  std::map<int, Transform>::iterator iter = _optimizedPoses.find(_path[_pathGoalIndex].first);
7064  if(iter != _optimizedPoses.end())
7065  {
7067  _pathGoalIndex == _path.size()-1)
7068  {
7069  distanceToCurrentGoal = currentPose.getDistanceSquared(iter->second*_pathTransformToGoal);
7070  }
7071  else
7072  {
7073  distanceToCurrentGoal = currentPose.getDistanceSquared(iter->second);
7074  }
7075  }
7076 
7077  if(distanceToCurrentGoal > 0.0f)
7078  {
7079  if(distanceToCurrentGoal >= _pathStuckDistance)
7080  {
7081  // we are not approaching the goal
7082  isStuck = true;
7083  if(_pathStuckDistance == 0.0f)
7084  {
7085  _pathStuckDistance = distanceToCurrentGoal;
7086  }
7087  }
7088  }
7089  else
7090  {
7091  // no nodes available, cannot plan
7092  isStuck = true;
7093  }
7094  }
7095 
7096  if(isStuck && ++_pathStuckCount > _pathStuckIterations)
7097  {
7098  UWARN("Current goal %d not reached since %d iterations (\"RGBD/PlanStuckIterations\"=%d), mark that node as unreachable.",
7102  _pathStuckCount = 0;
7103  _pathStuckDistance = 0.0;
7105  // select previous reachable one
7107  {
7109  {
7110  // plan failed!
7111  UERROR("No upcoming nodes on the path are reachable! Aborting the plan...");
7112  this->clearPath(-1);
7113  return;
7114  }
7115  }
7116  }
7117  else if(!isStuck)
7118  {
7119  _pathStuckCount = 0;
7120  _pathStuckDistance = 0.0;
7121  }
7122  }
7123  }
7124 }
7125 
7127 {
7128  UDEBUG("Creating global scan map (if scans are available)");
7130  _globalScanMapPoses.clear();
7131  std::vector<int> scanIndices;
7132  std::map<int, Transform> scanViewpoints;
7133  for(std::map<int, Transform>::iterator iter=_optimizedPoses.begin(); iter!=_optimizedPoses.end(); ++iter)
7134  {
7135  SensorData data = _memory->getNodeData(iter->first, false, true, false, false);
7136  if(!data.laserScanCompressed().empty())
7137  {
7138  LaserScan scan;
7139  data.uncompressDataConst(0, 0, &scan, 0, 0, 0, 0);
7140  if(!scan.empty())
7141  {
7142  UDEBUG("Adding scan %d (format=%s, points=%d)", iter->first, scan.formatName().c_str(), scan.size());
7143  scan = util3d::transformLaserScan(scan, iter->second*scan.localTransform());
7144  if(_globalScanMap.empty() || _globalScanMap.format() == scan.format())
7145  {
7146  _globalScanMap += scan;
7147  _globalScanMapPoses.insert(*iter);
7148  scanViewpoints.insert(std::make_pair(iter->first, iter->second * scan.localTransform()));
7149  scanIndices.resize(_globalScanMap.size(), iter->first);
7150  }
7151  else
7152  {
7153  UWARN("Incompatible scan formats (%s vs %s), cannot create global scan map.",
7154  _globalScanMap.formatName().c_str(),
7155  scan.formatName().c_str());
7157  _globalScanMapPoses.clear();
7158  break;
7159  }
7160  }
7161  else
7162  {
7163  UDEBUG("Ignored %d (scan is empty), pose still added.", iter->first);
7164  _globalScanMapPoses.insert(*iter);
7165  }
7166  }
7167  else
7168  {
7169  UDEBUG("Ignored %d (no scan), pose still added.", iter->first);
7170  _globalScanMapPoses.insert(*iter);
7171  }
7172  }
7173  if(_globalScanMap.size() > 3)
7174  {
7175  float voxelSize = 0.0f;
7176  int normalK = 0;
7177  float normalRadius = 0.0f;
7178  Parameters::parse(_parameters, Parameters::kMemLaserScanVoxelSize(), voxelSize);
7179  Parameters::parse(_parameters, Parameters::kMemLaserScanNormalK(), normalK);
7180  Parameters::parse(_parameters, Parameters::kMemLaserScanNormalRadius(), normalRadius);
7181 
7182  if(voxelSize > 0.0f)
7183  {
7184  LaserScan voxelScan = util3d::commonFiltering(_globalScanMap, 1, 0, 0, voxelSize, normalK, normalRadius);
7185  if(voxelScan.hasNormals())
7186  {
7187  // adjust with point of views
7189  scanViewpoints,
7191  scanIndices,
7192  voxelScan);
7193  }
7194  _globalScanMap = voxelScan;
7195  }
7196 
7197  UINFO("Global scan map has been assembled (size=%d points, %d poses) "
7198  "for proximity detection (only in localization mode %s=false and with %s=true)",
7199  (int)_globalScanMap.size(),
7200  (int)_globalScanMapPoses.size(),
7201  Parameters::kMemIncrementalMemory().c_str(),
7202  Parameters::kRGBDProximityGlobalScanMap().c_str());
7203 
7204  //for debugging...
7206  {
7207  if(!_wDir.empty())
7208  {
7209  UWARN("Saving %s/rtabmap_global_scan_map.pcd (only saved when logger level is debug)", _wDir.c_str());
7210  pcl::PCLPointCloud2::Ptr cloud2 = util3d::laserScanToPointCloud2(_globalScanMap);
7211  pcl::io::savePCDFile(_wDir+"/rtabmap_global_scan_map.pcd", *cloud2);
7212  }
7213  else
7214  {
7215  UWARN("%s is enabled and logger is debug, but %s is not set, cannot save global scan map for debugging.",
7216  Parameters::kRGBDProximityGlobalScanMap().c_str(), Parameters::kRtabmapWorkingDirectory().c_str());
7217  }
7218  }
7219  }
7220  if(!_globalScanMap.empty() && _globalScanMap.size()<100)
7221  {
7222  UWARN("Ignoring global scan map because it is too small (%d points).", (int)_globalScanMap.size());
7224  _globalScanMapPoses.clear();
7225  }
7226 }
7227 
7228 } // 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:4238
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:5291
rtabmap::SensorData::setLaserScan
void setLaserScan(const LaserScan &laserScan, bool clearPreviousData=true)
Definition: SensorData.cpp:381
rtabmap::Rtabmap::getPathNextPoses
std::vector< std::pair< int, Transform > > getPathNextPoses() const
Definition: Rtabmap.cpp:6803
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:5499
LOG_I
#define LOG_I
Definition: Rtabmap.cpp:76
rtabmap::Rtabmap::refineLinks
int refineLinks()
Definition: Rtabmap.cpp:6042
rtabmap::Statistics::addSignatureData
void addSignatureData(const Signature &data)
Definition: Statistics.h:242
rtabmap::Memory::updateAge
void updateAge(int signatureId)
Definition: Memory.cpp:1702
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:6019
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:6475
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:2230
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:1437
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:484
rtabmap::Memory::loadOptimizedPoses
std::map< int, Transform > loadOptimizedPoses(Transform *lastlocalizationPose) const
Definition: Memory.cpp:2151
rtabmap::Memory::removeVirtualLinks
void removeVirtualLinks(int signatureId)
Definition: Memory.cpp:3574
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:6863
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:4769
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:1477
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:3420
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:4076
rtabmap::Memory::saveOptimizedPoses
void saveOptimizedPoses(const std::map< int, Transform > &optimizedPoses, const Transform &lastlocalizationPose) const
Definition: Memory.cpp:2143
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:2826
rtabmap::Rtabmap::_odomCachePoses
std::map< int, Transform > _odomCachePoses
Definition: Rtabmap.h:377
rtabmap::Rtabmap::rejectLastLoopClosure
void rejectLastLoopClosure()
Definition: Rtabmap.cpp:4822
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:5152
rtabmap::Rtabmap::createGlobalScanMap
void createGlobalScanMap()
Definition: Rtabmap.cpp:7126
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:2556
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:5960
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:5510
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:6394
rtabmap::Rtabmap::dumpData
void dumpData() const
Definition: Rtabmap.cpp:4936
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:2006
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:2183
rtabmap::Memory::getLastWorkingSignature
const Signature * getLastWorkingSignature() const
Definition: Memory.cpp:2561
rtabmap::Rtabmap::addNodesToRepublish
void addNodesToRepublish(const std::vector< int > &ids)
Definition: Rtabmap.cpp:6491
rtabmap::Transform::to4DoF
Transform to4DoF() const
Definition: Transform.cpp:222
rtabmap::Rtabmap::setWorkingDirectory
void setWorkingDirectory(std::string path)
Definition: Rtabmap.cpp:4794
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:4028
rtabmap::Memory::getSignature
const Signature * getSignature(int id) const
Definition: Memory.cpp:1240
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:1742
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:503
rtabmap::Rtabmap::_forceOdom3doF
bool _forceOdom3doF
Definition: Rtabmap.h:329
rtabmap::Memory::joinTrashThread
void joinTrashThread()
Definition: Memory.cpp:2240
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:2119
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:4227
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:3663
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:2100
rtabmap::Memory::getNodeCalibration
void getNodeCalibration(int nodeId, std::vector< CameraModel > &models, std::vector< StereoCameraModel > &stereoModels) const
Definition: Memory.cpp:4209
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:2197
rtabmap::Parameters::getDefaultParameters
static const ParametersMap & getDefaultParameters()
Definition: Parameters.h:905
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:2731
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:5582
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:167
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:6529
rtabmap::Memory::getNeighborsIdRadius
std::map< int, float > getNeighborsIdRadius(int signatureId, float radius, const std::map< int, Transform > &optimizedPoses, int maxGraphDepth) const
Definition: Memory.cpp:1614
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:849
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:3205
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:2360
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:6088
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:6511
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:2721
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:1255
Optimizer.h
rtabmap::Memory::getDatabaseMemoryUsed
int getDatabaseMemoryUsed() const
Definition: Memory.cpp:1711
rtabmap::SensorData::clearCompressedData
void clearCompressedData(bool images=true, bool scan=true, bool userData=true)
Definition: SensorData.cpp:832
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:3565
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:5420
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:4126
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:2869
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:1038
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:2216
rtabmap::Memory::emptyTrash
void emptyTrash()
Definition: Memory.cpp:2232
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:5070
rtabmap::Rtabmap::setOptimizedPoses
void setOptimizedPoses(const std::map< int, Transform > &poses, const std::multimap< int, Link > &constraints)
Definition: Rtabmap.cpp:4930
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:1296
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:1288
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:1679
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:2305
rtabmap::Memory::dumpMemory
virtual void dumpMemory(std::string directory) const
Definition: Memory.cpp:3604
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:5626
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:1266
rtabmap::Rtabmap::isIDsGenerated
bool isIDsGenerated() const
Definition: Rtabmap.cpp:870
rtabmap::Rtabmap::getPathNextNodes
std::vector< int > getPathNextNodes() const
Definition: Rtabmap.cpp:6828
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:3731
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:2028
rtabmap::Rtabmap::_newMapOdomChangeDistance
float _newMapOdomChangeDistance
Definition: Rtabmap.h:303
rtabmap::Memory::getVWDictionary
const VWDictionary * getVWDictionary() const
Definition: Memory.cpp:1250
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:1336
rtabmap::Memory::getAllSignatureIds
std::set< int > getAllSignatureIds(bool ignoreChildren=true) const
Definition: Memory.cpp:1747
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:2706
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:4164
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:3989
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:5362
rtabmap::Rtabmap::setMemoryThreshold
void setMemoryThreshold(int maxMemoryAllowed)
Definition: Rtabmap.cpp:4783
rtabmap::Transform::r23
float r23() const
Definition: Transform.h:67
rtabmap::Memory::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Memory.cpp:557
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:2628
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:3505
rtabmap::Memory::computeIcpTransformMulti
Transform computeIcpTransformMulti(int newId, int oldId, const std::map< int, Transform > &poses, RegistrationInfo *info=0)
Definition: Memory.cpp:3219
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:1365
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:848
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:4880
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:6853
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:1770
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:6471
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:2750
rtabmap::Memory::computeLikelihood
std::map< int, float > computeLikelihood(const Signature *signature, const std::list< int > &ids)
Definition: Memory.cpp:1888
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:5198
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:4954
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 Thu Feb 13 2025 03:44:58