Main MRPT website > C++ reference
MRPT logo
Public Member Functions | Public Attributes

mrpt::bayes::CParticleFilter::TParticleFilterOptions Struct Reference


Detailed Description

The configuration of a particle filter.

Definition at line 103 of file CParticleFilter.h.

#include <mrpt/bayes/CParticleFilter.h>

Inheritance diagram for mrpt::bayes::CParticleFilter::TParticleFilterOptions:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 TParticleFilterOptions ()
 Initilization of default parameters.
void loadFromConfigFile (const mrpt::utils::CConfigFileBase &source, const std::string &section)
 See mrpt::utils::CLoadableOptions.
void dumpToTextStream (mrpt::utils::CStream &out) const
 See mrpt::utils::CLoadableOptions.

Public Attributes

bool adaptiveSampleSize
 A flag that indicates whether the CParticleFilterCapable object should perform adative sample size (default=false).
double BETA
 The resampling of particles will be performed when ESS (in range [0,1]) < BETA (default is 0.5)
unsigned int sampleSize
 The initial number of particles in the filter (it can change only if adaptiveSampleSize=true) (default=1)
unsigned int pfAuxFilterOptimal_MaximumSearchSamples
 In the algorithm "CParticleFilter::pfAuxiliaryPFOptimal" (and in "CParticleFilter::pfAuxiliaryPFStandard" only if pfAuxFilterStandard_FirstStageWeightsMonteCarlo = true) the number of samples for searching the maximum likelihood value and also to estimate the "first stage weights" (see papers!) (default=100)
double powFactor
 An optional step to "smooth" dramatic changes in the observation model to affect the variance of the particle weights, eg weight*=likelihood^powFactor (default=1 = no effects).
TParticleFilterAlgorithm PF_algorithm
 The PF algorithm to use (default=pfStandardProposal) See TParticleFilterAlgorithm for the posibilities.
TParticleResamplingAlgorithm resamplingMethod
 The resampling algorithm to use (default=prMultinomial).
double max_loglikelihood_dyn_range
 Only for PF_algorithm=pfAuxiliaryPFOptimal: If a given particle has a max_likelihood (from the a-priori estimate) below the maximum from all the samples - max_loglikelihood_dyn_range, then the particle is directly discarded.
bool pfAuxFilterStandard_FirstStageWeightsMonteCarlo
 Only for PF_algorithm==pfAuxiliaryPFStandard: If false, the APF will predict the first stage weights just at the mean of the prior of the next time step.
bool verbose
 Enable extra messages for each PF iteration (Default=false)
bool pfAuxFilterOptimal_MLE
 (Default=false) In the algorithm "CParticleFilter::pfAuxiliaryPFOptimal", if set to true, do not perform rejection sampling, but just the most-likely (ML) particle found in the preliminary weight-determination stage.

Constructor & Destructor Documentation

mrpt::bayes::CParticleFilter::TParticleFilterOptions::TParticleFilterOptions ( )

Initilization of default parameters.


Member Function Documentation

void mrpt::bayes::CParticleFilter::TParticleFilterOptions::dumpToTextStream ( mrpt::utils::CStream out) const [virtual]
void mrpt::bayes::CParticleFilter::TParticleFilterOptions::loadFromConfigFile ( const mrpt::utils::CConfigFileBase source,
const std::string &  section 
) [virtual]

Member Data Documentation

The resampling of particles will be performed when ESS (in range [0,1]) < BETA (default is 0.5)

Definition at line 126 of file CParticleFilter.h.

Referenced by mrpt::slam::PF_implementation< PARTICLE_TYPE, MYSELF >::PF_SLAM_implementation_pfAuxiliaryPFStandardAndOptimal().

Only for PF_algorithm=pfAuxiliaryPFOptimal: If a given particle has a max_likelihood (from the a-priori estimate) below the maximum from all the samples - max_loglikelihood_dyn_range, then the particle is directly discarded.

This is done to assure that the rejection sampling doesn't get stuck in an infinite loop trying to get an acceptable sample. Default = 15 (in logarithmic likelihood)

Definition at line 153 of file CParticleFilter.h.

Referenced by mrpt::slam::PF_implementation< PARTICLE_TYPE, MYSELF >::PF_SLAM_aux_perform_one_rejection_sampling_step().

The PF algorithm to use (default=pfStandardProposal) See TParticleFilterAlgorithm for the posibilities.

Definition at line 142 of file CParticleFilter.h.

In the algorithm "CParticleFilter::pfAuxiliaryPFOptimal" (and in "CParticleFilter::pfAuxiliaryPFStandard" only if pfAuxFilterStandard_FirstStageWeightsMonteCarlo = true) the number of samples for searching the maximum likelihood value and also to estimate the "first stage weights" (see papers!) (default=100)

Definition at line 134 of file CParticleFilter.h.

Referenced by mrpt::slam::PF_implementation< PARTICLE_TYPE, MYSELF >::PF_SLAM_particlesEvaluator_AuxPFOptimal(), and mrpt::slam::PF_implementation< PARTICLE_TYPE, MYSELF >::PF_SLAM_particlesEvaluator_AuxPFStandard().

Only for PF_algorithm==pfAuxiliaryPFStandard: If false, the APF will predict the first stage weights just at the mean of the prior of the next time step.

If true, these weights will be estimated as described in the papers for the "pfAuxiliaryPFOptimal" method, i.e. through a monte carlo simulation. In that case, "pfAuxFilterOptimal_MaximumSearchSamples" is the number of MC samples used.

Definition at line 160 of file CParticleFilter.h.

Referenced by mrpt::slam::PF_implementation< PARTICLE_TYPE, MYSELF >::PF_SLAM_particlesEvaluator_AuxPFStandard().

An optional step to "smooth" dramatic changes in the observation model to affect the variance of the particle weights, eg weight*=likelihood^powFactor (default=1 = no effects).

Definition at line 138 of file CParticleFilter.h.

Referenced by mrpt::slam::PF_implementation< PARTICLE_TYPE, MYSELF >::PF_SLAM_aux_perform_one_rejection_sampling_step(), and mrpt::slam::PF_implementation< PARTICLE_TYPE, MYSELF >::PF_SLAM_implementation_pfStandardProposal().

The resampling algorithm to use (default=prMultinomial).

Definition at line 146 of file CParticleFilter.h.

The initial number of particles in the filter (it can change only if adaptiveSampleSize=true) (default=1)

Definition at line 130 of file CParticleFilter.h.




Page generated by Doxygen 1.7.3 for MRPT 0.9.4 SVN:exported at Tue Jan 25 21:56:31 UTC 2011