Go to the documentation of this file.
9 #ifndef CMonteCarloLocalization3D_H
10 #define CMonteCarloLocalization3D_H
35 mrpt::math::TPose3D, CMonteCarloLocalization3D,
36 mrpt::bayes::particle_storage_mode::VALUE>
103 const size_t i,
bool& is_valid_pose)
const override;
112 const std::vector<mrpt::math::TPose3D>& newParticles,
113 const std::vector<double>& newParticlesWeight,
114 const std::vector<size_t>& newParticlesDerivedFromIdx)
const;
120 const size_t particleIndexForMap,
std::deque< CParticleData > CParticleList
Use this type to refer to the list of particles m_particles.
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.
Declares a class that represents a Probability Density Function (PDF) over a 3D pose (x,...
mrpt::math::TPose3D getLastPose(const size_t i, bool &is_valid_pose) const override
Return the robot pose for the i'th particle.
Declares a class for storing a collection of robot actions.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
CMonteCarloLocalization3D(size_t M=1)
Constructor.
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
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
mrpt::math::TPose3D CParticleDataContent
This is the type inside the corresponding CParticleData class.
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.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
A set of common data shared by PF implementations for both SLAM and localization.
Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).
Declares a class that represents a Probability Density function (PDF) of a 3D pose.
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 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.
The struct for passing extra simulation parameters to the prediction stage when running a particle fi...
TMonteCarloLocalizationParams options
MCL parameters.
The configuration of a particle filter.
Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST | |