42 class PARTICLE_TYPE,
class MYSELF,
44 template <
class BINTYPE>
50 auto* me =
static_cast<MYSELF*
>(
this);
52 if (actions !=
nullptr)
58 if (m_accumRobotMovement3DIsValid)
61 ASSERT_(robotMovement2D->poseChange);
62 if (!m_accumRobotMovement2DIsValid)
64 robotMovement2D->poseChange->getMean(
65 m_accumRobotMovement2D.rawOdometryIncrementReading);
66 m_accumRobotMovement2D.motionModelConfiguration =
67 robotMovement2D->motionModelConfiguration;
70 m_accumRobotMovement2D.rawOdometryIncrementReading +=
71 robotMovement2D->poseChange->getMeanVal();
73 m_accumRobotMovement2DIsValid =
true;
81 if (m_accumRobotMovement2DIsValid)
84 if (!m_accumRobotMovement3DIsValid)
85 m_accumRobotMovement3D = robotMovement3D->poseChange;
87 m_accumRobotMovement3D += robotMovement3D->poseChange;
91 m_accumRobotMovement3DIsValid =
true;
98 const bool SFhasValidObservations =
99 (sf ==
nullptr) ?
false 100 : PF_SLAM_implementation_doWeHaveValidObservations(
101 me->m_particles, sf);
104 if (!((m_accumRobotMovement2DIsValid || m_accumRobotMovement3DIsValid) &&
105 SFhasValidObservations))
110 if (m_accumRobotMovement3DIsValid)
112 m_movementDrawer.setPosePDF(
113 m_accumRobotMovement3D);
114 m_accumRobotMovement3DIsValid =
121 m_accumRobotMovement2D.rawOdometryIncrementReading,
122 m_accumRobotMovement2D.motionModelConfiguration);
125 m_movementDrawer.setPosePDF(
127 m_accumRobotMovement2DIsValid =
151 class PARTICLE_TYPE,
class MYSELF,
153 template <
class BINTYPE>
163 PF_SLAM_implementation_pfAuxiliaryPFStandardAndOptimal<BINTYPE>(
164 actions, sf, PF_options, KLD_options,
true );
175 class PARTICLE_TYPE,
class MYSELF,
177 template <
class BINTYPE>
186 using TSetStateSpaceBins = std::set<BINTYPE, typename BINTYPE::lt_operator>;
188 auto* me =
static_cast<MYSELF*
>(
this);
208 ASSERT_(robotMovement2D->poseChange);
209 m_movementDrawer.setPosePDF(*robotMovement2D->poseChange);
211 robotMovement2D->poseChange->getMeanVal());
220 m_movementDrawer.setPosePDF(robotMovement3D->poseChange);
221 robotMovement3D->poseChange.getMean(motionModelMeanIncr);
226 "Action list does not contain any " 227 "CActionRobotMovement2D or CActionRobotMovement3D " 236 const size_t M = me->m_particles.size();
241 for (
size_t i = 0; i < M; i++)
245 m_movementDrawer.drawSample(incrPose);
256 PF_SLAM_implementation_custom_update_particle_with_new_pose(
257 me->m_particles[i].d.get(), finalPose.
asTPose());
261 PF_SLAM_implementation_custom_update_particle_with_new_pose(
262 &me->m_particles[i].d, finalPose.
asTPose());
274 TSetStateSpaceBins stateSpaceBins;
277 const double delta_1 = 1.0 - KLD_options.
KLD_delta;
278 const double epsilon_1 = 0.5 / KLD_options.
KLD_epsilon;
281 me->prepareFastDrawSample(PF_options);
284 std::vector<mrpt::math::TPose3D> newParticles;
285 std::vector<double> newParticlesWeight;
286 std::vector<size_t> newParticlesDerivedFromIdx;
294 m_movementDrawer.drawSample(increment_i);
297 const size_t drawn_idx = me->fastDrawSample(PF_options);
302 getLastPose(drawn_idx, pose_is_valid)) +
307 newParticles.push_back(newPose_s);
308 newParticlesWeight.push_back(0);
309 newParticlesDerivedFromIdx.push_back(drawn_idx);
313 const PARTICLE_TYPE* part;
316 part = me->m_particles[drawn_idx].d.get();
318 part = &me->m_particles[drawn_idx].d;
321 KLF_loadBinFromParticle<PARTICLE_TYPE, BINTYPE>(
322 p, KLD_options, part, &newPose_s);
324 if (stateSpaceBins.find(p) == stateSpaceBins.end())
328 stateSpaceBins.insert(p);
331 size_t K = stateSpaceBins.size();
341 N = newParticles.size();
351 this->PF_SLAM_implementation_replaceByNewParticleSet(
352 me->m_particles, newParticles, newParticlesWeight,
353 newParticlesDerivedFromIdx);
360 const size_t M = me->m_particles.size();
364 for (
size_t i = 0; i < M; i++)
368 getLastPose(i, pose_is_valid);
370 const double obs_log_lik =
371 PF_SLAM_computeObservationLikelihoodForParticle(
372 PF_options, i, *sf, partPose2);
373 ASSERT_(!std::isnan(obs_log_lik) && std::isfinite(obs_log_lik));
374 me->m_particles[i].log_w += obs_log_lik * PF_options.
powFactor;
400 class PARTICLE_TYPE,
class MYSELF,
402 template <
class BINTYPE>
412 PF_SLAM_implementation_pfAuxiliaryPFStandardAndOptimal<BINTYPE>(
413 actions, sf, PF_options, KLD_options,
false );
420 class PARTICLE_TYPE,
class MYSELF,
422 template <
class BINTYPE>
427 const void* action,
const void* observation)
434 const auto* me =
static_cast<const MYSELF*
>(obj);
440 double indivLik, maxLik = -1e300;
451 for (
size_t q = 0; q < N; q++)
453 me->m_movementDrawer.drawSample(drawnSample);
457 indivLik = me->PF_SLAM_computeObservationLikelihoodForParticle(
459 *static_cast<const mrpt::obs::CSensoryFrame*>(observation),
463 vectLiks[q] = indivLik;
464 if (indivLik > maxLik)
466 maxLikDraw = drawnSample;
477 me->m_pfAuxiliaryPFOptimal_estimatedProb[index] =
479 me->m_pfAuxiliaryPFOptimal_maxLikelihood[index] = maxLik;
482 me->m_pfAuxiliaryPFOptimal_maxLikDrawnMovement[index] =
487 return me->m_particles[index].log_w +
488 me->m_pfAuxiliaryPFOptimal_estimatedProb[index];
500 class PARTICLE_TYPE,
class MYSELF,
502 template <
class BINTYPE>
507 const void* action,
const void* observation)
513 const auto* myObj =
static_cast<const MYSELF*
>(obj);
516 const double cur_logweight = myObj->m_particles[index].log_w;
527 oldPose, *static_cast<const mrpt::poses::CPose3D*>(action));
531 myObj->m_pfAuxiliaryPFStandard_estimatedProb[index] =
532 myObj->PF_SLAM_computeObservationLikelihoodForParticle(
534 *static_cast<const mrpt::obs::CSensoryFrame*>(observation),
538 return cur_logweight +
539 myObj->m_pfAuxiliaryPFStandard_estimatedProb[index];
549 double indivLik, maxLik = -1e300;
557 for (
size_t q = 0; q < N; q++)
559 myObj->m_movementDrawer.drawSample(drawnSample);
563 indivLik = myObj->PF_SLAM_computeObservationLikelihoodForParticle(
565 *static_cast<const mrpt::obs::CSensoryFrame*>(observation),
569 vectLiks[q] = indivLik;
570 if (indivLik > maxLik)
572 maxLikDraw = drawnSample;
583 myObj->m_pfAuxiliaryPFStandard_estimatedProb[index] =
586 myObj->m_pfAuxiliaryPFOptimal_maxLikelihood[index] = maxLik;
588 myObj->m_pfAuxiliaryPFOptimal_maxLikDrawnMovement[index] =
593 return cur_logweight +
594 myObj->m_pfAuxiliaryPFOptimal_estimatedProb[index];
603 class PARTICLE_TYPE,
class MYSELF,
605 template <
class BINTYPE>
611 const TKLDParams& KLD_options,
const bool USE_OPTIMAL_SAMPLING)
614 using TSetStateSpaceBins = std::set<BINTYPE, typename BINTYPE::lt_operator>;
616 auto* me =
static_cast<MYSELF*
>(
this);
618 const size_t M = me->m_particles.size();
626 if (!PF_SLAM_implementation_gatherActionsCheckBothActObs<BINTYPE>(
641 m_pfAuxiliaryPFOptimal_maxLikDrawnMovement.resize(M);
642 m_pfAuxiliaryPFOptimal_estimatedProb.resize(M);
643 m_pfAuxiliaryPFStandard_estimatedProb.resize(M);
647 m_movementDrawer.getSamplingMean3D(meanRobotMovement);
652 &TMyClass::template PF_SLAM_particlesEvaluator_AuxPFOptimal<BINTYPE>;
654 &TMyClass::template PF_SLAM_particlesEvaluator_AuxPFStandard<BINTYPE>;
656 me->prepareFastDrawSample(
657 PF_options, USE_OPTIMAL_SAMPLING ? funcOpt : funcStd,
658 &meanRobotMovement, sf);
663 if (USE_OPTIMAL_SAMPLING &&
669 "[prepareFastDrawSample] max (log) = %10.06f\n",
674 "[prepareFastDrawSample] max-mean (log) = %10.06f\n",
675 -
math::mean(m_pfAuxiliaryPFOptimal_estimatedProb) +
680 "[prepareFastDrawSample] max-min (log) = %10.06f\n",
700 std::vector<mrpt::math::TPose3D> newParticles;
701 std::vector<double> newParticlesWeight;
702 std::vector<size_t> newParticlesDerivedFromIdx;
710 m_pfAuxiliaryPFOptimal_maxLikMovementDrawHasBeenUsed.assign(M,
false);
713 USE_OPTIMAL_SAMPLING ? m_pfAuxiliaryPFOptimal_estimatedProb
714 : m_pfAuxiliaryPFStandard_estimatedProb);
721 newParticles.resize(M);
722 newParticlesWeight.resize(M);
723 newParticlesDerivedFromIdx.resize(M);
725 const bool doResample = me->ESS() < PF_options.
BETA;
727 for (
size_t i = 0; i < M; i++)
735 k = me->fastDrawSample(
743 double newParticleLogWeight = 0;
744 PF_SLAM_aux_perform_one_rejection_sampling_step<BINTYPE>(
745 USE_OPTIMAL_SAMPLING, doResample, maxMeanLik, k, sf, PF_options,
746 newPose, newParticleLogWeight);
749 newParticles[i] = newPose.asTPose();
750 newParticlesDerivedFromIdx[i] = k;
751 newParticlesWeight[i] = newParticleLogWeight;
764 newParticles.clear();
765 newParticlesWeight.resize(0);
766 newParticlesDerivedFromIdx.clear();
780 TSetStateSpaceBins stateSpaceBinsLastTimestep;
781 std::vector<std::vector<uint32_t>> stateSpaceBinsLastTimestepParticles;
782 typename MYSELF::CParticleList::iterator partIt;
783 unsigned int partIndex;
786 for (partIt = me->m_particles.begin(), partIndex = 0;
787 partIt != me->m_particles.end(); ++partIt, ++partIndex)
790 const PARTICLE_TYPE* part;
793 part = partIt->d.get();
798 KLF_loadBinFromParticle<PARTICLE_TYPE, BINTYPE>(
799 p, KLD_options, part);
802 auto posFound = stateSpaceBinsLastTimestep.find(p);
803 if (posFound == stateSpaceBinsLastTimestep.end())
805 stateSpaceBinsLastTimestep.insert(p);
806 stateSpaceBinsLastTimestepParticles.emplace_back(1, partIndex);
812 stateSpaceBinsLastTimestepParticles[idx].push_back(partIndex);
818 "[FIXED_SAMPLING] done (%u bins in t-1)\n",
819 (
unsigned int)stateSpaceBinsLastTimestep.size()));
824 double delta_1 = 1.0 - KLD_options.
KLD_delta;
826 bool doResample = me->ESS() < PF_options.
BETA;
833 const size_t minNumSamples_KLD = std::max(
837 stateSpaceBinsLastTimestep.size()));
838 size_t Nx = minNumSamples_KLD;
840 const size_t Np1 = me->m_particles.size();
841 std::vector<size_t> oldPartIdxsStillNotPropragated(
843 for (
size_t k = 0; k < Np1; k++)
844 oldPartIdxsStillNotPropragated[k] = k;
846 const size_t Np = stateSpaceBinsLastTimestepParticles.size();
847 std::vector<size_t> permutationPathsAuxVector(Np);
848 for (
size_t k = 0; k < Np; k++) permutationPathsAuxVector[k] = k;
854 permutationPathsAuxVector.begin(), permutationPathsAuxVector.end());
859 TSetStateSpaceBins stateSpaceBins;
873 k = me->fastDrawSample(
881 if (permutationPathsAuxVector.size())
883 const size_t idxBinSpacePath =
884 *permutationPathsAuxVector.rbegin();
885 permutationPathsAuxVector.resize(
886 permutationPathsAuxVector.size() - 1);
890 stateSpaceBinsLastTimestepParticles[idxBinSpacePath]
892 k = stateSpaceBinsLastTimestepParticles[idxBinSpacePath]
894 ASSERT_(k < me->m_particles.size());
897 oldPartIdxsStillNotPropragated.erase(
std::find(
898 oldPartIdxsStillNotPropragated.begin(),
899 oldPartIdxsStillNotPropragated.end(), k));
914 if (oldPartIdxsStillNotPropragated.size())
919 oldPartIdxsStillNotPropragated.size();
920 auto it = oldPartIdxsStillNotPropragated.begin() +
923 oldPartIdxsStillNotPropragated.erase(it);
930 me->m_particles.size();
938 double newParticleLogWeight;
939 PF_SLAM_aux_perform_one_rejection_sampling_step<BINTYPE>(
940 USE_OPTIMAL_SAMPLING, doResample, maxMeanLik, k, sf, PF_options,
941 newPose, newParticleLogWeight);
944 newParticles.push_back(newPose.asTPose());
945 newParticlesDerivedFromIdx.push_back(k);
946 newParticlesWeight.push_back(newParticleLogWeight);
952 const PARTICLE_TYPE* part;
955 part = me->m_particles[k].d.get();
957 part = &me->m_particles[k].d;
961 KLF_loadBinFromParticle<PARTICLE_TYPE, BINTYPE>(
962 p, KLD_options, part, &newPose_s);
971 if (stateSpaceBins.find(p) == stateSpaceBins.end())
974 stateSpaceBins.insert(p);
977 int K = stateSpaceBins.
size();
987 N = newParticles.size();
990 N < std::max(Nx, minNumSamples_KLD)) ||
991 (permutationPathsAuxVector.size() && !doResample));
996 "[ADAPTIVE SAMPLE SIZE] #Bins: %u \t #Particles: %u \t " 998 static_cast<unsigned>(stateSpaceBins.size()),
999 static_cast<unsigned>(N), (unsigned)Nx));
1008 this->PF_SLAM_implementation_replaceByNewParticleSet(
1009 me->m_particles, newParticles, newParticlesWeight,
1010 newParticlesDerivedFromIdx);
1013 me->normalizeWeights();
1022 class PARTICLE_TYPE,
class MYSELF,
1024 template <
class BINTYPE>
1027 const bool USE_OPTIMAL_SAMPLING,
const bool doResample,
1028 const double maxMeanLik,
1034 auto* me =
static_cast<MYSELF*
>(
this);
1039 while (((USE_OPTIMAL_SAMPLING ? m_pfAuxiliaryPFOptimal_estimatedProb[k]
1040 : m_pfAuxiliaryPFStandard_estimatedProb[k]) -
1045 me->m_particles.size();
1048 "[PF_SLAM_aux_perform_one_rejection_sampling_step] Warning: " 1049 "Discarding very unlikely particle.");
1054 getLastPose(k, pose_is_valid));
1061 if (PF_SLAM_implementation_skipRobotMovement())
1066 out_newPose = oldPose;
1072 if (!USE_OPTIMAL_SAMPLING)
1074 m_movementDrawer.drawSample(movementDraw);
1076 oldPose, movementDraw);
1078 poseLogLik = PF_SLAM_computeObservationLikelihoodForParticle(
1079 PF_options, k, *sf, out_newPose);
1084 double acceptanceProb;
1086 const int maxTries = 10000;
1087 double bestTryByNow_loglik = -std::numeric_limits<double>::max();
1093 !m_pfAuxiliaryPFOptimal_maxLikMovementDrawHasBeenUsed[k])
1096 m_pfAuxiliaryPFOptimal_maxLikMovementDrawHasBeenUsed[k] =
1099 m_pfAuxiliaryPFOptimal_maxLikDrawnMovement[k]);
1104 m_movementDrawer.drawSample(movementDraw);
1112 poseLogLik = PF_SLAM_computeObservationLikelihoodForParticle(
1113 PF_options, k, *sf, out_newPose);
1115 if (poseLogLik > bestTryByNow_loglik)
1117 bestTryByNow_loglik = poseLogLik;
1118 bestTryByNow_pose = out_newPose.
asTPose();
1121 double ratioLikLik = std::exp(
1122 poseLogLik - m_pfAuxiliaryPFOptimal_maxLikelihood[k]);
1123 acceptanceProb = std::min(1.0, ratioLikLik);
1125 if (ratioLikLik > 1)
1127 m_pfAuxiliaryPFOptimal_maxLikelihood[k] =
1133 ++timeout < maxTries &&
1137 if (timeout >= maxTries)
1140 poseLogLik = bestTryByNow_loglik;
1143 "[PF_implementation] Warning: timeout in rejection " 1149 if (USE_OPTIMAL_SAMPLING)
1152 out_newParticleLogWeight = 0;
1157 const double weightFact =
1158 m_pfAuxiliaryPFOptimal_estimatedProb[k] *
1160 out_newParticleLogWeight =
1161 me->m_particles[k].log_w + weightFact;
1166 const double weightFact =
1167 (poseLogLik - m_pfAuxiliaryPFStandard_estimatedProb[k]) *
1170 out_newParticleLogWeight = weightFact;
1172 out_newParticleLogWeight =
1173 weightFact + me->m_particles[k].log_w;
uint32_t drawUniform32bit()
Generate a uniformly distributed pseudo-random number using the MT19937 algorithm, in the whole range of 32-bit integers.
mrpt::math::TPose3D asTPose() const
const_iterator find(const KEY &key) const
#define THROW_EXCEPTION(msg)
std::string std::string format(std::string_view fmt, ARGS &&... args)
#define INVALID_LIKELIHOOD_VALUE
unsigned int pfAuxFilterOptimal_MaximumSearchSamples
In the algorithm "CParticleFilter::pfAuxiliaryPFOptimal" (and in "CParticleFilter::pfAuxiliaryPFStand...
void shuffle(RandomIt first, RandomIt last, URBG &&g)
Uniform shuffle a sequence.
void PF_SLAM_implementation_pfAuxiliaryPFStandard(const mrpt::obs::CActionCollection *actions, const mrpt::obs::CSensoryFrame *sf, const mrpt::bayes::CParticleFilter::TParticleFilterOptions &PF_options, const TKLDParams &KLD_options)
A generic implementation of the PF method "prediction_and_update_pfAuxiliaryPFStandard" (Auxiliary pa...
Option set for KLD algorithm.
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...
void PF_SLAM_implementation_pfAuxiliaryPFOptimal(const mrpt::obs::CActionCollection *actions, const mrpt::obs::CSensoryFrame *sf, const mrpt::bayes::CParticleFilter::TParticleFilterOptions &PF_options, const TKLDParams &KLD_options)
A generic implementation of the PF method "prediction_and_update_pfAuxiliaryPFOptimal" (optimal sampl...
Declares a class for storing a collection of robot actions.
A set of common data shared by PF implementations for both SLAM and localization. ...
#define ASSERT_(f)
Defines an assertion mechanism.
Represents a probabilistic 3D (6D) movement.
Represents a probabilistic 2D movement of the robot mobile base.
void PF_SLAM_aux_perform_one_rejection_sampling_step(const bool USE_OPTIMAL_SAMPLING, const bool doResample, const double maxMeanLik, size_t k, const mrpt::obs::CSensoryFrame *sf, const mrpt::bayes::CParticleFilter::TParticleFilterOptions &PF_options, mrpt::poses::CPose3D &out_newPose, double &out_newParticleLogWeight)
unsigned int KLD_minSampleSize
Parameters for the KLD adaptive sample size algorithm (see Dieter Fox's papers), which is used only i...
CActionRobotMovement2D::Ptr getBestMovementEstimation() const
Returns the best pose increment estimator in the collection, based on the determinant of its pose cha...
#define MRPT_CHECK_NORMAL_NUMBER(v)
Throws an exception if the number is NaN, IND, or +/-INF, or return the same number otherwise...
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...
double KLD_minSamplesPerBin
(Default: KLD_minSamplesPerBin=0) The minimum number of samples will be the maximum of KLD_minSampleS...
double averageLogLikelihood(const CVectorDouble &logLikelihoods)
A numerically-stable method to compute average likelihood values with strongly different ranges (unwe...
CONTAINER::Scalar maximum(const CONTAINER &v)
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
This virtual class defines the interface that any particles based PDF class must implement in order t...
bool pfAuxFilterStandard_FirstStageWeightsMonteCarlo
Only for PF_algorithm==pfAuxiliaryPFStandard: If false, the APF will predict the first stage weights ...
double BETA
The resampling of particles will be performed when ESS (in range [0,1]) < BETA (default is 0...
unsigned int KLD_maxSampleSize
T::Ptr getActionByClass(size_t ith=0) const
Access to the i'th action of a given class, or a nullptr smart pointer if there is no action of that ...
static double PF_SLAM_particlesEvaluator_AuxPFOptimal(const mrpt::bayes::CParticleFilter::TParticleFilterOptions &PF_options, const mrpt::bayes::CParticleFilterCapable *obj, size_t index, const void *action, const void *observation)
void PF_SLAM_implementation_pfAuxiliaryPFStandardAndOptimal(const mrpt::obs::CActionCollection *actions, const mrpt::obs::CSensoryFrame *sf, const mrpt::bayes::CParticleFilter::TParticleFilterOptions &PF_options, const TKLDParams &KLD_options, const bool USE_OPTIMAL_SAMPLING)
The shared implementation body of two PF methods: APF and Optimal-APF, depending on USE_OPTIMAL_SAMPL...
CONTAINER::Scalar minimum(const CONTAINER &v)
constexpr std::size_t size() const
double chi2inv(double P, unsigned int dim=1)
The "quantile" of the Chi-Square distribution, for dimension "dim" and probability 0<P<1 (the inverse...
void PF_SLAM_implementation_pfStandardProposal(const mrpt::obs::CActionCollection *actions, const mrpt::obs::CSensoryFrame *sf, const mrpt::bayes::CParticleFilter::TParticleFilterOptions &PF_options, const TKLDParams &KLD_options)
A generic implementation of the PF method "pfStandardProposal" (standard proposal distribution...
mrpt::containers::deepcopy_poly_ptr< mrpt::poses::CPosePDF::Ptr > poseChange
The 2D pose change probabilistic estimation.
double max_loglikelihood_dyn_range
Only for PF_algorithm=pfAuxiliaryPFOptimal: If a given particle has a max_likelihood (from the a-prio...
void logStr(const VerbosityLevel level, std::string_view msg_str) const
Main method to add the specified message string to the logger.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
static double PF_SLAM_particlesEvaluator_AuxPFStandard(const mrpt::bayes::CParticleFilter::TParticleFilterOptions &PF_options, const mrpt::bayes::CParticleFilterCapable *obj, size_t index, const void *action, const void *observation)
Compute w[i]*p(z_t | mu_t^i), with mu_t^i being the mean of the new robot pose.
double powFactor
An optional step to "smooth" dramatic changes in the observation model to affect the variance of the ...
The configuration of a particle filter.
Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).
double mean(const CONTAINER &v)
Computes the mean value of a vector.
bool pfAuxFilterOptimal_MLE
(Default=false) In the algorithm "CParticleFilter::pfAuxiliaryPFOptimal", if set to true...
bool PF_SLAM_implementation_gatherActionsCheckBothActObs(const mrpt::obs::CActionCollection *actions, const mrpt::obs::CSensoryFrame *sf)
Auxiliary method called by PF implementations: return true if we have both action & observation...
particle_storage_mode
use for CProbabilityParticle
CRandomGenerator & getRandomGenerator()
A static instance of a CRandomGenerator class, for use in single-thread applications.
double distance(const TPoint2D &p1, const TPoint2D &p2)
Gets the distance between two points in a 2D space.
bool adaptiveSampleSize
A flag that indicates whether the CParticleFilterCapable object should perform adative sample size (d...
#define MRPT_UNUSED_PARAM(a)
Determines whether this is an X86 or AMD64 platform.
int round(const T value)
Returns the closer integer (int) to x.