9 #ifndef CMonteCarloLocalization3D_H
10 #define CMonteCarloLocalization3D_H
57 void prediction_and_update_pfStandardProposal(
71 void prediction_and_update_pfAuxiliaryPFStandard(
85 void prediction_and_update_pfAuxiliaryPFOptimal(
95 void PF_SLAM_implementation_custom_update_particle_with_new_pose(
100 void PF_SLAM_implementation_replaceByNewParticleSet(
102 const std::vector<mrpt::math::TPose3D> &newParticles,
103 const std::vector<double> &newParticlesWeight,
104 const std::vector<size_t> &newParticlesDerivedFromIdx )
const;
107 double PF_SLAM_computeObservationLikelihoodForParticle(
109 const size_t particleIndexForMap,
The struct for passing extra simulation parameters to the prediction stage when running a particle fi...
Declares a class for storing a collection of robot actions.
A set of common data shared by PF implementations for both SLAM and localization. ...
CPose3D CParticleDataContent
This is the type inside the corresponding CParticleData class.
TMonteCarloLocalizationParams options
MCL parameters.
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
Declares a class that represents a Probability Density Function (PDF) over a 3D pose (x...
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
std::deque< CParticleData > CParticleList
Use this type to refer to the list of particles m_particles.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
The configuration of a particle filter.
Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).
Declares a class that represents a Probability Density function (PDF) of a 3D pose.