MRPT  2.0.4
CParticleFilter.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2020, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 #pragma once
10 
14 
15 namespace mrpt
16 {
17 namespace obs
18 {
19 class CSensoryFrame;
20 class CActionCollection;
21 } // namespace obs
22 
23 /** The namespace for Bayesian filtering algorithm: different particle filters
24  * and Kalman filter algorithms. \ingroup mrpt_bayes_grp
25  */
26 namespace bayes
27 {
28 class CParticleFilterCapable;
29 
30 /** This class acts as a common interface to the different interfaces (see
31  *CParticleFilter::TParticleFilterAlgorithm) any bayes::CParticleFilterCapable
32  *class can implement: it is the invoker of particle filter algorithms.
33  * The particle filter is executed on a probability density function (PDF)
34  *described by a CParticleFilterCapable object, passed in the constructor or
35  *alternatively through the CParticleFilter::executeOn method.<br>
36  *
37  * For a complete example and further details, see the <a
38  *href="http://www.mrpt.org/Particle_Filter_Tutorial" >Particle Filter
39  *tutorial</a>.
40  *
41  * The basic SIR algorithm (pfStandardProposal) consists of:
42  * - Execute a prediction with the given "action".
43  * - Update the weights of the particles using the likelihood of the
44  *"observation".
45  * - Normalize weights.
46  * - Perform resampling if the ESS is below the threshold options.BETA.
47  *
48  * \ingroup mrpt_bayes_grp
49  * \sa mrpt::poses::CPoseParticlesPDF
50  */
52 {
53  public:
54  /** Defines different types of particle filter algorithms.
55  * The defined SIR implementations are:
56  * - pfStandardProposal: Standard proposal distribution + weights
57  *according to likelihood function.
58  * - pfAuxiliaryPFStandard: An auxiliary PF using the standard proposal
59  *distribution.
60  * - pfOptimalProposal: Use the optimal proposal distribution (where
61  *available!, usually this will perform approximations)
62  * - pfAuxiliaryPFOptimal: Use the optimal proposal and a auxiliary
63  *particle filter (see <a
64  *href="http://www.mrpt.org/Paper:An_Optimal_Filtering_Algorithm_for_Non-Parametric_Observation_Models_in_Robot_Localization_(ICRA_2008)"
65  *>paper</a>).
66  *
67  * See the theoretical discussion in <a
68  *href="http://www.mrpt.org/Resampling_Schemes" >resampling schemes</a>.
69  */
71  {
76  };
77 
78  /** Defines the different resampling algorithms.
79  * The implemented resampling methods are:
80  * - prMultinomial (Default): Uses standard select with replacement
81  *(draws
82  *M random uniform numbers)
83  * - prResidual: The residual or "remainder" method.
84  * - prStratified: The stratified resampling, where a uniform sample is
85  *drawn for each of M subdivisions of the range (0,1].
86  * - prSystematic: A single uniform sample is drawn in the range
87  *(0,1/M].
88  *
89  * See the theoretical discussion in <a
90  *href="http://www.mrpt.org/Resampling_Schemes" >resampling schemes</a>.
91  */
93  {
98  };
99 
100  /** The configuration of a particle filter.
101  */
103  {
104  public:
105  // See base docs:
106  void loadFromConfigFile(
107  const mrpt::config::CConfigFileBase& source,
108  const std::string& section) override;
109  void saveToConfigFile(
111  const std::string& section) const override;
112 
113  /** A flag that indicates whether the CParticleFilterCapable object
114  * should perform adative sample size (default=false). */
115  bool adaptiveSampleSize{false};
116  /** The resampling of particles will be performed when ESS (in range
117  * [0,1]) < BETA (default is 0.5) */
118  double BETA{0.5};
119  /** The initial number of particles in the filter (it can change only if
120  * adaptiveSampleSize=true) (default=1) */
121  unsigned int sampleSize{1};
122 
123  /** In the algorithm "CParticleFilter::pfAuxiliaryPFOptimal" (and in
124  * "CParticleFilter::pfAuxiliaryPFStandard" only if
125  * pfAuxFilterStandard_FirstStageWeightsMonteCarlo = true) the number of
126  * samples for searching the maximum likelihood value and also to
127  * estimate the "first stage weights" (see papers!) (default=100)
128  */
130  /** An optional step to "smooth" dramatic changes in the observation
131  * model to affect the variance of the particle weights, eg
132  * weight*=likelihood^powFactor (default=1 = no effects). */
133  double powFactor{1};
134  /** The PF algorithm to use (default=pfStandardProposal) See
135  * TParticleFilterAlgorithm for the possibilities. */
137  /** The resampling algorithm to use (default=prMultinomial). */
139 
140  /** Only for PF_algorithm=pfAuxiliaryPFOptimal: If a given particle has
141  * a max_likelihood (from the a-priori estimate) below the maximum from
142  * all the samples - max_loglikelihood_dyn_range, then the particle is
143  * directly discarded.
144  * This is done to assure that the rejection sampling doesn't get
145  * stuck in an infinite loop trying to get an acceptable sample.
146  * Default = 15 (in logarithmic likelihood)
147  */
149 
150  /** Only for PF_algorithm==pfAuxiliaryPFStandard:
151  * If false, the APF will predict the first stage weights just at the
152  * mean of the prior of the next time step.
153  * If true, these weights will be estimated as described in the papers
154  * for the "pfAuxiliaryPFOptimal" method, i.e. through a monte carlo
155  * simulation.
156  * In that case, "pfAuxFilterOptimal_MaximumSearchSamples" is the
157  * number of MC samples used.
158  */
160 
161  /** (Default=false) In the algorithm
162  * "CParticleFilter::pfAuxiliaryPFOptimal", if set to true, do not
163  * perform rejection sampling, but just the most-likely (ML) particle
164  * found in the preliminary weight-determination stage. */
166  };
167 
168  /** Statistics for being returned from the "execute" method. */
170  {
173  };
174 
175  /** Default constructor.
176  * After creating the PF object, set the options in
177  * CParticleFilter::m_options, then execute steps through
178  * CParticleFilter::executeOn.
179  */
180  CParticleFilter();
181 
182  ~CParticleFilter() override = default;
183  /** Executes a complete prediction + update step of the selected particle
184  * filtering algorithm.
185  * The member CParticleFilter::m_options must be set before calling this
186  * to settle the algorithm parameters.
187  *
188  * \param obj The object representing the probability distribution
189  * function (PDF) which apply the particle filter algorithm to.
190  * \param action A pointer to an action in the form of a
191  * CActionCollection,
192  * or nullptr if there is no action.
193  * \param observation A pointer to observations in the form of a
194  * CSensoryFrame, or nullptr if there is no observation.
195  * \param stats An output structure for gathering statistics of the particle
196  * filter execution, or set to nullptr if you do not need it (see
197  * CParticleFilter::TParticleFilterStats).
198  *
199  * \sa CParticleFilterCapable, executeOn
200  */
201  void executeOn(
203  const mrpt::obs::CSensoryFrame* observation,
204  TParticleFilterStats* stats = nullptr);
205 
206  /** The options to be used in the PF, must be set before executing any step
207  * of the particle filter.
208  */
210 
211 }; // End of class def.
212 
213 } // namespace bayes
214 } // namespace mrpt
215 
222 
223 MRPT_ENUM_TYPE_BEGIN(mrpt::bayes::CParticleFilter::TParticleResamplingAlgorithm)
224 MRPT_FILL_ENUM_MEMBER(mrpt::bayes::CParticleFilter, prMultinomial);
225 MRPT_FILL_ENUM_MEMBER(mrpt::bayes::CParticleFilter, prResidual);
226 MRPT_FILL_ENUM_MEMBER(mrpt::bayes::CParticleFilter, prStratified);
227 MRPT_FILL_ENUM_MEMBER(mrpt::bayes::CParticleFilter, prSystematic);
~CParticleFilter() override=default
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string &section) override
This method load the options from a ".ini"-like file or memory-stored string list.
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
unsigned int pfAuxFilterOptimal_MaximumSearchSamples
In the algorithm "CParticleFilter::pfAuxiliaryPFOptimal" (and in "CParticleFilter::pfAuxiliaryPFStand...
MRPT_FILL_ENUM_MEMBER(mrpt::bayes::CParticleFilter, pfStandardProposal)
Statistics for being returned from the "execute" method.
Declares a class for storing a collection of robot actions.
void saveToConfigFile(mrpt::config::CConfigFileBase &target, const std::string &section) const override
This method saves the options to a ".ini"-like file or memory-stored string list. ...
This class allows loading and storing values and vectors of different types from a configuration text...
TParticleResamplingAlgorithm
Defines the different resampling algorithms.
TParticleResamplingAlgorithm resamplingMethod
The resampling algorithm to use (default=prMultinomial).
Versatile class for consistent logging and management of output messages.
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
Definition: CSensoryFrame.h:51
This virtual class defines the interface that any particles based PDF class must implement in order t...
#define MRPT_ENUM_TYPE_END()
Definition: TEnumType.h:78
This class acts as a common interface to the different interfaces (see CParticleFilter::TParticleFilt...
bool pfAuxFilterStandard_FirstStageWeightsMonteCarlo
Only for PF_algorithm==pfAuxiliaryPFStandard: If false, the APF will predict the first stage weights ...
double BETA
The resampling of particles will be performed when ESS (in range [0,1]) < BETA (default is 0...
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
void executeOn(CParticleFilterCapable &obj, const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, TParticleFilterStats *stats=nullptr)
Executes a complete prediction + update step of the selected particle filtering algorithm.
TParticleFilterAlgorithm
Defines different types of particle filter algorithms.
double max_loglikelihood_dyn_range
Only for PF_algorithm=pfAuxiliaryPFOptimal: If a given particle has a max_likelihood (from the a-prio...
double powFactor
An optional step to "smooth" dramatic changes in the observation model to affect the variance of the ...
The configuration of a particle filter.
CParticleFilter()
Default constructor.
unsigned int sampleSize
The initial number of particles in the filter (it can change only if adaptiveSampleSize=true) (defaul...
bool pfAuxFilterOptimal_MLE
(Default=false) In the algorithm "CParticleFilter::pfAuxiliaryPFOptimal", if set to true...
#define MRPT_ENUM_TYPE_BEGIN(_ENUM_TYPE_WITH_NS)
Definition: TEnumType.h:62
CParticleFilter::TParticleFilterOptions m_options
The options to be used in the PF, must be set before executing any step of the particle filter...
TParticleFilterAlgorithm PF_algorithm
The PF algorithm to use (default=pfStandardProposal) See TParticleFilterAlgorithm for the possibiliti...
bool adaptiveSampleSize
A flag that indicates whether the CParticleFilterCapable object should perform adative sample size (d...



Page generated by Doxygen 1.8.14 for MRPT 2.0.4 Git: 33de1d0ad Sat Jun 20 11:02:42 2020 +0200 at sáb jun 20 17:35:17 CEST 2020