A set of common data shared by PF implementations for both SLAM and localization.
Definition at line 40 of file PF_implementations_data.h.
#include <mrpt/slam/PF_implementations_data.h>
Public Member Functions | |
PF_implementation () | |
Virtual methods that the PF_implementations assume exist. | |
virtual mrpt::math::TPose3D | getLastPose (const size_t i, bool &is_valid_pose) const =0 |
Return the last robot pose in the i'th particle; is_valid_pose will be false if there is no such last pose. More... | |
virtual void | PF_SLAM_implementation_custom_update_particle_with_new_pose (PARTICLE_TYPE *particleData, const mrpt::math::TPose3D &newPose) const =0 |
virtual 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 |
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< PARTICLE_TYPE >::CParticleList &particles, const mrpt::obs::CSensoryFrame *sf) const |
virtual bool | PF_SLAM_implementation_skipRobotMovement () const |
Make a specialization if needed, eg. More... | |
virtual 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 =0 |
Evaluate the observation likelihood for one particle at a given location. More... | |
|
inline |
Definition at line 43 of file PF_implementations_data.h.
|
pure virtual |
Return the last robot pose in the i'th particle; is_valid_pose will be false if there is no such last pose.
std::exception | on out-of-range particle index |
Implemented in mrpt::maps::CMultiMetricMapPDF, mrpt::slam::CMonteCarloLocalization2D, and mrpt::slam::CMonteCarloLocalization3D.
|
pure virtual |
Evaluate the observation likelihood for one particle at a given location.
Implemented in mrpt::maps::CMultiMetricMapPDF, mrpt::slam::CMonteCarloLocalization2D, and mrpt::slam::CMonteCarloLocalization3D.
|
pure virtual |
Referenced by mrpt::slam::PF_implementation< mrpt::poses::CPose2D, mrpt::poses::CPosePDFParticles >::PF_SLAM_implementation_replaceByNewParticleSet().
|
inlinevirtual |
Definition at line 179 of file PF_implementations_data.h.
|
inlinevirtual |
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.
|
inlinevirtual |
Make a specialization if needed, eg.
in the first step in SLAM.
Reimplemented in mrpt::maps::CMultiMetricMapPDF.
Definition at line 190 of file PF_implementations_data.h.
|
static |
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*" |
mrpt::obs::CActionRobotMovement2D mrpt::slam::PF_implementation< PARTICLE_TYPE, PDF_TYPE, CParticleList >::m_accumRobotMovement2D |
Definition at line 48 of file PF_implementations_data.h.
bool mrpt::slam::PF_implementation< PARTICLE_TYPE, PDF_TYPE, CParticleList >::m_accumRobotMovement2DIsValid = false |
Definition at line 49 of file PF_implementations_data.h.
mrpt::poses::CPose3DPDFGaussian mrpt::slam::PF_implementation< PARTICLE_TYPE, PDF_TYPE, CParticleList >::m_accumRobotMovement3D |
Definition at line 50 of file PF_implementations_data.h.
bool mrpt::slam::PF_implementation< PARTICLE_TYPE, PDF_TYPE, CParticleList >::m_accumRobotMovement3DIsValid = false |
Definition at line 51 of file PF_implementations_data.h.
mrpt::poses::CPoseRandomSampler mrpt::slam::PF_implementation< PARTICLE_TYPE, PDF_TYPE, CParticleList >::m_movementDrawer |
Used in al PF implementations.
Definition at line 55 of file PF_implementations_data.h.
|
mutable |
Auxiliary variable used in the "pfAuxiliaryPFOptimal" algorithm.
Definition at line 57 of file PF_implementations_data.h.
|
mutable |
Auxiliary variable used in the "pfAuxiliaryPFOptimal" algorithm.
Definition at line 64 of file PF_implementations_data.h.
|
mutable |
Auxiliary variable used in the "pfAuxiliaryPFOptimal" algorithm.
Definition at line 61 of file PF_implementations_data.h.
std::vector<bool> mrpt::slam::PF_implementation< PARTICLE_TYPE, PDF_TYPE, CParticleList >::m_pfAuxiliaryPFOptimal_maxLikMovementDrawHasBeenUsed |
Definition at line 65 of file PF_implementations_data.h.
|
mutable |
Auxiliary variable used in the "pfAuxiliaryPFStandard" algorithm.
Definition at line 59 of file PF_implementations_data.h.
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 |