Main MRPT website > C++ reference for MRPT 1.5.6
List of all members | Public Member Functions | Public Attributes | Static Protected Member Functions
mrpt::bayes::CParticleFilter::TParticleFilterOptions Struct Reference

Detailed Description

The configuration of a particle filter.

Definition at line 80 of file CParticleFilter.h.

#include <mrpt/bayes/CParticleFilter.h>

Inheritance diagram for mrpt::bayes::CParticleFilter::TParticleFilterOptions:
Inheritance graph

Public Member Functions

 TParticleFilterOptions ()
 Initilization of default parameters. More...
 
void loadFromConfigFile (const mrpt::utils::CConfigFileBase &source, const std::string &section) MRPT_OVERRIDE
 This method load the options from a ".ini"-like file or memory-stored string list. More...
 
void dumpToTextStream (mrpt::utils::CStream &out) const MRPT_OVERRIDE
 This method should clearly display all the contents of the structure in textual form, sending it to a CStream. More...
 
void loadFromConfigFileName (const std::string &config_file, const std::string &section)
 Behaves like loadFromConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to load the file. More...
 
virtual void saveToConfigFile (mrpt::utils::CConfigFileBase &target, const std::string &section) const
 This method saves the options to a ".ini"-like file or memory-stored string list. More...
 
void saveToConfigFileName (const std::string &config_file, const std::string &section) const
 Behaves like saveToConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to save the file. More...
 
void dumpToConsole () const
 Just like dumpToTextStream() but sending the text to the console (std::cout) More...
 

Public Attributes

bool adaptiveSampleSize
 A flag that indicates whether the CParticleFilterCapable object should perform adative sample size (default=false). More...
 
double BETA
 The resampling of particles will be performed when ESS (in range [0,1]) < BETA (default is 0.5) More...
 
unsigned int sampleSize
 The initial number of particles in the filter (it can change only if adaptiveSampleSize=true) (default=1) More...
 
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) More...
 
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). More...
 
TParticleFilterAlgorithm PF_algorithm
 The PF algorithm to use (default=pfStandardProposal) See TParticleFilterAlgorithm for the posibilities. More...
 
TParticleResamplingAlgorithm resamplingMethod
 The resampling algorithm to use (default=prMultinomial). More...
 
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. More...
 
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. More...
 
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. More...
 

Static Protected Member Functions

static void dumpVar_int (CStream &out, const char *varName, int v)
 Used to print variable info from dumpToTextStream with the macro LOADABLEOPTS_DUMP_VAR. More...
 
static void dumpVar_float (CStream &out, const char *varName, float v)
 
static void dumpVar_double (CStream &out, const char *varName, double v)
 
static void dumpVar_bool (CStream &out, const char *varName, bool v)
 
static void dumpVar_string (CStream &out, const char *varName, const std::string &v)
 

Constructor & Destructor Documentation

◆ TParticleFilterOptions()

CParticleFilter::TParticleFilterOptions::TParticleFilterOptions ( )

Initilization of default parameters.

Definition at line 106 of file CParticleFilter.cpp.

Member Function Documentation

◆ dumpToConsole()

void CLoadableOptions::dumpToConsole ( ) const
inherited

◆ dumpToTextStream()

void CParticleFilter::TParticleFilterOptions::dumpToTextStream ( mrpt::utils::CStream out) const
virtual

This method should clearly display all the contents of the structure in textual form, sending it to a CStream.

The default implementation in this base class relies on saveToConfigFile() to generate a plain text representation of all the parameters.

Reimplemented from mrpt::utils::CLoadableOptions.

Definition at line 123 of file CParticleFilter.cpp.

References mrpt::bayes::CParticleFilter::pfAuxiliaryPFOptimal, mrpt::bayes::CParticleFilter::pfAuxiliaryPFStandard, mrpt::bayes::CParticleFilter::pfOptimalProposal, mrpt::bayes::CParticleFilter::pfStandardProposal, mrpt::utils::CStream::printf(), mrpt::bayes::CParticleFilter::prMultinomial, mrpt::bayes::CParticleFilter::prResidual, mrpt::bayes::CParticleFilter::prStratified, and mrpt::bayes::CParticleFilter::prSystematic.

◆ dumpVar_bool()

void CLoadableOptions::dumpVar_bool ( CStream out,
const char *  varName,
bool  v 
)
staticprotectedinherited

◆ dumpVar_double()

void CLoadableOptions::dumpVar_double ( CStream out,
const char *  varName,
double  v 
)
staticprotectedinherited

◆ dumpVar_float()

void CLoadableOptions::dumpVar_float ( CStream out,
const char *  varName,
float  v 
)
staticprotectedinherited

◆ dumpVar_int()

void CLoadableOptions::dumpVar_int ( CStream out,
const char *  varName,
int  v 
)
staticprotectedinherited

Used to print variable info from dumpToTextStream with the macro LOADABLEOPTS_DUMP_VAR.

Definition at line 52 of file CLoadableOptions.cpp.

References LOADABLEOPTS_COLUMN_WIDTH, and mrpt::utils::CStream::printf().

◆ dumpVar_string()

void CLoadableOptions::dumpVar_string ( CStream out,
const char *  varName,
const std::string v 
)
staticprotectedinherited

◆ loadFromConfigFile()

void CParticleFilter::TParticleFilterOptions::loadFromConfigFile ( const mrpt::utils::CConfigFileBase source,
const std::string section 
)
virtual

This method load the options from a ".ini"-like file or memory-stored string list.

Only those parameters found in the given "section" and having the same name that the variable are loaded. Those not found in the file will stay with their previous values (usually the default values loaded at initialization). An example of an ".ini" file:

[section]
resolution = 0.10 // blah blah...
modeSelection = 1 // 0=blah, 1=blah,...
See also
loadFromConfigFileName, saveToConfigFile

Implements mrpt::utils::CLoadableOptions.

Definition at line 164 of file CParticleFilter.cpp.

References ASSERT_, MRPT_END, MRPT_LOAD_CONFIG_VAR, MRPT_LOAD_CONFIG_VAR_CAST_NO_DEFAULT, MRPT_LOAD_CONFIG_VAR_NO_DEFAULT, MRPT_START, and mrpt::bayes::CParticleFilter::pfAuxiliaryPFOptimal.

Referenced by mrpt::hmtslam::CHMTSLAM::loadOptions(), and run_test_pf_localization().

◆ loadFromConfigFileName()

void CLoadableOptions::loadFromConfigFileName ( const std::string config_file,
const std::string section 
)
inherited

Behaves like loadFromConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to load the file.

See also
loadFromConfigFile

Definition at line 23 of file CLoadableOptions.cpp.

References mrpt::utils::CLoadableOptions::loadFromConfigFile().

Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::loadParams().

◆ saveToConfigFile()

void CLoadableOptions::saveToConfigFile ( mrpt::utils::CConfigFileBase target,
const std::string section 
) const
virtualinherited

◆ saveToConfigFileName()

void CLoadableOptions::saveToConfigFileName ( const std::string config_file,
const std::string section 
) const
inherited

Behaves like saveToConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to save the file.

See also
saveToConfigFile, loadFromConfigFileName

Definition at line 39 of file CLoadableOptions.cpp.

References mrpt::utils::CLoadableOptions::saveToConfigFile().

Member Data Documentation

◆ adaptiveSampleSize

bool mrpt::bayes::CParticleFilter::TParticleFilterOptions::adaptiveSampleSize

◆ BETA

double mrpt::bayes::CParticleFilter::TParticleFilterOptions::BETA

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

Definition at line 88 of file CParticleFilter.h.

Referenced by mrpt::bayes::CParticleFilter::executeOn(), and mrpt::slam::PF_implementation< mrpt::poses::CPose3D, CMonteCarloLocalization3D >::PF_SLAM_implementation_pfAuxiliaryPFStandardAndOptimal().

◆ max_loglikelihood_dyn_range

double mrpt::bayes::CParticleFilter::TParticleFilterOptions::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.

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 102 of file CParticleFilter.h.

Referenced by mrpt::slam::PF_implementation< mrpt::poses::CPose3D, CMonteCarloLocalization3D >::PF_SLAM_aux_perform_one_rejection_sampling_step().

◆ PF_algorithm

TParticleFilterAlgorithm mrpt::bayes::CParticleFilter::TParticleFilterOptions::PF_algorithm

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

Definition at line 95 of file CParticleFilter.h.

Referenced by mrpt::bayes::CParticleFilter::executeOn(), and mrpt::bayes::CParticleFilterCapable::prediction_and_update().

◆ pfAuxFilterOptimal_MaximumSearchSamples

unsigned int mrpt::bayes::CParticleFilter::TParticleFilterOptions::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)

Definition at line 93 of file CParticleFilter.h.

Referenced by mrpt::hmtslam::CLSLAM_RBPF_2DLASER::particlesEvaluator_AuxPFOptimal(), mrpt::slam::PF_implementation< mrpt::poses::CPose3D, CMonteCarloLocalization3D >::PF_SLAM_particlesEvaluator_AuxPFOptimal(), mrpt::slam::PF_implementation< mrpt::poses::CPose3D, CMonteCarloLocalization3D >::PF_SLAM_particlesEvaluator_AuxPFStandard(), and mrpt::hmtslam::CLSLAM_RBPF_2DLASER::prediction_and_update_pfAuxiliaryPFOptimal().

◆ pfAuxFilterOptimal_MLE

bool mrpt::bayes::CParticleFilter::TParticleFilterOptions::pfAuxFilterOptimal_MLE

◆ pfAuxFilterStandard_FirstStageWeightsMonteCarlo

bool mrpt::bayes::CParticleFilter::TParticleFilterOptions::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.

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 109 of file CParticleFilter.h.

Referenced by mrpt::slam::PF_implementation< mrpt::poses::CPose3D, CMonteCarloLocalization3D >::PF_SLAM_particlesEvaluator_AuxPFStandard().

◆ powFactor

double mrpt::bayes::CParticleFilter::TParticleFilterOptions::powFactor

◆ resamplingMethod

TParticleResamplingAlgorithm mrpt::bayes::CParticleFilter::TParticleFilterOptions::resamplingMethod

◆ sampleSize

unsigned int mrpt::bayes::CParticleFilter::TParticleFilterOptions::sampleSize

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

Definition at line 89 of file CParticleFilter.h.




Page generated by Doxygen 1.8.14 for MRPT 1.5.6 Git: 4c65e8431 Tue Apr 24 08:18:17 2018 +0200 at lun oct 28 01:35:26 CET 2019