Virtual base for local SLAM methods, used in mrpt::slam::CHMTSLAM.
Definition at line 511 of file CHMTSLAM.h.
#include <mrpt/hmtslam/CHMTSLAM.h>
Public Member Functions | |
CLSLAMAlgorithmBase (CHMTSLAM *parent) | |
Constructor. | |
virtual | ~CLSLAMAlgorithmBase () |
Destructor. | |
virtual void | processOneLMH (CLocalMetricHypothesis *LMH, const CActionCollectionPtr &act, const CSensoryFramePtr &sf)=0 |
Main entry point from HMT-SLAM: process some actions & observations. | |
virtual void | prediction_and_update_pfAuxiliaryPFOptimal (CLocalMetricHypothesis *LMH, const mrpt::slam::CActionCollection *action, const mrpt::slam::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options)=0 |
The PF algorithm implementation. | |
virtual void | prediction_and_update_pfOptimalProposal (CLocalMetricHypothesis *LMH, const mrpt::slam::CActionCollection *action, const mrpt::slam::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options)=0 |
The PF algorithm implementation. | |
Protected Attributes | |
safe_ptr< CHMTSLAM > | m_parent |
Friends | |
class HMTSLAM_IMPEXP | CLocalMetricHypothesis |
mrpt::hmtslam::CLSLAMAlgorithmBase::CLSLAMAlgorithmBase | ( | CHMTSLAM * | parent | ) | [inline] |
Constructor.
Definition at line 520 of file CHMTSLAM.h.
virtual mrpt::hmtslam::CLSLAMAlgorithmBase::~CLSLAMAlgorithmBase | ( | ) | [inline, virtual] |
Destructor.
Definition at line 524 of file CHMTSLAM.h.
virtual void mrpt::hmtslam::CLSLAMAlgorithmBase::prediction_and_update_pfAuxiliaryPFOptimal | ( | CLocalMetricHypothesis * | LMH, |
const mrpt::slam::CActionCollection * | action, | ||
const mrpt::slam::CSensoryFrame * | observation, | ||
const bayes::CParticleFilter::TParticleFilterOptions & | PF_options | ||
) | [pure virtual] |
The PF algorithm implementation.
Implemented in mrpt::hmtslam::CLSLAM_RBPF_2DLASER.
virtual void mrpt::hmtslam::CLSLAMAlgorithmBase::prediction_and_update_pfOptimalProposal | ( | CLocalMetricHypothesis * | LMH, |
const mrpt::slam::CActionCollection * | action, | ||
const mrpt::slam::CSensoryFrame * | observation, | ||
const bayes::CParticleFilter::TParticleFilterOptions & | PF_options | ||
) | [pure virtual] |
The PF algorithm implementation.
Implemented in mrpt::hmtslam::CLSLAM_RBPF_2DLASER.
virtual void mrpt::hmtslam::CLSLAMAlgorithmBase::processOneLMH | ( | CLocalMetricHypothesis * | LMH, |
const CActionCollectionPtr & | act, | ||
const CSensoryFramePtr & | sf | ||
) | [pure virtual] |
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.
LMH | The local metric hypothesis which must be updated by this SLAM algorithm. |
act | The action to process (or NULL). |
sf | The observations to process (or NULL). |
Implemented in mrpt::hmtslam::CLSLAM_RBPF_2DLASER.
friend class HMTSLAM_IMPEXP CLocalMetricHypothesis [friend] |
Reimplemented in mrpt::hmtslam::CLSLAM_RBPF_2DLASER.
Definition at line 513 of file CHMTSLAM.h.
safe_ptr<CHMTSLAM> mrpt::hmtslam::CLSLAMAlgorithmBase::m_parent [protected] |
Definition at line 515 of file CHMTSLAM.h.
Page generated by Doxygen 1.7.3 for MRPT 0.9.4 SVN: at Sat Mar 26 06:16:28 UTC 2011 |