class mrpt::hmtslam::CLSLAM_RBPF_2DLASER
Implements a 2D local SLAM method based on a RBPF over an occupancy grid map.
This class is used internally in mrpt::slam::CHMTSLAM
#include <mrpt/hmtslam/CHMTSLAM.h> class CLSLAM_RBPF_2DLASER: public mrpt::hmtslam::CLSLAMAlgorithmBase { public: // structs struct TPathBin; // construction CLSLAM_RBPF_2DLASER(CHMTSLAM* parent); // methods virtual void processOneLMH(CLocalMetricHypothesis* LMH, const mrpt::obs::CActionCollection::Ptr& act, const mrpt::obs::CSensoryFrame::Ptr& sf); virtual void prediction_and_update_pfAuxiliaryPFOptimal(CLocalMetricHypothesis* LMH, const mrpt::obs::CActionCollection* action, const mrpt::obs::CSensoryFrame* observation, const bayes::CParticleFilter::TParticleFilterOptions& PF_options); virtual void prediction_and_update_pfOptimalProposal(CLocalMetricHypothesis* LMH, const mrpt::obs::CActionCollection* action, const mrpt::obs::CSensoryFrame* observation, const bayes::CParticleFilter::TParticleFilterOptions& PF_options); };
Inherited Members
public: // methods virtual void processOneLMH(CLocalMetricHypothesis* LMH, const mrpt::obs::CActionCollection::Ptr& act, const mrpt::obs::CSensoryFrame::Ptr& sf) = 0; virtual void prediction_and_update_pfAuxiliaryPFOptimal(CLocalMetricHypothesis* LMH, const mrpt::obs::CActionCollection* action, const mrpt::obs::CSensoryFrame* observation, const bayes::CParticleFilter::TParticleFilterOptions& PF_options) = 0; virtual void prediction_and_update_pfOptimalProposal(CLocalMetricHypothesis* LMH, const mrpt::obs::CActionCollection* action, const mrpt::obs::CSensoryFrame* observation, const bayes::CParticleFilter::TParticleFilterOptions& PF_options) = 0;
Construction
CLSLAM_RBPF_2DLASER(CHMTSLAM* parent)
Constructor.
Methods
virtual void processOneLMH(CLocalMetricHypothesis* LMH, const mrpt::obs::CActionCollection::Ptr& act, const mrpt::obs::CSensoryFrame::Ptr& sf)
Main entry point from HMT-SLAM: process some actions & observations.
The passed action/observation will be deleted, so a copy must be made if necessary. This method must be in charge of updating the robot pose estimates and also to update the map when required.
Parameters:
LMH |
The local metric hypothesis which must be updated by this SLAM algorithm. |
act |
The action to process (or nullptr). |
sf |
The observations to process (or nullptr). |
virtual void prediction_and_update_pfAuxiliaryPFOptimal( CLocalMetricHypothesis* LMH, const mrpt::obs::CActionCollection* action, const mrpt::obs::CSensoryFrame* observation, const bayes::CParticleFilter::TParticleFilterOptions& PF_options )
The PF algorithm implementation.
The PF algorithm implementation for “optimal sampling for non-parametric observation models”.
virtual void prediction_and_update_pfOptimalProposal( CLocalMetricHypothesis* LMH, const mrpt::obs::CActionCollection* action, const mrpt::obs::CSensoryFrame* observation, const bayes::CParticleFilter::TParticleFilterOptions& PF_options )
The PF algorithm implementation.
The PF algorithm implementation for “optimal sampling” approximated with scan matching (Stachniss method)