class mrpt::hmtslam::CLSLAMAlgorithmBase

Virtual base for local SLAM methods, used in mrpt::slam::CHMTSLAM.

#include <mrpt/hmtslam/CHMTSLAM.h>

class CLSLAMAlgorithmBase
{
public:
    // construction

    CLSLAMAlgorithmBase(CHMTSLAM* parent);

    //
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;
};

// direct descendants

class CLSLAM_RBPF_2DLASER;

Construction

CLSLAMAlgorithmBase(CHMTSLAM* parent)

Constructor.

Methods

virtual void processOneLMH(CLocalMetricHypothesis* LMH, const mrpt::obs::CActionCollection::Ptr& act, const mrpt::obs::CSensoryFrame::Ptr& sf) = 0

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
    ) = 0

The PF algorithm implementation.

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

The PF algorithm implementation.