Main MRPT website > C++ reference for MRPT 1.9.9
CHMTSLAM_LSLAM_RBPF_2DLASER.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2017, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #include "hmtslam-precomp.h" // Precomp header
11 
14 #include <mrpt/math/wrap2pi.h>
15 #include <mrpt/slam/CICP.h>
16 
17 #include <mrpt/random.h>
18 #include <mrpt/math/utils.h>
20 #include <mrpt/utils/CTicTac.h>
21 #include <mrpt/utils/CFileStream.h>
24 #include <mrpt/system/os.h>
25 #include <mrpt/utils/CTicTac.h>
26 
27 #include <functional>
28 
29 using namespace mrpt;
30 using namespace mrpt::slam;
31 using namespace mrpt::hmtslam;
32 using namespace mrpt::utils;
33 using namespace mrpt::obs;
34 using namespace mrpt::random;
35 using namespace mrpt::maps;
36 using namespace mrpt::bayes;
37 using namespace mrpt::poses;
38 using namespace std;
39 
40 namespace mrpt
41 {
42 namespace hmtslam
43 {
45 {
46 public:
47  static constexpr bool DoesResampling = false;
48  MRPT_TODO("MOVE predicition_and_update code here");
49 };
50 
52 {
53  public:
54  static constexpr bool DoesResampling = true;
55  MRPT_TODO("MOVE prediction_and_update here");
56 };
57 
58 void CLocalMetricHypothesis::executeOn(
60  const mrpt::obs::CSensoryFrame* observation,
63 {
64  switch (PF_algorithm)
65  {
66  case CParticleFilter::pfOptimalProposal:
67  pf.executeOn<
69  *this, action, observation, stats);
70  break;
71  case CParticleFilter::pfAuxiliaryPFOptimal:
72  pf.executeOn<
74  *this, action, observation, stats);
75  break;
76  default:
77  {
78  THROW_EXCEPTION("Invalid particle filter algorithm selection!");
79  }
80  break;
81  }
82 }
83 } // namespace bayes
84 
85 namespace hmtslam
86 {
87 // Constructor
88 CLSLAM_RBPF_2DLASER::CLSLAM_RBPF_2DLASER(CHMTSLAM* parent)
89  : CLSLAMAlgorithmBase(parent)
90 {
91 }
92 // Destructor
94 /*---------------------------------------------------------------
95 
96  CLSLAM_RBPF_2DLASER
97 
98  Implements a 2D local SLAM method based on a RBPF
99  over an occupancy grid map. A part of HMT-SLAM.
100 
101 \param LMH The local metric hypothesis which must be updated by this SLAM
102 algorithm.
103 \param act The action to process (or nullptr).
104 \param sf The observations to process (or nullptr).
105 
106  WE ALREADY HAVE CONTROL OVER THE CRITICAL SECTION OF THE LMHs!
107 
108 --------------------------------------------------------------- */
110  CLocalMetricHypothesis* LMH, const CActionCollection::Ptr& actions,
111  const CSensoryFrame::Ptr& sf)
112 {
113  MRPT_START
114 
115  // Get the current robot pose estimation:
116  TPoseID currentPoseID = LMH->m_currentRobotPose;
117 
118  // If this is the first iteration, just create a new robot pose at the
119  // origin:
120  if (currentPoseID == POSEID_INVALID)
121  {
122  currentPoseID = CHMTSLAM::generatePoseID();
123  LMH->m_currentRobotPose = currentPoseID; // Change it in the LMH
124 
125  // Create a new robot pose:
126  CPose3D initPose(0, 0, 0);
127 
128  ASSERT_(LMH->m_poseParticles.m_particles.size() > 0);
130  LMH->m_poseParticles.m_particles.begin();
131  it != LMH->m_poseParticles.m_particles.end(); ++it)
132  it->d->robotPoses[currentPoseID] = initPose;
133 
134  ASSERT_(m_parent->m_map.nodeCount() == 1);
135 
136  m_parent->m_map_cs.lock();
137  CHMHMapNode::Ptr firstArea = m_parent->m_map.getFirstNode();
138  ASSERT_(firstArea);
139  LMH->m_nodeIDmemberships[currentPoseID] = firstArea->getID();
140 
141  // Set annotation for the reference pose:
142  firstArea->m_annotations.setElemental(
143  NODE_ANNOTATION_REF_POSEID, currentPoseID, LMH->m_ID);
144  m_parent->m_map_cs.unlock();
145  }
146 
147  bool insertNewRobotPose = false;
148  if (sf)
149  {
150  if (LMH->m_nodeIDmemberships.size() < 2) // If there is just 1 node
151  // (the current robot pose),
152  // then there is no
153  // observation in the map yet!
154  { // Update map if this is the first observation!
155  insertNewRobotPose = true;
156  }
157  else
158  {
159  // Check minimum distance from current robot pose to those in the
160  // neighborhood:
161  TMapPoseID2Pose3D lstRobotPoses;
162  LMH->getMeans(lstRobotPoses);
163 
164  CPose3D* currentRobotPose = &lstRobotPoses[currentPoseID];
165  float minDistLin = 1e6f;
166  float minDistAng = 1e6f;
167 
168  // printf("Poses in graph:\n");
169  for (TMapPoseID2Pose3D::iterator it = lstRobotPoses.begin();
170  it != lstRobotPoses.end(); ++it)
171  {
172  if (it->first != currentPoseID)
173  {
174  float linDist = it->second.distanceTo(*currentRobotPose);
175  float angDist = fabs(math::wrapToPi(
176  it->second.yaw() - currentRobotPose->yaw()));
177 
178  minDistLin = min(minDistLin, linDist);
179 
180  if (linDist < m_parent->m_options.SLAM_MIN_DIST_BETWEEN_OBS)
181  minDistAng = min(minDistAng, angDist);
182  }
183  }
184 
185  // time to insert a new node??
186  insertNewRobotPose =
187  (minDistLin > m_parent->m_options.SLAM_MIN_DIST_BETWEEN_OBS) ||
188  (minDistAng > m_parent->m_options.SLAM_MIN_HEADING_BETWEEN_OBS);
189  }
190 
191  } // end if there are SF
192 
193  // Save data in members so PF callback "prediction_and_update_pfXXXX" have
194  // access to them:
195  m_insertNewRobotPose = insertNewRobotPose;
196 
197  // ------------------------------------------------
198  // Execute RBPF method:
199  // 1) PROCESS ACTION
200  // 2) PROCESS OBSERVATIONS
201  // ------------------------------------------------
203  pf.m_options = m_parent->m_options.pf_options;
204  LMH->executeOn(pf, actions.get(), sf.get(), nullptr, pf.m_options.PF_algorithm);
205 
206  // 3) The appearance observation: update the log likelihood
207  // ...
208 
209  // -----------------------------------------------------------
210  // 4) UPDATE THE MAP
211  // -----------------------------------------------------------
212  if (insertNewRobotPose)
213  {
214  m_parent->logStr(
215  mrpt::utils::LVL_INFO,
216  "[CLSLAM_RBPF_2DLASER] Adding new pose...\n");
217 
218  // Leave the up-to-now "current pose" in the map, insert the SF in it,
219  // and...
220  // ----------------------------------------------------------------------------
221  TPoseID newCurrentPoseID = CHMTSLAM::generatePoseID();
222 
223  // ...and create a new "current pose" making a copy of the previous
224  // one:
225  // and insert the observations into the metric maps:
226  // ----------------------------------------------------------------------------
228  LMH->m_poseParticles.m_particles.begin();
229  partIt != LMH->m_poseParticles.m_particles.end(); partIt++)
230  {
231  const CPose3D* curRobotPose = &partIt->d->robotPoses[currentPoseID];
232  partIt->d->robotPoses[newCurrentPoseID] = *curRobotPose;
233  sf->insertObservationsInto(&partIt->d->metricMaps, curRobotPose);
234  }
235 
236  // Add node membership: for now, a copy of the current pose:
237  LMH->m_nodeIDmemberships[newCurrentPoseID] =
238  LMH->m_nodeIDmemberships[currentPoseID];
239 
240  // Now, insert the SF in the just added robot pose:
241  // -----------------------------------------------------
242  LMH->m_SFs[currentPoseID] = *sf;
243 
244  // Sets the new poseID as current robot pose:
245  // ----------------------------------------------------
246  TPoseID newlyAddedPose = currentPoseID;
247  currentPoseID = LMH->m_currentRobotPose = newCurrentPoseID;
248 
249  // Mark the "newlyAddedPose" as pending to reconsider in the graph-cut
250  // method
251  // (Done in the main loop @ LSLAM thread)
252  // --------------------------------------------------------------------------------
253  LMH->m_posesPendingAddPartitioner.push_back(newlyAddedPose);
254 
255  m_parent->logFmt(
256  mrpt::utils::LVL_INFO, "[CLSLAM_RBPF_2DLASER] Added pose %i.\n",
257  (int)newlyAddedPose);
258 
259  // Notice LC detectors:
260  // ------------------------------
261  {
262  std::lock_guard<std::mutex> lock(m_parent->m_topLCdets_cs);
263 
265  m_parent->m_topLCdets.begin();
266  it != m_parent->m_topLCdets.end(); ++it)
267  (*it)->OnNewPose(newlyAddedPose, sf.get());
268  }
269 
270  } // end of insertNewRobotPose
271 
272  MRPT_END
273 }
274 
275 /** The PF algorithm implementation for "optimal sampling for non-parametric
276  * observation models"
277  */
278 template <>
279 void CLocalMetricHypothesis::prediction_and_update<LSLAMAuxiliaryPFOptimal>(
280  const mrpt::obs::CActionCollection* actions,
281  const mrpt::obs::CSensoryFrame* sf,
283 {
284  MRPT_START
285 
286  // Get the current robot pose estimation:
287  TPoseID currentPoseID = m_currentRobotPose;
288 
289  size_t i, k, N, M = m_poseParticles.m_particles.size();
290 
291  // ----------------------------------------------------------------------
292  // We can execute optimal PF only when we have both, an action, and
293  // a valid observation from which to compute the likelihood:
294  // Accumulate odometry/actions until we have a valid observation, then
295  // process them simultaneously.
296  // ----------------------------------------------------------------------
297  // static CActionRobotMovement2D accumRobotMovement;
298  // static bool accumRobotMovementIsValid = false;
299  bool SFhasValidObservations = false;
300  // A valid action?
301  if (actions != nullptr)
302  {
304  actions->getBestMovementEstimation(); // Find a robot movement
305  // estimation:
306  if (!act)
308  "Action list does not contain any CActionRobotMovement2D "
309  "derived object!");
310 
311  if (!m_accumRobotMovementIsValid) // Reset accum.
312  {
313  act->poseChange->getMean(
314  m_accumRobotMovement.rawOdometryIncrementReading);
315  m_accumRobotMovement.motionModelConfiguration =
316  act->motionModelConfiguration;
317  }
318  else
319  m_accumRobotMovement.rawOdometryIncrementReading =
320  m_accumRobotMovement.rawOdometryIncrementReading +
321  act->poseChange->getMeanVal();
322 
323  m_accumRobotMovementIsValid = true;
324  }
325 
326  if (sf != nullptr)
327  {
328  ASSERT_(m_poseParticles.m_particles.size() > 0);
329  SFhasValidObservations =
330  (*m_poseParticles.m_particles.begin())
331  .d->metricMaps.canComputeObservationsLikelihood(*sf);
332  }
333 
334  // All the needed things?
335  if (!m_accumRobotMovementIsValid || !SFhasValidObservations)
336  return; // Nothing we can do here...
337 
338  // OK, we have all we need, let's start!
339 
340  // Take the accum. actions as input:
341  CActionRobotMovement2D theResultingRobotMov;
342 
343  // Over
344  keep_max(
345  m_accumRobotMovement.motionModelConfiguration.gaussianModel
346  .minStdXY,
347  m_parent->m_options.MIN_ODOMETRY_STD_XY);
348  keep_max(
349  m_accumRobotMovement.motionModelConfiguration.gaussianModel
350  .minStdPHI,
351  m_parent->m_options.MIN_ODOMETRY_STD_PHI);
352 
353  theResultingRobotMov.computeFromOdometry(
354  m_accumRobotMovement.rawOdometryIncrementReading,
355  m_accumRobotMovement.motionModelConfiguration);
356 
357  const CActionRobotMovement2D* robotMovement = &theResultingRobotMov;
358 
359  m_accumRobotMovementIsValid =
360  false; // To reset odometry at next iteration!
361 
362  // ----------------------------------------------------------------------
363  // 0) Common part: Prepare m_poseParticles.m_particles "draw" and compute
364  // ----------------------------------------------------------------------
365  // Precompute a list of "random" samples from the movement model:
366  m_movementDraws.clear();
367 
368  // Fast pseudorandom generator of poses...
369  // m_movementDraws.resize(
370  // max(2000,(int)(PF_options.pfAuxFilterOptimal_MaximumSearchSamples *
371  // 5.6574) ) );
372  m_movementDraws.resize(
373  PF_options.pfAuxFilterOptimal_MaximumSearchSamples * M);
374  size_t size_movementDraws = m_movementDraws.size();
375  m_movementDrawsIdx = (unsigned int)floor(
376  getRandomGenerator().drawUniform(0.0f, ((float)size_movementDraws) - 0.01f));
377 
378  robotMovement->prepareFastDrawSingleSamples();
379  for (size_t i = 0; i < m_movementDraws.size(); i++)
380  robotMovement->fastDrawSingleSample(m_movementDraws[i]);
381 
382  m_pfAuxiliaryPFOptimal_estimatedProb.resize(M);
383  m_maxLikelihood.clear();
384  m_maxLikelihood.resize(M, 0);
385  m_movementDrawMaximumLikelihood.resize(M);
386 
387  // Prepare data for executing "fastDrawSample"
388  CTicTac tictac;
389  tictac.Tic();
390  using namespace std::placeholders;
391  m_poseParticles.prepareFastDrawSample(
392  PF_options, [&](size_t i)
393  {
394  return this->particlesEvaluator_AuxPFOptimal(PF_options, i, sf);
395  });
396  printf("[prepareFastDrawSample] Done in %.06f ms\n", tictac.Tac() * 1e3f);
397 
398 #if 0
399  printf("[prepareFastDrawSample] max (log) = %10.06f\n", math::maximum(m_poseParticles.m_pfAuxiliaryPFOptimal_estimatedProb) );
400  printf("[prepareFastDrawSample] max-mean (log) = %10.06f\n", -math::mean(m_poseParticles.m_pfAuxiliaryPFOptimal_estimatedProb) + math::maximum(m_poseParticles.m_pfAuxiliaryPFOptimal_estimatedProb) );
401  printf("[prepareFastDrawSample] max-min (log) = %10.06f\n", -math::minimum(m_poseParticles.m_pfAuxiliaryPFOptimal_estimatedProb) + math::maximum(m_poseParticles.m_pfAuxiliaryPFOptimal_estimatedProb) );
402 #endif
403 
404  // Now we have the vector "m_fastDrawProbability" filled out with:
405  // w[i]p(zt|z^{t-1},x^{[i],t-1},X)
406  // where X is the robot pose prior (as implemented in
407  // the aux. function "particlesEvaluator_AuxPFOptimal"),
408  // and also the "m_maxLikelihood" filled with the maximum lik. values.
409  StdVector_CPose2D newParticles;
410  vector<double> newParticlesWeight;
411  vector<size_t> newParticlesDerivedFromIdx;
412 
413  // We need the (aproximate) maximum likelihood value for each
414  // previous particle [i]:
415  //
416  // max{ p( z^t | data^[i], x_(t-1)^[i], u_(t) ) }
417  //
418  // CVectorDouble maxLikelihood(M, -1 );
419 
420  float MIN_ACCEPT_UNIF_DISTRIB = 0.00f;
421 
422  CPose2D movementDraw, newPose, oldPose;
423  double acceptanceProb, newPoseLikelihood, ratioLikLik;
424  unsigned int statsTrialsCount = 0, statsTrialsSuccess = 0;
425  std::vector<bool> maxLikMovementDrawHasBeenUsed(M, false);
426  unsigned int statsWarningsAccProbAboveOne = 0;
427  // double maxMeanLik = math::maximum(
428  // m_poseParticles.m_pfAuxiliaryPFOptimal_estimatedProb ); // For normalization
429  // purposes only
430 
431  ASSERT_(!PF_options.adaptiveSampleSize);
432 
433  // ----------------------------------------------------------------------
434  // 1) FIXED SAMPLE SIZE VERSION
435  // ----------------------------------------------------------------------
436  newParticles.resize(M);
437  newParticlesWeight.resize(M);
438  newParticlesDerivedFromIdx.resize(M);
439 
440  bool doResample = m_poseParticles.ESS() < 0.5;
441 
442  for (i = 0; i < M; i++)
443  {
444  // Generate a new particle:
445  // (a) Draw a "t-1" m_poseParticles.m_particles' index:
446  // ----------------------------------------------------------------
447  if (doResample)
448  k = m_poseParticles.fastDrawSample(
449  PF_options); // Based on weights of last step only!
450  else
451  k = i;
452 
453  oldPose = CPose2D(*getCurrentPose(k));
454 
455  // (b) Rejection-sampling: Draw a new robot pose from x[k],
456  // and accept it with probability p(zk|x) / maxLikelihood:
457  // ----------------------------------------------------------------
458  if (m_SFs.empty())
459  {
460  // The first robot pose in the SLAM execution: All m_poseParticles.m_particles start
461  // at the same point (this is the lowest bound of subsequent
462  // uncertainty):
463  movementDraw = CPose2D(0, 0, 0);
464  newPose = oldPose; // + movementDraw;
465  }
466  else
467  {
468  // Rejection-sampling:
469  do
470  {
471  // Draw new robot pose:
472  if (!maxLikMovementDrawHasBeenUsed[k])
473  {
474  // No! first take advantage of a good drawn value, but only
475  // once!!
476  maxLikMovementDrawHasBeenUsed[k] = true;
477  movementDraw = m_movementDrawMaximumLikelihood[k];
478 #if 0
479  cout << "Drawn pose (max. lik): " << movementDraw << endl;
480 #endif
481  }
482  else
483  {
484  // Draw new robot pose:
485  // robotMovement->drawSingleSample( movementDraw );
486  // robotMovement->fastDrawSingleSample( movementDraw );
487  movementDraw =
488  m_movementDraws[m_movementDrawsIdx++ % size_movementDraws];
489  }
490 
491  newPose.composeFrom(
492  oldPose,
493  movementDraw); // newPose = oldPose + movementDraw;
494 
495  // Compute acceptance probability:
496  newPoseLikelihood = auxiliarComputeObservationLikelihood(
497  PF_options, k, sf, &newPose);
498  ratioLikLik = exp(newPoseLikelihood - m_maxLikelihood[k]);
499  acceptanceProb = min(1.0, ratioLikLik);
500 
501  if (ratioLikLik > 1)
502  {
503  if (ratioLikLik > 1.5)
504  {
505  statsWarningsAccProbAboveOne++;
506  // DEBUG
507  // printf("[pfAuxiliaryPFOptimal] Warning!!
508  // p(z|x)/p(z|x*)=%f\n",ratioLikLik);
509  }
510  m_maxLikelihood[k] = newPoseLikelihood; // :'-( !!!
511  acceptanceProb = 0; // Keep searching!!
512  }
513 
514  statsTrialsCount++; // Stats
515 
516  } while (acceptanceProb < getRandomGenerator().drawUniform(
517  MIN_ACCEPT_UNIF_DISTRIB, 0.999f));
518 
519  statsTrialsSuccess++; // Stats:
520  }
521 
522  // Insert the new particle!:
523  newParticles[i] = newPose;
524 
525  // And its weight:
526  double weightFact =
527  m_pfAuxiliaryPFOptimal_estimatedProb[k] * PF_options.powFactor;
528 
529  // Add to historic record of log_w weights:
530  m_log_w_metric_history.resize(M);
531  m_log_w_metric_history[i][currentPoseID] += weightFact;
532 
533  if (doResample)
534  newParticlesWeight[i] = 0;
535  else
536  newParticlesWeight[i] = m_poseParticles.m_particles[k].log_w + weightFact;
537 
538  // and its heritance:
539  newParticlesDerivedFromIdx[i] = (unsigned int)k;
540 
541  } // for i
542 
543  // ---------------------------------------------------------------------------------
544  // Substitute old by new particle set:
545  // Old are in "m_poseParticles.m_particles"
546  // New are in "newParticles",
547  // "newParticlesWeight","newParticlesDerivedFromIdx"
548  // ---------------------------------------------------------------------------------
549  N = newParticles.size();
550  CLocalMetricHypothesis::CParticleList newParticlesArray(N);
552 
553  // For efficiency, just copy the "CRBPFParticleData" from the old particle
554  // into the
555  // new one, but this can be done only once:
556  std::vector<bool> oldParticleAlreadyCopied(m_poseParticles.m_particles.size(), false);
557  CLSLAMParticleData* newPartData;
558 
559  for (newPartIt = newParticlesArray.begin(), i = 0;
560  newPartIt != newParticlesArray.end(); newPartIt++, i++)
561  {
562  // The weight:
563  newPartIt->log_w = newParticlesWeight[i];
564 
565  // The data (CRBPFParticleData):
566  if (!oldParticleAlreadyCopied[newParticlesDerivedFromIdx[i]])
567  {
568  // The first copy of this old particle:
569  newPartData =
570  m_poseParticles.m_particles[newParticlesDerivedFromIdx[i]].d.release();
571  oldParticleAlreadyCopied[newParticlesDerivedFromIdx[i]] = true;
572  }
573  else
574  {
575  // Make a copy:
576  newPartData = new CLSLAMParticleData(
577  *m_poseParticles.m_particles[newParticlesDerivedFromIdx[i]].d);
578  }
579 
580  newPartIt->d.reset(newPartData);
581  } // end for "newPartIt"
582 
583  // Now add the new robot pose to the paths: (this MUST be done after the
584  // above loop, separately):
585  for (newPartIt = newParticlesArray.begin(), i = 0;
586  newPartIt != newParticlesArray.end(); newPartIt++, i++)
587  newPartIt->d->robotPoses[m_currentRobotPose] =
588  CPose3D(newParticles[i]);
589 
590  // Free those old m_poseParticles.m_particles not being copied into the new ones:
591  for (i = 0; i < m_poseParticles.m_particles.size(); i++)
592  {
593  m_poseParticles.m_particles[i].d.reset();
594  }
595 
596  // Copy into "m_poseParticles.m_particles":
597  m_poseParticles.m_particles.resize(newParticlesArray.size());
598  for (newPartIt = newParticlesArray.begin(),
599  trgPartIt = m_poseParticles.m_particles.begin();
600  newPartIt != newParticlesArray.end(); newPartIt++, trgPartIt++)
601  {
602  trgPartIt->log_w = newPartIt->log_w;
603  trgPartIt->d.move_from(newPartIt->d);
604  }
605 
606  // Free buffers:
607  newParticles.clear();
608  newParticlesArray.clear();
609  newParticlesWeight.clear();
610  newParticlesDerivedFromIdx.clear();
611 
612  double out_max_log_w;
613  m_poseParticles.normalizeWeights(&out_max_log_w); // Normalize weights:
614  m_log_w += out_max_log_w;
615 
616 #if 0
617  printf("[REJ-SAMP.RATIO: \t%.03f%% \t %u out of %u with P(acep)>1]\n\n",
618  100.0f*statsTrialsSuccess / (float)(max(1u,statsTrialsCount)),
619  statsWarningsAccProbAboveOne,
620  statsTrialsCount
621  );
622 #endif
623 
624  MRPT_END
625 }
626 
627 /*---------------------------------------------------------------
628  particlesEvaluator_AuxPFOptimal
629  ---------------------------------------------------------------*/
631  const bayes::CParticleFilter::TParticleFilterOptions& PF_options, size_t index,
632  const CSensoryFrame* observation)
633 {
634  MRPT_START
635 
636  // Compute the quantity:
637  // w[i]p(zt|z^{t-1},x^{[i],t-1})
638  // As the Monte-Carlo approximation of the
639  // integral over all posible $x_t$.
640 
641  // Take the previous particle weight:
642  // --------------------------------------------
643  double indivLik, maxLik = -std::numeric_limits<double>::max();
644  size_t maxLikDraw = 0;
645  size_t N;
646  size_t nDraws = m_movementDraws.size();
647 
648  ASSERT_(nDraws > 1);
649 
650  // , perform a Monte-Carlo approximation:
651  // --------------------------------------------
653  ASSERT_(N > 1);
654 
655  CPose2D oldPose(*getCurrentPose(index));
656  // CPose2D drawnSample;
657  mrpt::math::CVectorDouble vectLiks(
658  N, 0); // The vector with the individual log-likelihoods.
659 
660  for (size_t q = 0; q < N; q++)
661  {
662  CPose2D x_predict(
663  oldPose +
664  m_movementDraws[(++m_movementDrawsIdx) % nDraws]);
665 
666  // Estimate the mean...
668  PF_options, index, observation, &x_predict);
669 
670  MRPT_CHECK_NORMAL_NUMBER(indivLik);
671  vectLiks[q] = indivLik;
672 
673  // and the maximum value:
674  if (indivLik > maxLik)
675  {
676  maxLikDraw = m_movementDrawsIdx % nDraws;
677  maxLik = indivLik;
678  }
679  }
680 
681  // This is done to avoid floating point overflow!!
682  double maxLogLik = math::maximum(vectLiks);
683  vectLiks.array() -=
684  maxLogLik; // Maximum log-lik = 0 (max linear likelihood=1)
685 
686  // average_lik = \sum(e^liks) * e^maxLik / N
687  // log( average_lik ) = log( \sum(e^liks) ) + maxLik - log( N )
688  double avrgLogLik =
689  log(vectLiks.array().exp().sum()) + maxLogLik - log((double)N);
690 
691  // Save into the object:
693  avrgLogLik; // log( accum / N );
694  m_maxLikelihood[index] = maxLik;
696  m_movementDraws[maxLikDraw];
697 
698  // and compute the resulting probability of this particle:
699  // ------------------------------------------------------------
700  // if (myObj->m_adaptiveSampleSize)
701  // return myObj->m_poseParticles.m_particles[index].w *
702  // myObj->m_pfAuxiliaryPFOptimal_estimatedProb[index];
703  // else return myObj->m_poseParticles.m_particles[index].w;
704 
705  double ret = m_poseParticles.m_particles[index].log_w +
707 
709 
710  return ret;
711 
712  MRPT_END
713 }
714 
715 /*---------------------------------------------------------------
716  auxiliarComputeObservationLikelihood
717  ---------------------------------------------------------------*/
720  size_t particleIndexForMap,
721  const CSensoryFrame* observation, const CPose2D* x)
722 {
723  MRPT_UNUSED_PARAM(PF_options);
724  CMultiMetricMap* map = const_cast<CMultiMetricMap*>(
725  &m_poseParticles.m_particles[particleIndexForMap].d->metricMaps);
726 
727  return map->computeObservationsLikelihood(*observation, *x);
728 }
729 
730 /*---------------------------------------------------------------
731  dumpToStdOut
732  ---------------------------------------------------------------*/
734 {
736 
737  std::cout << "x = [";
738  for (it = x.begin(); it != x.end(); it++) std::cout << *it << " ";
739  std::cout << "]" << std::endl;
740 
741  std::cout << "y = [";
742  for (it = y.begin(); it != y.end(); it++) std::cout << *it << " ";
743  std::cout << "]" << std::endl;
744 
745  std::cout << "Phi = [";
746  for (it = phi.begin(); it != phi.end(); it++) std::cout << *it << " ";
747  std::cout << "]" << std::endl;
748 }
749 
750 /*---------------------------------------------------------------
751  loadTPathBinFromPath
752  ---------------------------------------------------------------*/
755  CPose2D* newPose)
756 {
757  size_t lenBinPath;
758 
759  if (path != nullptr)
760  lenBinPath = path->size();
761  else
762  lenBinPath = 0;
763 
765  vector_int::iterator itX, itY, itPHI;
766 
767  // Set the output bin dimensionality:
768  outBin.x.resize(lenBinPath + (newPose != nullptr ? 1 : 0));
769  outBin.y.resize(lenBinPath + (newPose != nullptr ? 1 : 0));
770  outBin.phi.resize(lenBinPath + (newPose != nullptr ? 1 : 0));
771 
772  // Is a path provided??
773  if (path != nullptr)
774  {
775  // Fill the bin data:
776  for (itSrc = path->begin(), itX = outBin.x.begin(),
777  itY = outBin.y.begin(), itPHI = outBin.phi.begin();
778  itSrc != path->end(); itSrc++, itX++, itY++, itPHI++)
779  {
780  *itX = (int)round(
781  itSrc->second.x() /
782  m_parent->m_options.KLD_params.KLD_binSize_XY);
783  *itY = (int)round(
784  itSrc->second.y() /
785  m_parent->m_options.KLD_params.KLD_binSize_XY);
786  *itPHI = (int)round(
787  itSrc->second.yaw() /
788  m_parent->m_options.KLD_params.KLD_binSize_PHI);
789  } // end-for build path bin
790  }
791 
792  // Is a newPose provided??
793  if (newPose != nullptr)
794  {
795  // And append the last pose: the new one:
796  outBin.x[lenBinPath] = (int)round(
797  newPose->x() / m_parent->m_options.KLD_params.KLD_binSize_XY);
798  outBin.y[lenBinPath] = (int)round(
799  newPose->y() / m_parent->m_options.KLD_params.KLD_binSize_XY);
800  outBin.phi[lenBinPath] = (int)round(
801  newPose->phi() / m_parent->m_options.KLD_params.KLD_binSize_PHI);
802  }
803 }
804 
805 /*---------------------------------------------------------------
806  findTPathBinIntoSet
807  ---------------------------------------------------------------*/
809  CLSLAM_RBPF_2DLASER::TPathBin& desiredBin,
810  std::deque<CLSLAM_RBPF_2DLASER::TPathBin>& theSet)
811 {
812  // it = pathBins.find( p ); <---- This doesn't work!!!
813  // TODO: A more efficient search algorithm here!!
815  int ret;
816 
817  for (it = theSet.begin(), ret = 0; it != theSet.end(); it++, ret++)
818  if ((it->x == desiredBin.x) && (it->y == desiredBin.y) &&
819  (it->phi == desiredBin.phi))
820  return ret;
821 
822  // Not found!
823  return -1;
824 }
825 
826 /** The PF algorithm implementation for "optimal sampling" approximated with
827  * scan matching (Stachniss method)
828  */
829 template <>
830 void CLocalMetricHypothesis::prediction_and_update<LSLAMOptimalProposal>(
831  const mrpt::obs::CActionCollection* actions,
832  const mrpt::obs::CSensoryFrame* sf,
834 {
835  MRPT_START
836 
837  CTicTac tictac;
838 
839  // Get the current robot pose estimation:
840  TPoseID currentPoseID = m_currentRobotPose;
841 
842  // ----------------------------------------------------------------------
843  // We can execute optimal PF only when we have both, an action, and
844  // a valid observation from which to compute the likelihood:
845  // Accumulate odometry/actions until we have a valid observation, then
846  // process them simultaneously.
847  // ----------------------------------------------------------------------
848  bool SFhasValidObservations = false;
849  // A valid action?
850  if (actions != nullptr)
851  {
853  actions->getBestMovementEstimation(); // Find a robot movement
854  // estimation:
855  if (!act)
857  "Action list does not contain any CActionRobotMovement2D "
858  "derived object!");
859 
860  if (!m_accumRobotMovementIsValid) // Reset accum.
861  {
862  act->poseChange->getMean(
863  m_accumRobotMovement.rawOdometryIncrementReading);
864  m_accumRobotMovement.motionModelConfiguration =
865  act->motionModelConfiguration;
866  }
867  else
868  m_accumRobotMovement.rawOdometryIncrementReading =
869  m_accumRobotMovement.rawOdometryIncrementReading +
870  act->poseChange->getMeanVal();
871 
872  m_accumRobotMovementIsValid = true;
873  }
874 
875  if (sf != nullptr)
876  {
877  ASSERT_(m_poseParticles.m_particles.size() > 0);
878  SFhasValidObservations =
879  (*m_poseParticles.m_particles.begin())
880  .d->metricMaps.canComputeObservationsLikelihood(*sf);
881  }
882 
883  // All the needed things?
884  if (!m_accumRobotMovementIsValid || !SFhasValidObservations)
885  return; // Nothing we can do here...
886  ASSERT_(sf != nullptr);
887  ASSERT_(!PF_options.adaptiveSampleSize);
888 
889  // OK, we have all we need, let's start!
890 
891  // The odometry-based increment since last step is
892  // in: m_accumRobotMovement.rawOdometryIncrementReading
893  const CPose2D initialPoseEstimation =
894  m_accumRobotMovement.rawOdometryIncrementReading;
895  m_accumRobotMovementIsValid =
896  false; // To reset odometry at next iteration!
897 
898  // ----------------------------------------------------------------------
899  // 1) FIXED SAMPLE SIZE VERSION
900  // ----------------------------------------------------------------------
901 
902  // ICP used if "pfOptimalProposal_mapSelection" = 0 or 1
903  CICP icp;
904  CICP::TReturnInfo icpInfo;
905 
906  // ICP options
907  // ------------------------------
908  icp.options.maxIterations = 80;
909  icp.options.thresholdDist = 0.50f;
910  icp.options.thresholdAng = DEG2RAD(20);
911  icp.options.smallestThresholdDist = 0.05f;
912  icp.options.ALFA = 0.5f;
914  icp.options.doRANSAC = false;
915 
916  // Build the map of points to align:
917  CSimplePointsMap localMapPoints;
918 
919  ASSERT_(m_poseParticles.m_particles[0].d->metricMaps.m_gridMaps.size() > 0);
920  // float minDistBetweenPointsInLocalMaps = 0.02f; //3.0f *
921  // m_poseParticles.m_particles[0].d->metricMaps.m_gridMaps[0]->getResolution();
922 
923  // Build local map:
924  localMapPoints.clear();
925  localMapPoints.insertionOptions.minDistBetweenLaserPoints = 0.02f;
926  sf->insertObservationsInto(&localMapPoints);
927 
928  // Process the particles
929  const size_t M = m_poseParticles.m_particles.size();
930  m_log_w_metric_history.resize(M);
931 
932  for (size_t i = 0; i < M; i++)
933  {
934  CLocalMetricHypothesis::CParticleData& part = m_poseParticles.m_particles[i];
935  CPose3D* part_pose = getCurrentPose(i);
936 
937  if (m_SFs.empty())
938  {
939  // The first robot pose in the SLAM execution: All m_poseParticles.m_particles start
940  // at the same point (this is the lowest bound of subsequent
941  // uncertainty):
942  // New pose = old pose.
943  // part_pose: Unmodified
944  }
945  else
946  {
947  // ICP and add noise:
948  CPosePDFGaussian icpEstimation;
949 
950  // Select map to use with ICP:
951  CMetricMap* mapalign;
952 
953  if (!part.d->metricMaps.m_pointsMaps.empty())
954  mapalign = part.d->metricMaps.m_pointsMaps[0].get();
955  else if (!part.d->metricMaps.m_gridMaps.empty())
956  mapalign = part.d->metricMaps.m_gridMaps[0].get();
957  else
959  "There is no point or grid map. At least one needed for "
960  "ICP.");
961 
962  // Use ICP to align to each particle's map:
963  CPosePDF::Ptr alignEst = icp.Align(
964  mapalign, &localMapPoints, initialPoseEstimation, nullptr,
965  &icpInfo);
966 
967  icpEstimation.copyFrom(*alignEst);
968 
969 #if 0
970  // HACK:
971  CPose3D Ap = finalEstimatedPoseGauss.mean - ith_last_pose;
972  double Ap_dist = Ap.norm();
973  finalEstimatedPoseGauss.cov.zeros();
974  finalEstimatedPoseGauss.cov(0,0) = square( fabs(Ap_dist)*0.01 );
975  finalEstimatedPoseGauss.cov(1,1) = square( fabs(Ap_dist)*0.01 );
976  finalEstimatedPoseGauss.cov(2,2) = square( fabs(Ap.yaw())*0.02 );
977 #endif
978 
979  // Generate gaussian-distributed 2D-pose increments according to
980  // "finalEstimatedPoseGauss":
981  // -------------------------------------------------------------------------------------------
982  // Set the gaussian pose:
983  CPose3DPDFGaussian finalEstimatedPoseGauss(icpEstimation);
984 
985  CPose3D noisy_increment;
986  finalEstimatedPoseGauss.drawSingleSample(noisy_increment);
987 
988  CPose3D new_pose;
989  new_pose.composeFrom(*part_pose, noisy_increment);
990 
991  CPose2D new_pose2d = CPose2D(new_pose);
992 
993  // Add the pose to the path:
994  part.d->robotPoses[m_currentRobotPose] = new_pose;
995 
996  // Update the weight:
997  // ---------------------------------------------------------------------------
998  const double log_lik =
999  PF_options.powFactor * auxiliarComputeObservationLikelihood(
1000  PF_options, i, sf, &new_pose2d);
1001 
1002  part.log_w += log_lik;
1003 
1004  // Add to historic record of log_w weights:
1005  m_log_w_metric_history[i][currentPoseID] += log_lik;
1006 
1007  } // end else we can do ICP
1008 
1009  } // end for each particle i
1010 
1011  // Accumulate the log likelihood of this LMH as a whole:
1012  double out_max_log_w;
1013  m_poseParticles.normalizeWeights(&out_max_log_w); // Normalize weights:
1014  m_log_w += out_max_log_w;
1015 
1016  printf("[CLSLAM_RBPF_2DLASER] Overall likelihood = %.2e\n", out_max_log_w);
1017  printf("[CLSLAM_RBPF_2DLASER] Done in %.03fms\n", 1e3 * tictac.Tac());
1018 
1019  MRPT_END
1020 }
1021 } // namespace hmtslam
1022 } // namespace mrpt
void clear()
Erase all the contents of the map.
Definition: CMetricMap.cpp:31
A namespace of pseudo-random numbers genrators of diferent distributions.
double drawUniform(const double Min, const double Max)
Generate a uniformly distributed pseudo-random number using the MT19937 algorithm, scaled to the selected range.
double x() const
Common members of all points & poses classes.
Definition: CPoseOrPoint.h:135
std::map< TPoseID, CHMHMapNode::TNodeID > m_nodeIDmemberships
The hybrid map node membership for each robot pose.
void copyFrom(const CPosePDF &o) override
Copy operator, translating if necesary (for example, between particles and gaussian representations) ...
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
#define min(a, b)
THypothesisID m_ID
The unique ID of the hypothesis (Used for accessing mrpt::slam::CHierarchicalMHMap).
double distanceTo(const CPoseOrPoint< OTHERCLASS > &b) const
Returns the Euclidean distance to another pose/point:
Definition: CPoseOrPoint.h:206
float thresholdDist
Initial threshold distance for two points to become a correspondence.
Definition: CICP.h:122
unsigned int pfAuxFilterOptimal_MaximumSearchSamples
In the algorithm "CParticleFilter::pfAuxiliaryPFOptimal" (and in "CParticleFilter::pfAuxiliaryPFStand...
Classes related to the implementation of Hybrid Metric Topological (HMT) SLAM.
static TPoseID generatePoseID()
Generates a new and unique pose ID.
mrpt::poses::CPosePDF::Ptr Align(const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPose2D &grossEst, float *runningTime=nullptr, void *info=nullptr)
The method for aligning a pair of metric maps, aligning only 2D + orientation.
Several implementations of ICP (Iterative closest point) algorithms for aligning two point maps or a ...
Definition: CICP.h:67
double particlesEvaluator_AuxPFOptimal(const mrpt::bayes::CParticleFilter::TParticleFilterOptions &PF_options, size_t index, const mrpt::obs::CSensoryFrame *observation)
Auxiliary function used in "prediction_and_update_pfAuxiliaryPFOptimal".
#define MRPT_CHECK_NORMAL_NUMBER(val)
The namespace for Bayesian filtering algorithm: different particle filters and Kalman filter algorith...
std::vector< double > m_maxLikelihood
Auxiliary variable used in the "pfAuxiliaryPFOptimal" algorithm.
#define THROW_EXCEPTION(msg)
GLdouble GLdouble GLdouble GLdouble q
Definition: glext.h:3721
Scalar * iterator
Definition: eigen_plugins.h:26
This file implements several operations that operate element-wise on individual or pairs of container...
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
Definition: eigen_frwds.h:42
double yaw() const
Get the YAW angle (in radians)
Definition: CPose3D.h:533
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. ...
void computeFromOdometry(const mrpt::poses::CPose2D &odometryIncrement, const TMotionModelOptions &options)
Computes the PDF of the pose increment from an odometry reading and according to the given motion mod...
STL namespace.
const Scalar * const_iterator
Definition: eigen_plugins.h:27
uint64_t TPoseID
An integer number uniquely identifying each robot pose stored in HMT-SLAM.
int findTPathBinIntoSet(TPathBin &desiredBin, std::deque< TPathBin > &theSet)
Checks if a given "TPathBin" element is already into a set of them, and return its index (first one i...
float ALFA
The scale factor for threshold everytime convergence is achieved.
Definition: CICP.h:124
Statistics for being returned from the "execute" method.
Virtual base for local SLAM methods, used in mrpt::slam::CHMTSLAM.
Definition: CHMTSLAM.h:511
TConfigParams options
The options employed by the ICP align.
Definition: CICP.h:185
void Tic()
Starts the stopwatch.
Definition: CTicTac.cpp:82
An implementation of Hybrid Metric Topological SLAM (HMT-SLAM).
Definition: CHMTSLAM.h:65
void executeOn(mrpt::bayes::CParticleFilter &pf, const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, mrpt::bayes::CParticleFilter::TParticleFilterStats *stats, mrpt::bayes::CParticleFilter::TParticleFilterAlgorithm PF_algorithm)
Declares a class for storing a collection of robot actions.
mrpt::utils::safe_ptr< CHMTSLAM > m_parent
Definition: CHMTSLAM.h:516
#define MRPT_TODO(x)
T square(const T x)
Inline function for the square of a number.
Definition: bits.h:55
mrpt::poses::StdVector_CPose2D m_movementDraws
Auxiliary variable used in the "pfAuxiliaryPFOptimal" algorithm.
CONTAINER::Scalar minimum(const CONTAINER &v)
Represents a probabilistic 2D movement of the robot mobile base.
CParticleList m_particles
The array of particles.
std::shared_ptr< CPosePDF > Ptr
Definition: CPosePDF.h:44
mrpt::aligned_containers< TPoseID, mrpt::poses::CPose3D >::map_t TMapPoseID2Pose3D
TPoseIDList m_posesPendingAddPartitioner
The list of poseIDs waiting to be added to the graph partitioner, what happens in the LSLAM thread ma...
Declares a class that represents a Probability Density function (PDF) of a 2D pose ...
#define MRPT_END
std::shared_ptr< CActionRobotMovement2D > Ptr
#define MRPT_UNUSED_PARAM(a)
Can be used to avoid "not used parameters" warnings from the compiler.
void composeFrom(const CPose3D &A, const CPose3D &B)
Makes "this = A (+) B"; this method is slightly more efficient than "this= A + B;" since it avoids th...
Definition: CPose3D.cpp:639
void fastDrawSingleSample(mrpt::poses::CPose2D &outSample) const
Faster version than "drawSingleSample", but requires a previous call to "prepareFastDrawSingleSamples...
double norm() const
Returns the euclidean norm of vector: .
Definition: CPoseOrPoint.h:252
#define POSEID_INVALID
mrpt::bayes::CParticleFilterData< CLSLAMParticleData >::CParticleList CParticleList
GLuint index
Definition: glext.h:4054
double computeObservationsLikelihood(const mrpt::obs::CSensoryFrame &sf, const mrpt::poses::CPose2D &takenFrom)
Returns the sum of the log-likelihoods of each individual observation within a mrpt::obs::CSensoryFra...
Definition: CMetricMap.cpp:67
unsigned int maxIterations
Maximum number of iterations to run.
Definition: CICP.h:109
This class implements a high-performance stopwatch.
Definition: CTicTac.h:23
static void resize(const size_t n)
Definition: CPose3D.h:769
This namespace contains representation of robot actions and observations.
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
Definition: CSensoryFrame.h:54
mrpt::math::CVectorDouble m_pfAuxiliaryPFOptimal_estimatedProb
Auxiliary variable used in the "pfAuxiliaryPFOptimal" algorithm.
std::shared_ptr< CSensoryFrame > Ptr
Definition: CSensoryFrame.h:56
unsigned int m_movementDrawsIdx
Auxiliary variable used in the "pfAuxiliaryPFOptimal" algorithm.
bool doRANSAC
Perform a RANSAC step, mrpt::tfest::se2_l2_robust(), after the ICP convergence, to obtain a better es...
Definition: CICP.h:140
This class acts as a common interface to the different interfaces (see CParticleFilter::TParticleFilt...
#define DEG2RAD
This class is used in HMT-SLAM to represent each of the Local Metric Hypotheses (LMHs).
bool onlyClosestCorrespondences
The usual approach: to consider only the closest correspondence for each local point (Default to true...
Definition: CICP.h:99
CONTAINER::Scalar maximum(const CONTAINER &v)
T wrapToPi(T a)
Modifies the given angle to translate it into the ]-pi,pi] range.
Definition: wrap2pi.h:53
void keep_max(T &var, const K test_val)
If the second argument is above the first one, set the first argument to this higher value...
Definition: bits.h:227
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
Definition: CPoint.h:17
std::map< TPoseID, mrpt::obs::CSensoryFrame > m_SFs
The SF gathered at each robot pose.
Auxiliary class used in mrpt::slam::CLocalMetricHypothesis for HMT-SLAM; this class keeps the data re...
void prepareFastDrawSingleSamples() const
Call this before calling a high number of times "fastDrawSingleSample", which is much faster than "dr...
#define MRPT_START
void executeOn(PARTICLEFILTERCAPABLE &obj, const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, TParticleFilterStats *stats=nullptr)
Executes a complete prediction + update step of the selected particle filtering algorithm.
mrpt::poses::StdVector_CPose2D m_movementDrawMaximumLikelihood
Auxiliary variable used in the "pfAuxiliaryPFOptimal" algorithm.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
void loadTPathBinFromPath(TPathBin &outBin, TMapPoseID2Pose3D *path=nullptr, mrpt::poses::CPose2D *newPose=nullptr)
Fills out a "TPathBin" variable, given a path hypotesis and (if not set to nullptr) a new pose append...
double auxiliarComputeObservationLikelihood(const mrpt::bayes::CParticleFilter::TParticleFilterOptions &PF_options, size_t particleIndexForMap, const mrpt::obs::CSensoryFrame *observation, const mrpt::poses::CPose2D *x)
Auxiliary function that evaluates the likelihood of an observation, given a robot pose...
void processOneLMH(CLocalMetricHypothesis *LMH, const mrpt::obs::CActionCollection::Ptr &act, const mrpt::obs::CSensoryFrame::Ptr &sf)
Main entry point from HMT-SLAM: process some actions & observations.
std::shared_ptr< CActionCollection > Ptr
TParticleFilterAlgorithm
Defines different types of particle filter algorithms.
A template class for holding a the data and the weight of a particle.
void getMeans(TMapPoseID2Pose3D &outList) const
Returns the mean of each robot pose in this LMH, as computed from the set of particles.
Declares a virtual base class for all metric maps storage classes.
Definition: CMetricMap.h:55
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
Definition: CPose2D.h:40
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:88
float smallestThresholdDist
The size for threshold such that iterations will stop, since it is considered precise enough...
Definition: CICP.h:127
const double & phi() const
Get the phi angle of the 2D pose (in radians)
Definition: CPose2D.h:91
The configuration of a particle filter.
static void resize(const size_t n)
Definition: CPose2D.h:347
void composeFrom(const CPose2D &A, const CPose2D &B)
Makes .
Definition: CPose2D.cpp:124
double log_w
The (logarithmic) weight value for this particle.
The ICP algorithm return information.
Definition: CICP.h:195
mrpt::utils::copy_ptr< T > d
The data associated with this particle.
double mean(const CONTAINER &v)
Computes the mean value of a vector.
double Tac()
Stops the stopwatch.
Definition: CTicTac.cpp:97
#define ASSERT_(f)
#define NODE_ANNOTATION_REF_POSEID
Declares a class that represents a Probability Density function (PDF) of a 3D pose ...
int round(const T value)
Returns the closer integer (int) to x.
Definition: round.h:25
GLenum GLint GLint y
Definition: glext.h:3538
TInsertionOptions insertionOptions
The options used when inserting observations in the map.
Definition: CPointsMap.h:256
std::shared_ptr< CHMHMapNode > Ptr
Definition: CHMHMapNode.h:42
GLenum GLint x
Definition: glext.h:3538
This class stores any customizable set of metric maps.
bool m_insertNewRobotPose
For use within PF callback methods.
Definition: CHMTSLAM.h:586
CLSLAMParticleDataParticles m_poseParticles
CParticleFilter::TParticleFilterOptions m_options
The options to be used in the PF, must be set before executing any step of the particle filter...
CRandomGenerator & getRandomGenerator()
A static instance of a CRandomGenerator class, for use in single-thread applications.
void drawSingleSample(CPose3D &outPart) const override
Draws a single sample from the distribution.
const mrpt::poses::CPose3D * getCurrentPose(const size_t &particleIdx) const
Returns the i&#39;th particle hypothesis for the current robot pose.
TParticleFilterAlgorithm PF_algorithm
The PF algorithm to use (default=pfStandardProposal) See TParticleFilterAlgorithm for the posibilitie...
mrpt::aligned_containers< CPose2D >::vector_t StdVector_CPose2D
Eigen aligment-compatible container.
Definition: CPose2D.h:374
float minDistBetweenLaserPoints
The minimum distance between points (in 3D): If two points are too close, one of them is not inserted...
Definition: CPointsMap.h:217
TPoseID m_currentRobotPose
The current robot pose (its global unique ID) for this hypothesis.



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019