Class CMonteCarloLocalization2D

Inheritance Relationships

Base Types

  • public mrpt::poses::CPosePDFParticles

  • public mrpt::slam::PF_implementation< mrpt::math::TPose2D, CMonteCarloLocalization2D, mrpt::poses::CPosePDFParticles::PARTICLE_STORAGE > (Template Class PF_implementation)

Class Documentation

class CMonteCarloLocalization2D : public mrpt::poses::CPosePDFParticles, public mrpt::slam::PF_implementation<mrpt::math::TPose2D, CMonteCarloLocalization2D, mrpt::poses::CPosePDFParticles::PARTICLE_STORAGE>

Declares a class that represents a Probability Density Function (PDF) over a 2D pose (x,y,phi), using a set of weighted samples.

This class also implements particle filtering for robot localization. See the MRPT application “app/pf-localization” for an example of usage.

See also

CMonteCarloLocalization3D, CPose2D, CPosePDF, CPoseGaussianPDF, CParticleFilterCapable

Virtual methods that the PF_implementations assume exist.

virtual mrpt::math::TPose3D getLastPose(size_t i, bool &is_valid_pose) const override

Return the robot pose for the i’th particle. is_valid is always true in this class.

virtual void PF_SLAM_implementation_custom_update_particle_with_new_pose(mrpt::math::TPose2D *particleData, const mrpt::math::TPose3D &newPose) const override
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
virtual double PF_SLAM_computeObservationLikelihoodForParticle(const mrpt::bayes::CParticleFilter::TParticleFilterOptions &PF_options, 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

Public Functions

CMonteCarloLocalization2D(size_t M = 1)

Constructor

Parameters:

M – The number of m_particles.

~CMonteCarloLocalization2D() override

Destructor

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-grid-map. Orientation is randomly generated in the whole 2*PI range.

See also

resetDeterm32inistic

Parameters:
  • theMap – The occupancy grid map

  • freeCellsThreshold – The minimum free-probability to consider a cell as empty (default is 0.7)

  • particlesCount – If set to -1 the number of m_particles remains unchanged.

  • x_min – The limits of the area to look for free cells.

  • x_max – The limits of the area to look for free cells.

  • y_min – The limits of the area to look for free cells.

  • y_max – The limits of the area to look for free cells.

  • phi_min – The limits of the area to look for free cells.

  • phi_max – The limits of the area to look for free cells.

Throws:

std::exception – On any error (no free cell found in map, map=nullptr, etc…)

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. This method has additional configuration parameters in “options”. Performs the update stage of the RBPF, using the sensed CSensoryFrame:

See also

options

Parameters:
  • action – This is a pointer to CActionCollection, containing the pose change the robot has been commanded.

  • observation – This must be a pointer to a CSensoryFrame object, with robot sensed observations.

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. This method has additional configuration parameters in “options”. Performs the update stage of the RBPF, using the sensed CSensoryFrame:

See also

options

Parameters:
  • Action – This is a pointer to CActionCollection, containing the pose change the robot has been commanded.

  • observation – This must be a pointer to a CSensoryFrame object, with robot sensed observations.

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. This method has additional configuration parameters in “options”. Performs the update stage of the RBPF, using the sensed CSensoryFrame:

See also

options

Parameters:
  • Action – This is a pointer to CActionCollection, containing the pose change the robot has been commanded.

  • observation – This must be a pointer to a CSensoryFrame object, with robot sensed observations.

inline mrpt::viz::CSetOfObjects::Ptr getVisualization() const

Returns a 3D representation of this PDF.

Note

Needs the mrpt-opengl library, and using mrpt::viz::CSetOfObjects::Ptr as template argument.

Public Members

TMonteCarloLocalizationParams options

MCL parameters