MRPT  2.0.0
CMonteCarloLocalization3D.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 
11 #include <mrpt/obs/obs_frwds.h>
15 
16 namespace mrpt::slam
17 {
18 /** Declares a class that represents a Probability Density Function (PDF) over a
19  * 3D pose (x,y,phi,yaw,pitch,roll), using a set of weighted samples.
20  *
21  * This class also implements particle filtering for robot localization. See
22  * the MRPT
23  * application "app/pf-localization" for an example of usage.
24  *
25  * \sa CMonteCarloLocalization2D, CPose2D, CPosePDF, CPoseGaussianPDF,
26  * CParticleFilterCapable
27  * \ingroup mrpt_slam_grp
28  */
31  public PF_implementation<
32  mrpt::math::TPose3D, CMonteCarloLocalization3D,
33  mrpt::bayes::particle_storage_mode::VALUE>
34 {
35  public:
36  /** MCL parameters */
38 
39  /** Constructor
40  * \param M The number of m_particles.
41  */
42  CMonteCarloLocalization3D(size_t M = 1);
43 
44  /** Update the m_particles, predicting the posterior of robot pose and map
45  * after a movement command.
46  * This method has additional configuration parameters in "options".
47  * Performs the update stage of the RBPF, using the sensed CSensoryFrame:
48  *
49  * \param action This is a pointer to CActionCollection, containing the
50  * pose change the robot has been commanded.
51  * \param observation This must be a pointer to a CSensoryFrame object,
52  * with robot sensed observations.
53  *
54  * \sa options
55  */
57  const mrpt::obs::CActionCollection* action,
58  const mrpt::obs::CSensoryFrame* observation,
60  override;
61 
62  /** Update the m_particles, predicting the posterior of robot pose and map
63  * after a movement command.
64  * This method has additional configuration parameters in "options".
65  * Performs the update stage of the RBPF, using the sensed CSensoryFrame:
66  *
67  * \param Action This is a pointer to CActionCollection, containing the
68  * pose change the robot has been commanded.
69  * \param observation This must be a pointer to a CSensoryFrame object,
70  * with robot sensed observations.
71  *
72  * \sa options
73  */
75  const mrpt::obs::CActionCollection* action,
76  const mrpt::obs::CSensoryFrame* observation,
78  override;
79 
80  /** Update the m_particles, predicting the posterior of robot pose and map
81  * after a movement command.
82  * This method has additional configuration parameters in "options".
83  * Performs the update stage of the RBPF, using the sensed CSensoryFrame:
84  *
85  * \param Action This is a pointer to CActionCollection, containing the
86  * pose change the robot has been commanded.
87  * \param observation This must be a pointer to a CSensoryFrame object,
88  * with robot sensed observations.
89  *
90  * \sa options
91  */
93  const mrpt::obs::CActionCollection* action,
94  const mrpt::obs::CSensoryFrame* observation,
96  override;
97 
98  /** \name Virtual methods that the PF_implementations assume exist.
99  @{ */
100  /** Return the robot pose for the i'th particle. is_valid is
101  * always true in this class. */
103  const size_t i, bool& is_valid_pose) const override;
104 
106  CParticleDataContent* particleData,
107  const mrpt::math::TPose3D& newPose) const override;
108 
109  // We'll redefine this one:
111  CParticleList& old_particles,
112  const std::vector<mrpt::math::TPose3D>& newParticles,
113  const std::vector<double>& newParticlesWeight,
114  const std::vector<size_t>& newParticlesDerivedFromIdx) const override;
115 
116  /** Evaluate the observation likelihood for one particle at a given location
117  */
120  const size_t particleIndexForMap,
121  const mrpt::obs::CSensoryFrame& observation,
122  const mrpt::poses::CPose3D& x) const override;
123  /** @} */
124 
125 }; // End of class def.
126 
127 } // namespace mrpt::slam
The struct for passing extra simulation parameters to the prediction stage when running a particle fi...
void PF_SLAM_implementation_replaceByNewParticleSet(CParticleList &old_particles, const std::vector< mrpt::math::TPose3D > &newParticles, const std::vector< double > &newParticlesWeight, const std::vector< size_t > &newParticlesDerivedFromIdx) const override
void prediction_and_update_pfStandardProposal(const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options) override
Update the m_particles, predicting the posterior of robot pose and map after a movement command...
Declares a class for storing a collection of robot actions.
A set of common data shared by PF implementations for both SLAM and localization. ...
void prediction_and_update_pfAuxiliaryPFStandard(const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options) override
Update the m_particles, predicting the posterior of robot pose and map after a movement command...
TMonteCarloLocalizationParams options
MCL parameters.
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
Definition: CSensoryFrame.h:51
std::deque< CParticleData > CParticleList
Use this type to refer to the list of particles m_particles.
Declares a class that represents a Probability Density Function (PDF) over a 3D pose (x...
void PF_SLAM_implementation_custom_update_particle_with_new_pose(CParticleDataContent *particleData, const mrpt::math::TPose3D &newPose) const override
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:85
The configuration of a particle filter.
Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).
Definition: TPose3D.h:24
void prediction_and_update_pfAuxiliaryPFOptimal(const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options) override
Update the m_particles, predicting the posterior of robot pose and map after a movement command...
mrpt::math::TPose3D getLastPose(const size_t i, bool &is_valid_pose) const override
Return the robot pose for the i&#39;th particle.
double PF_SLAM_computeObservationLikelihoodForParticle(const mrpt::bayes::CParticleFilter::TParticleFilterOptions &PF_options, const size_t particleIndexForMap, const mrpt::obs::CSensoryFrame &observation, const mrpt::poses::CPose3D &x) const override
Evaluate the observation likelihood for one particle at a given location.
Declares a class that represents a Probability Density function (PDF) of a 3D pose.
mrpt::math::TPose3D CParticleDataContent
This is the type inside the corresponding CParticleData class.



Page generated by Doxygen 1.8.14 for MRPT 2.0.0 Git: b38439d21 Tue Mar 31 19:58:06 2020 +0200 at miƩ abr 1 00:50:30 CEST 2020