9 #ifndef CMonteCarloLocalization3D_H 10 #define CMonteCarloLocalization3D_H 55 void prediction_and_update_pfStandardProposal(
69 void prediction_and_update_pfAuxiliaryPFStandard(
83 void prediction_and_update_pfAuxiliaryPFOptimal(
92 void PF_SLAM_implementation_custom_update_particle_with_new_pose(
93 CParticleDataContent *particleData,
97 void PF_SLAM_implementation_replaceByNewParticleSet(
98 CParticleList &old_particles,
99 const std::vector<mrpt::math::TPose3D> &newParticles,
100 const std::vector<double> &newParticlesWeight,
101 const std::vector<size_t> &newParticlesDerivedFromIdx )
const;
104 double PF_SLAM_computeObservationLikelihoodForParticle(
106 const size_t particleIndexForMap,
The struct for passing extra simulation parameters to the prediction stage when running a particle fi...
#define MRPT_OVERRIDE
C++11 "override" for virtuals:
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.
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.
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.