The configuration of a particle filter.
Definition at line 80 of file CParticleFilter.h.
#include <mrpt/bayes/CParticleFilter.h>
Public Member Functions | |
TParticleFilterOptions () | |
Initilization of default parameters. More... | |
void | loadFromConfigFile (const mrpt::utils::CConfigFileBase &source, const std::string §ion) 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 §ion) |
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 §ion) 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 §ion) 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) |
CParticleFilter::TParticleFilterOptions::TParticleFilterOptions | ( | ) |
Initilization of default parameters.
Definition at line 106 of file CParticleFilter.cpp.
|
inherited |
Just like dumpToTextStream() but sending the text to the console (std::cout)
Definition at line 47 of file CLoadableOptions.cpp.
References mrpt::utils::CLoadableOptions::dumpToTextStream(), and loadable_opts_my_cout.
Referenced by mrpt::hmtslam::CTopLCDetector_GridMatching::computeTopologicalObservationModel(), mrpt::hmtslam::CHMTSLAM::loadOptions(), and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::printParams().
|
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.
|
staticprotectedinherited |
Definition at line 67 of file CLoadableOptions.cpp.
References LOADABLEOPTS_COLUMN_WIDTH, and mrpt::utils::CStream::printf().
|
staticprotectedinherited |
Definition at line 62 of file CLoadableOptions.cpp.
References LOADABLEOPTS_COLUMN_WIDTH, and mrpt::utils::CStream::printf().
|
staticprotectedinherited |
Definition at line 57 of file CLoadableOptions.cpp.
References LOADABLEOPTS_COLUMN_WIDTH, and mrpt::utils::CStream::printf().
|
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().
|
staticprotectedinherited |
Definition at line 72 of file CLoadableOptions.cpp.
References LOADABLEOPTS_COLUMN_WIDTH, and mrpt::utils::CStream::printf().
|
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:
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().
|
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.
Definition at line 23 of file CLoadableOptions.cpp.
References mrpt::utils::CLoadableOptions::loadFromConfigFile().
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::loadParams().
|
virtualinherited |
This method saves the options to a ".ini"-like file or memory-stored string list.
Reimplemented in mrpt::vision::TMultiResDescOptions, mrpt::vision::TMultiResDescMatchOptions, mrpt::nav::CPTG_RobotShape_Circular, mrpt::nav::CPTG_RobotShape_Polygonal, mrpt::nav::CParameterizedTrajectoryGenerator, mrpt::nav::CAbstractPTGBasedReactive::TAbstractPTGNavigatorParams, mrpt::nav::CAbstractNavigator::TAbstractNavigatorParams, mrpt::nav::CPTG_DiffDrive_CollisionGridBased, mrpt::nav::CHolonomicND::TOptions, mrpt::nav::CWaypointsNavigator::TWaypointsNavigatorParams, mrpt::nav::CHolonomicFullEval::TOptions, mrpt::nav::CReactiveNavigationSystem::TReactiveNavigatorParams, mrpt::nav::CHolonomicVFF::TOptions, mrpt::nav::CMultiObjectiveMotionOptimizerBase::TParamsBase, mrpt::maps::CPointCloudFilterByDistance::TOptions, mrpt::nav::CPTG_DiffDrive_C, mrpt::nav::CPTG_DiffDrive_alpha, mrpt::nav::CMultiObjMotionOpt_Scalarization::TParams, mrpt::nav::CPTG_DiffDrive_CC, mrpt::nav::CPTG_DiffDrive_CCS, mrpt::nav::CPTG_DiffDrive_CS, and mrpt::nav::CPTG_Holo_Blend.
Definition at line 31 of file CLoadableOptions.cpp.
References MRPT_UNUSED_PARAM.
Referenced by mrpt::utils::CLoadableOptions::dumpToTextStream(), and mrpt::utils::CLoadableOptions::saveToConfigFileName().
|
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.
Definition at line 39 of file CLoadableOptions.cpp.
References mrpt::utils::CLoadableOptions::saveToConfigFile().
bool mrpt::bayes::CParticleFilter::TParticleFilterOptions::adaptiveSampleSize |
A flag that indicates whether the CParticleFilterCapable object should perform adative sample size (default=false).
Definition at line 87 of file CParticleFilter.h.
Referenced by mrpt::bayes::CParticleFilter::executeOn(), mrpt::bayes::CParticleFilterCapable::fastDrawSample(), mrpt::slam::PF_implementation< mrpt::poses::CPose3D, CMonteCarloLocalization3D >::PF_SLAM_implementation_pfAuxiliaryPFStandardAndOptimal(), mrpt::slam::PF_implementation< mrpt::poses::CPose3D, CMonteCarloLocalization3D >::PF_SLAM_implementation_pfStandardProposal(), mrpt::hmtslam::CLSLAM_RBPF_2DLASER::prediction_and_update_pfAuxiliaryPFOptimal(), mrpt::hmtslam::CLSLAM_RBPF_2DLASER::prediction_and_update_pfOptimalProposal(), and mrpt::bayes::CParticleFilterCapable::prepareFastDrawSample().
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().
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().
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().
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().
bool mrpt::bayes::CParticleFilter::TParticleFilterOptions::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.
Definition at line 111 of file CParticleFilter.h.
Referenced by mrpt::slam::PF_implementation< mrpt::poses::CPose3D, CMonteCarloLocalization3D >::PF_SLAM_aux_perform_one_rejection_sampling_step(), mrpt::slam::PF_implementation< mrpt::poses::CPose3D, CMonteCarloLocalization3D >::PF_SLAM_implementation_pfAuxiliaryPFStandardAndOptimal(), mrpt::slam::PF_implementation< mrpt::poses::CPose3D, CMonteCarloLocalization3D >::PF_SLAM_particlesEvaluator_AuxPFOptimal(), and mrpt::slam::PF_implementation< mrpt::poses::CPose3D, CMonteCarloLocalization3D >::PF_SLAM_particlesEvaluator_AuxPFStandard().
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().
double mrpt::bayes::CParticleFilter::TParticleFilterOptions::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).
Definition at line 94 of file CParticleFilter.h.
Referenced by mrpt::slam::PF_implementation< mrpt::poses::CPose3D, CMonteCarloLocalization3D >::PF_SLAM_aux_perform_one_rejection_sampling_step(), mrpt::slam::PF_implementation< mrpt::poses::CPose3D, CMonteCarloLocalization3D >::PF_SLAM_implementation_pfStandardProposal(), mrpt::hmtslam::CLSLAM_RBPF_2DLASER::prediction_and_update_pfAuxiliaryPFOptimal(), mrpt::maps::CMultiMetricMapPDF::prediction_and_update_pfOptimalProposal(), and mrpt::hmtslam::CLSLAM_RBPF_2DLASER::prediction_and_update_pfOptimalProposal().
TParticleResamplingAlgorithm mrpt::bayes::CParticleFilter::TParticleFilterOptions::resamplingMethod |
The resampling algorithm to use (default=prMultinomial).
Definition at line 96 of file CParticleFilter.h.
Referenced by mrpt::bayes::CParticleFilterCapable::fastDrawSample(), mrpt::bayes::CParticleFilterCapable::performResampling(), and mrpt::bayes::CParticleFilterCapable::prepareFastDrawSample().
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.5 Git: e06b63dbf Fri Dec 1 14:41:11 2017 +0100 at lun oct 28 01:31:35 CET 2019 |