20 class COccupancyGridMap2D;
40 mrpt::math::TPose2D, CMonteCarloLocalization2D,
41 mrpt::poses::CPosePDFParticles::PARTICLE_STORAGE>
76 const double freeCellsThreshold = 0.7,
const int particlesCount = -1,
77 const double x_min = -1e10f,
const double x_max = 1e10f,
78 const double y_min = -1e10f,
const double y_max = 1e10f,
79 const double phi_min = -
M_PI,
const double phi_max =
M_PI);
141 const size_t i,
bool& is_valid_pose)
const override;
150 const std::vector<mrpt::math::TPose3D>& newParticles,
151 const std::vector<double>& newParticlesWeight,
152 const std::vector<size_t>& newParticlesDerivedFromIdx)
const override;
158 const size_t particleIndexForMap,
void prediction_and_update_pfStandardProposal(const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options) override
Update the m_particles, predicting the posterior of robot pose and map after a movement command...
The struct for passing extra simulation parameters to the prediction stage when running a particle fi...
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...
~CMonteCarloLocalization2D() override
Destructor.
TMonteCarloLocalizationParams options
MCL parameters.
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 override
Declares a class for storing a collection of robot actions.
size_t particlesCount() const override
A set of common data shared by PF implementations for both SLAM and localization. ...
void PF_SLAM_implementation_custom_update_particle_with_new_pose(mrpt::math::TPose2D *particleData, const mrpt::math::TPose3D &newPose) const override
void prediction_and_update_pfAuxiliaryPFOptimal(const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options) override
Update the m_particles, predicting the posterior of robot pose and map after a movement command...
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
std::deque< CParticleData > CParticleList
Use this type to refer to the list of particles m_particles.
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...
A class for storing an occupancy grid map.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
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 override
Evaluate the observation likelihood for one particle at a given location.
mrpt::math::TPose3D getLastPose(const size_t i, bool &is_valid_pose) const override
Return the robot pose for the i'th particle.
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).
CMonteCarloLocalization2D(size_t M=1)
Constructor.
void prediction_and_update_pfAuxiliaryPFStandard(const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options) override
Update the m_particles, predicting the posterior of robot pose and map after a movement command...