9 #ifndef CMonteCarloLocalization3D_H
10 #define CMonteCarloLocalization3D_H
62 void prediction_and_update_pfStandardProposal(
76 void prediction_and_update_pfAuxiliaryPFStandard(
90 void prediction_and_update_pfAuxiliaryPFOptimal(
99 const TPose3D * getLastPose(
const size_t i)
const;
101 void PF_SLAM_implementation_custom_update_particle_with_new_pose(
106 void PF_SLAM_implementation_replaceByNewParticleSet(
108 const std::vector<TPose3D> &newParticles,
109 const vector<double> &newParticlesWeight,
110 const std::vector<size_t> &newParticlesDerivedFromIdx )
const;
113 double PF_SLAM_computeObservationLikelihoodForParticle(
115 const size_t particleIndexForMap,
The struct for passing extra simulation parameters to the prediction stage when running a particle fi...
The namespace for Bayesian filtering algorithm: different particle filters and Kalman filter algorith...
This namespace contains algorithms for SLAM, localization, map building, representation of robot's ac...
Declares a class for storing a collection of robot actions.
A set of common data shared by PF implementations for both SLAM and localization. ...
TMonteCarloLocalizationParams options
MCL parameters.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
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.
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
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.