9#ifndef CMonteCarloLocalization2D_H
10#define CMonteCarloLocalization2D_H
21 namespace maps {
class COccupancyGridMap2D; }
65 const double freeCellsThreshold = 0.7,
66 const int particlesCount = -1,
67 const double x_min = -1e10f,
68 const double x_max = 1e10f,
69 const double y_min = -1e10f,
70 const double y_max = 1e10f,
71 const double phi_min = -
M_PI,
72 const double phi_max =
M_PI );
129 const std::vector<mrpt::math::TPose3D> &newParticles,
130 const std::vector<double> &newParticlesWeight,
131 const std::vector<size_t> &newParticlesDerivedFromIdx )
const;
136 const size_t particleIndexForMap,
std::deque< CParticleData > CParticleList
Use this type to refer to the list of particles m_particles.
CPose2D CParticleDataContent
This is the type inside the corresponding CParticleData class.
A class for storing an occupancy grid map.
Declares a class for storing a collection of robot actions.
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).
Declares a class that represents a Probability Density Function (PDF) over a 2D pose (x,...
Declares a class that represents a Probability Density Function (PDF) over a 2D pose (x,...
double PF_SLAM_computeObservationLikelihoodForParticle(const mrpt::bayes::CParticleFilter::TParticleFilterOptions &PF_options, const size_t particleIndexForMap, const mrpt::obs::CSensoryFrame &observation, const mrpt::poses::CPose3D &x) const
Evaluate the observation likelihood for one particle at a given location.
void resetUniformFreeSpace(mrpt::maps::COccupancyGridMap2D *theMap, const double freeCellsThreshold=0.7, const int particlesCount=-1, const double x_min=-1e10f, const double x_max=1e10f, const double y_min=-1e10f, const double y_max=1e10f, const double phi_min=-M_PI, const double phi_max=M_PI)
Reset the PDF to an uniformly distributed one, but only in the free-space of a given 2D occupancy-gri...
void PF_SLAM_implementation_replaceByNewParticleSet(CParticleList &old_particles, const std::vector< mrpt::math::TPose3D > &newParticles, const std::vector< double > &newParticlesWeight, const std::vector< size_t > &newParticlesDerivedFromIdx) const
virtual ~CMonteCarloLocalization2D()
Destructor.
const mrpt::math::TPose3D * getLastPose(const size_t i) const
Return a pointer to the last robot pose in the i'th particle (or NULL if it's a path and it's empty).
TMonteCarloLocalizationParams options
MCL parameters.
void prediction_and_update_pfStandardProposal(const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options)
Update the m_particles, predicting the posterior of robot pose and map after a movement command.
void prediction_and_update_pfAuxiliaryPFOptimal(const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options)
Update the m_particles, predicting the posterior of robot pose and map after a movement command.
CMonteCarloLocalization2D(size_t M=1)
Constructor.
void PF_SLAM_implementation_custom_update_particle_with_new_pose(CParticleDataContent *particleData, const mrpt::math::TPose3D &newPose) const
void prediction_and_update_pfAuxiliaryPFStandard(const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options)
Update the m_particles, predicting the posterior of robot pose and map after a movement command.
A set of common data shared by PF implementations for both SLAM and localization.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
The configuration of a particle filter.
Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).
The struct for passing extra simulation parameters to the prediction stage when running a particle fi...