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. More...
#include <mrpt/slam/CMonteCarloLocalization3D.h>


Public Member Functions | |
| CMonteCarloLocalization3D (size_t M=1) | |
| Constructor. | |
| virtual | ~CMonteCarloLocalization3D () |
| Destructor. | |
| void | prediction_and_update_pfStandardProposal (const mrpt::slam::CActionCollection *action, const mrpt::slam::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_pfAuxiliaryPFStandard (const mrpt::slam::CActionCollection *action, const mrpt::slam::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::slam::CActionCollection *action, const mrpt::slam::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options) |
| Update the m_particles, predicting the posterior of robot pose and map after a movement command. | |
Public Attributes | |
| TMonteCarloLocalizationParams | options |
| MCL parameters. | |
Protected Member Functions | |
Virtual methods that the PF_implementations assume exist. | |
| const 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). | |
| void | PF_SLAM_implementation_custom_update_particle_with_new_pose (CParticleDataContent *particleData, const TPose3D &newPose) const |
| void | PF_SLAM_implementation_replaceByNewParticleSet (CParticleList &old_particles, const vector< TPose3D > &newParticles, const vector_double &newParticlesWeight, const vector< size_t > &newParticlesDerivedFromIdx) const |
| This is the default algorithm to efficiently replace one old set of samples by another new set. | |
| double | PF_SLAM_computeObservationLikelihoodForParticle (const CParticleFilter::TParticleFilterOptions &PF_options, const size_t particleIndexForMap, const CSensoryFrame &observation, const CPose3D &x) const |
| Evaluate the observation likelihood for one particle at a given location. | |
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 54 of file CMonteCarloLocalization3D.h.
| mrpt::slam::CMonteCarloLocalization3D::CMonteCarloLocalization3D | ( | size_t | M = 1 |
) |
Constructor.
| M | The number of m_particles. |
| virtual mrpt::slam::CMonteCarloLocalization3D::~CMonteCarloLocalization3D | ( | ) | [virtual] |
Destructor.
| const TPose3D* mrpt::slam::CMonteCarloLocalization3D::getLastPose | ( | const size_t | i | ) | const [protected, virtual] |
Return a pointer to the last robot pose in the i'th particle (or NULL if it's a path and it's empty).
Implements mrpt::slam::PF_implementation< CPose3D >.
| double mrpt::slam::CMonteCarloLocalization3D::PF_SLAM_computeObservationLikelihoodForParticle | ( | const CParticleFilter::TParticleFilterOptions & | PF_options, | |
| const size_t | particleIndexForMap, | |||
| const CSensoryFrame & | observation, | |||
| const CPose3D & | x | |||
| ) | const [protected, virtual] |
Evaluate the observation likelihood for one particle at a given location.
Implements mrpt::slam::PF_implementation< CPose3D >.
| void mrpt::slam::CMonteCarloLocalization3D::PF_SLAM_implementation_custom_update_particle_with_new_pose | ( | CParticleDataContent * | particleData, | |
| const TPose3D & | newPose | |||
| ) | const [protected] |
| void mrpt::slam::CMonteCarloLocalization3D::PF_SLAM_implementation_replaceByNewParticleSet | ( | CParticleList & | old_particles, | |
| const vector< TPose3D > & | newParticles, | |||
| const vector_double & | newParticlesWeight, | |||
| const vector< size_t > & | newParticlesDerivedFromIdx | |||
| ) | const [protected, virtual] |
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.
Reimplemented from mrpt::slam::PF_implementation< CPose3D >.
| void mrpt::slam::CMonteCarloLocalization3D::prediction_and_update_pfAuxiliaryPFOptimal | ( | const mrpt::slam::CActionCollection * | action, | |
| const mrpt::slam::CSensoryFrame * | observation, | |||
| const bayes::CParticleFilter::TParticleFilterOptions & | PF_options | |||
| ) | [virtual] |
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 Sensorial Frame:
| 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. |
Reimplemented from mrpt::bayes::CParticleFilterCapable.
| void mrpt::slam::CMonteCarloLocalization3D::prediction_and_update_pfAuxiliaryPFStandard | ( | const mrpt::slam::CActionCollection * | action, | |
| const mrpt::slam::CSensoryFrame * | observation, | |||
| const bayes::CParticleFilter::TParticleFilterOptions & | PF_options | |||
| ) | [virtual] |
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 Sensorial Frame:
| 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. |
Reimplemented from mrpt::bayes::CParticleFilterCapable.
| void mrpt::slam::CMonteCarloLocalization3D::prediction_and_update_pfStandardProposal | ( | const mrpt::slam::CActionCollection * | action, | |
| const mrpt::slam::CSensoryFrame * | observation, | |||
| const bayes::CParticleFilter::TParticleFilterOptions & | PF_options | |||
| ) | [virtual] |
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 Sensorial Frame:
| 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. |
Reimplemented from mrpt::bayes::CParticleFilterCapable.
MCL parameters.
Definition at line 59 of file CMonteCarloLocalization3D.h.
| Page generated by Doxygen 1.6.1 for MRPT 0.9.0 SVN: at Mon Jun 7 06:47:58 UTC 2010 |