Main MRPT website > C++ reference
MRPT logo
CMonteCarloLocalization2D.h
Go to the documentation of this file.
1 /* +---------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2014, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +---------------------------------------------------------------------------+ */
9 #ifndef CMonteCarloLocalization2D_H
10 #define CMonteCarloLocalization2D_H
11 
15 
16 #include <mrpt/slam/link_pragmas.h>
17 
18 namespace mrpt
19 {
20  /** \ingroup mrpt_slam_grp */
21  namespace slam
22  {
23  class COccupancyGridMap2D;
24  class CSensoryFrame;
25 
26  using namespace mrpt::poses;
27  using namespace mrpt::slam;
28  using namespace mrpt::bayes;
29 
30  /** Declares a class that represents a Probability Density Function (PDF) over a 2D pose (x,y,phi), using a set of weighted samples.
31  *
32  * This class also implements particle filtering for robot localization. See the MRPT
33  * application "app/pf-localization" for an example of usage.
34  *
35  * \sa CMonteCarloLocalization3D, CPose2D, CPosePDF, CPoseGaussianPDF, CParticleFilterCapable
36  * \ingroup mrpt_slam_grp
37  */
39  public CPosePDFParticles,
40  public PF_implementation<mrpt::poses::CPose2D,CMonteCarloLocalization2D>
41  {
42  public:
44 
45  /** Constructor
46  * \param M The number of m_particles.
47  */
48  CMonteCarloLocalization2D( size_t M = 1 );
49 
50  /** Destructor */
51  virtual ~CMonteCarloLocalization2D();
52 
53  /** Reset the PDF to an uniformly distributed one, but only in the free-space
54  * of a given 2D occupancy-grid-map. Orientation is randomly generated in the whole 2*PI range.
55  * \param theMap The occupancy grid map
56  * \param freeCellsThreshold The minimum free-probability to consider a cell as empty (default is 0.7)
57  * \param particlesCount If set to -1 the number of m_particles remains unchanged.
58  * \param x_min The limits of the area to look for free cells.
59  * \param x_max The limits of the area to look for free cells.
60  * \param y_min The limits of the area to look for free cells.
61  * \param y_max The limits of the area to look for free cells.
62  * \param phi_min The limits of the area to look for free cells.
63  * \param phi_max The limits of the area to look for free cells.
64  * \sa resetDeterm32inistic
65  * \exception std::exception On any error (no free cell found in map, map=NULL, etc...)
66  */
67  void resetUniformFreeSpace(
68  COccupancyGridMap2D *theMap,
69  const double freeCellsThreshold = 0.7,
70  const int particlesCount = -1,
71  const double x_min = -1e10f,
72  const double x_max = 1e10f,
73  const double y_min = -1e10f,
74  const double y_max = 1e10f,
75  const double phi_min = -M_PI,
76  const double phi_max = M_PI );
77 
78  /** Update the m_particles, predicting the posterior of robot pose and map after a movement command.
79  * This method has additional configuration parameters in "options".
80  * Performs the update stage of the RBPF, using the sensed CSensoryFrame:
81  *
82  * \param action This is a pointer to CActionCollection, containing the pose change the robot has been commanded.
83  * \param observation This must be a pointer to a CSensoryFrame object, with robot sensed observations.
84  *
85  * \sa options
86  */
87  void prediction_and_update_pfStandardProposal(
88  const mrpt::slam::CActionCollection * action,
89  const mrpt::slam::CSensoryFrame * observation,
91 
92  /** Update the m_particles, predicting the posterior of robot pose and map after a movement command.
93  * This method has additional configuration parameters in "options".
94  * Performs the update stage of the RBPF, using the sensed CSensoryFrame:
95  *
96  * \param Action This is a pointer to CActionCollection, containing the pose change the robot has been commanded.
97  * \param observation This must be a pointer to a CSensoryFrame object, with robot sensed observations.
98  *
99  * \sa options
100  */
101  void prediction_and_update_pfAuxiliaryPFStandard(
102  const mrpt::slam::CActionCollection * action,
103  const mrpt::slam::CSensoryFrame * observation,
105 
106  /** Update the m_particles, predicting the posterior of robot pose and map after a movement command.
107  * This method has additional configuration parameters in "options".
108  * Performs the update stage of the RBPF, using the sensed CSensoryFrame:
109  *
110  * \param Action This is a pointer to CActionCollection, containing the pose change the robot has been commanded.
111  * \param observation This must be a pointer to a CSensoryFrame object, with robot sensed observations.
112  *
113  * \sa options
114  */
115  void prediction_and_update_pfAuxiliaryPFOptimal(
116  const mrpt::slam::CActionCollection * action,
117  const mrpt::slam::CSensoryFrame * observation,
119 
120  //protected:
121  /** \name Virtual methods that the PF_implementations assume exist.
122  @{ */
123  /** Return a pointer to the last robot pose in the i'th particle (or NULL if it's a path and it's empty). */
124  const TPose3D * getLastPose(const size_t i) const;
125 
126  void PF_SLAM_implementation_custom_update_particle_with_new_pose(
127  CParticleDataContent *particleData,
128  const TPose3D &newPose) const;
129 
130  // We'll redefine this one:
131  void PF_SLAM_implementation_replaceByNewParticleSet(
132  CParticleList &old_particles,
133  const vector<TPose3D> &newParticles,
134  const vector<double> &newParticlesWeight,
135  const vector<size_t> &newParticlesDerivedFromIdx ) const;
136 
137  /** Evaluate the observation likelihood for one particle at a given location */
138  double PF_SLAM_computeObservationLikelihoodForParticle(
139  const CParticleFilter::TParticleFilterOptions &PF_options,
140  const size_t particleIndexForMap,
141  const CSensoryFrame &observation,
142  const mrpt::poses::CPose3D &x ) const;
143  /** @} */
144 
145 
146  }; // End of class def.
147 
148  } // End of namespace
149 } // End of namespace
150 
151 #endif
The struct for passing extra simulation parameters to the prediction stage when running a particle fi...
The namespace for Bayesian filtering algorithm: different particle filters and Kalman filter algorith...
TMonteCarloLocalizationParams options
MCL parameters.
#define M_PI
Definition: bits.h:65
This namespace contains algorithms for SLAM, localization, map building, representation of robot's ac...
Declares a class for storing a collection of robot actions.
A set of common data shared by PF implementations for both SLAM and localization. ...
Declares a class that represents a Probability Density Function (PDF) over a 2D pose (x...
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
Definition: CPoint.h:17
Declares a class that represents a Probability Density Function (PDF) over a 2D pose (x...
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
std::deque< CParticleData > CParticleList
Use this type to refer to the list of particles m_particles.
A class for storing an occupancy grid map.
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
Definition: CSensoryFrame.h:53
A class used to store a 2D pose.
Definition: CPose2D.h:36
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:69
The configuration of a particle filter.
Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).



Page generated by Doxygen 1.8.8 for MRPT 1.2.2 SVN:Unversioned directory at Tue Oct 14 02:14:08 UTC 2014