Declares a class that represents a Probability Density Function (PDF) over a 3D pose (x,y,phi,yaw,pitch,roll), 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.
Definition at line 30 of file CMonteCarloLocalization3D.h.
#include <mrpt/slam/CMonteCarloLocalization3D.h>
Public Types | |
using | CParticleDataContent = mrpt::poses::CPose3DPDFParticles::CParticleDataContent |
using | CParticleList = mrpt::poses::CPose3DPDFParticles::CParticleList |
Public Member Functions | |
CMonteCarloLocalization3D (size_t M=1) | |
Constructor. More... | |
virtual | ~CMonteCarloLocalization3D () |
Destructor. More... | |
template<typename T > | |
void | prediction_and_update (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. More... | |
void | executeOn (mrpt::bayes::CParticleFilter &pf, const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, mrpt::bayes::CParticleFilter::TParticleFilterStats *stats, mrpt::bayes::CParticleFilter::TParticleFilterAlgorithm PF_algorithm) |
Virtual methods that the PF_implementations assume exist. | |
mrpt::math::TPose3D | getLastPose (const size_t i, bool &is_valid_pose) const override |
Return the robot pose for the i'th particle. More... | |
void | PF_SLAM_implementation_custom_update_particle_with_new_pose (CParticleDataContent *particleData, const mrpt::math::TPose3D &newPose) const |
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 |
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. More... | |
Virtual methods that the PF_implementations assume exist. | |
virtual void | PF_SLAM_implementation_custom_update_particle_with_new_pose (mrpt::poses::CPose3D *particleData, const mrpt::math::TPose3D &newPose) const=0 |
virtual void | PF_SLAM_implementation_replaceByNewParticleSet (typename mrpt::poses::CPose3DPDFParticles ::CParticleList &old_particles, const std::vector< mrpt::math::TPose3D > &newParticles, const std::vector< double > &newParticlesWeight, const std::vector< size_t > &newParticlesDerivedFromIdx) const |
This is the default algorithm to efficiently replace one old set of samples by another new set. More... | |
virtual bool | PF_SLAM_implementation_doWeHaveValidObservations (const typename mrpt::bayes::CParticleFilterData< mrpt::poses::CPose3D >::typename mrpt::poses::CPose3DPDFParticles ::CParticleList &particles, const mrpt::obs::CSensoryFrame *sf) const |
virtual bool | PF_SLAM_implementation_skipRobotMovement () const |
Make a specialization if needed, eg. More... | |
Public Attributes | |
mrpt::poses::CPose3DPDFParticles | m_poseParticles |
TMonteCarloLocalizationParams | options |
MCL parameters. More... | |
using mrpt::slam::CMonteCarloLocalization3D::CParticleDataContent = mrpt::poses::CPose3DPDFParticles::CParticleDataContent |
Definition at line 36 of file CMonteCarloLocalization3D.h.
using mrpt::slam::CMonteCarloLocalization3D::CParticleList = mrpt::poses::CPose3DPDFParticles::CParticleList |
Definition at line 37 of file CMonteCarloLocalization3D.h.
mrpt::slam::CMonteCarloLocalization3D::CMonteCarloLocalization3D | ( | size_t | M = 1 | ) |
Constructor.
M | The number of m_particles. |
Definition at line 77 of file CMonteCarloLocalization3D.cpp.
Referenced by executeOn(), and prediction_and_update().
|
virtual |
Destructor.
Definition at line 86 of file CMonteCarloLocalization3D.cpp.
void mrpt::slam::CMonteCarloLocalization3D::executeOn | ( | mrpt::bayes::CParticleFilter & | pf, |
const mrpt::obs::CActionCollection * | action, | ||
const mrpt::obs::CSensoryFrame * | observation, | ||
mrpt::bayes::CParticleFilter::TParticleFilterStats * | stats, | ||
mrpt::bayes::CParticleFilter::TParticleFilterAlgorithm | PF_algorithm | ||
) |
Definition at line 188 of file CMonteCarloLocalization3D.cpp.
References CMonteCarloLocalization3D(), mrpt::bayes::CParticleFilter::executeOn(), and THROW_EXCEPTION.
|
overridevirtual |
Return the robot pose for the i'th particle.
is_valid is always true in this class.
Implements mrpt::slam::PF_implementation< mrpt::poses::CPose3D, mrpt::poses::CPose3DPDFParticles >.
Definition at line 87 of file CMonteCarloLocalization3D.cpp.
References ASSERTDEB_, mrpt::bayes::CParticleFilterData< T >::m_particles, m_poseParticles, and THROW_EXCEPTION.
|
virtual |
Evaluate the observation likelihood for one particle at a given location.
Implements mrpt::slam::PF_implementation< mrpt::poses::CPose3D, mrpt::poses::CPose3DPDFParticles >.
Definition at line 130 of file CMonteCarloLocalization3D.cpp.
References ASSERT_, mrpt::obs::CSensoryFrame::begin(), mrpt::obs::CSensoryFrame::end(), mrpt::slam::TMonteCarloLocalizationParams::metricMap, mrpt::slam::TMonteCarloLocalizationParams::metricMaps, MRPT_UNUSED_PARAM, and options.
void mrpt::slam::CMonteCarloLocalization3D::PF_SLAM_implementation_custom_update_particle_with_new_pose | ( | CParticleDataContent * | particleData, |
const mrpt::math::TPose3D & | newPose | ||
) | const |
Definition at line 156 of file CMonteCarloLocalization3D.cpp.
|
pure virtualinherited |
|
inlinevirtualinherited |
Definition at line 179 of file PF_implementations_data.h.
void mrpt::slam::CMonteCarloLocalization3D::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 |
Definition at line 162 of file CMonteCarloLocalization3D.cpp.
References ASSERT_, and MRPT_UNUSED_PARAM.
|
inlinevirtualinherited |
This is the default algorithm to efficiently replace one old set of samples by another new set.
The method uses pointers to make fast copies the first time each particle is duplicated, then makes real copies for the next ones.
Note that more efficient specializations might exist for specific particle data structs.
Definition at line 105 of file PF_implementations_data.h.
|
inlinevirtualinherited |
Make a specialization if needed, eg.
in the first step in SLAM.
Definition at line 190 of file PF_implementations_data.h.
|
staticinherited |
Compute w[i]*p(z_t | mu_t^i), with mu_t^i being the mean of the new robot pose.
action | MUST be a "const CPose3D*" |
observation | MUST be a "const CSensoryFrame*" |
void mrpt::slam::CMonteCarloLocalization3D::prediction_and_update | ( | 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.
This method has additional configuration parameters in "options". Performs the update stage of the RBPF, using the sensed CSensoryFrame:
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. |
Definition at line 103 of file CMonteCarloLocalization3D.cpp.
References ASSERT_, CMonteCarloLocalization3D(), mrpt::slam::TMonteCarloLocalizationParams::KLD_params, mrpt::bayes::CParticleFilterData< T >::m_particles, m_poseParticles, mrpt::slam::TMonteCarloLocalizationParams::metricMap, mrpt::slam::TMonteCarloLocalizationParams::metricMaps, MRPT_END, MRPT_START, and options.
|
inherited |
Definition at line 48 of file PF_implementations_data.h.
|
inherited |
Definition at line 49 of file PF_implementations_data.h.
|
inherited |
Definition at line 50 of file PF_implementations_data.h.
|
inherited |
Definition at line 51 of file PF_implementations_data.h.
|
inherited |
Used in al PF implementations.
Definition at line 55 of file PF_implementations_data.h.
|
mutableinherited |
Auxiliary variable used in the "pfAuxiliaryPFOptimal" algorithm.
Definition at line 57 of file PF_implementations_data.h.
|
mutableinherited |
Auxiliary variable used in the "pfAuxiliaryPFOptimal" algorithm.
Definition at line 64 of file PF_implementations_data.h.
|
mutableinherited |
Auxiliary variable used in the "pfAuxiliaryPFOptimal" algorithm.
Definition at line 61 of file PF_implementations_data.h.
|
inherited |
Definition at line 65 of file PF_implementations_data.h.
|
mutableinherited |
Auxiliary variable used in the "pfAuxiliaryPFStandard" algorithm.
Definition at line 59 of file PF_implementations_data.h.
mrpt::poses::CPose3DPDFParticles mrpt::slam::CMonteCarloLocalization3D::m_poseParticles |
Definition at line 39 of file CMonteCarloLocalization3D.h.
Referenced by getLastPose(), and prediction_and_update().
TMonteCarloLocalizationParams mrpt::slam::CMonteCarloLocalization3D::options |
MCL parameters.
Definition at line 42 of file CMonteCarloLocalization3D.h.
Referenced by PF_SLAM_computeObservationLikelihoodForParticle(), and prediction_and_update().
Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019 |