00001 /* +---------------------------------------------------------------------------+ 00002 | The Mobile Robot Programming Toolkit (MRPT) C++ library | 00003 | | 00004 | http://mrpt.sourceforge.net/ | 00005 | | 00006 | Copyright (C) 2005-2010 University of Malaga | 00007 | | 00008 | This software was written by the Machine Perception and Intelligent | 00009 | Robotics Lab, University of Malaga (Spain). | 00010 | Contact: Jose-Luis Blanco <jlblanco@ctima.uma.es> | 00011 | | 00012 | This file is part of the MRPT project. | 00013 | | 00014 | MRPT is free software: you can redistribute it and/or modify | 00015 | it under the terms of the GNU General Public License as published by | 00016 | the Free Software Foundation, either version 3 of the License, or | 00017 | (at your option) any later version. | 00018 | | 00019 | MRPT is distributed in the hope that it will be useful, | 00020 | but WITHOUT ANY WARRANTY; without even the implied warranty of | 00021 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the | 00022 | GNU General Public License for more details. | 00023 | | 00024 | You should have received a copy of the GNU General Public License | 00025 | along with MRPT. If not, see <http://www.gnu.org/licenses/>. | 00026 | | 00027 +---------------------------------------------------------------------------+ */ 00028 #ifndef CMonteCarloLocalization2D_H 00029 #define CMonteCarloLocalization2D_H 00030 00031 #include <mrpt/poses/CPosePDFParticles.h> 00032 #include <mrpt/slam/PF_implementations_data.h> 00033 #include <mrpt/slam/TMonteCarloLocalizationParams.h> 00034 00035 #include <mrpt/slam/link_pragmas.h> 00036 00037 namespace mrpt 00038 { 00039 namespace slam 00040 { 00041 class COccupancyGridMap2D; 00042 class CSensoryFrame; 00043 00044 using namespace mrpt::poses; 00045 using namespace mrpt::slam; 00046 using namespace mrpt::bayes; 00047 00048 /** Declares a class that represents a Probability Density Function (PDF) over a 2D pose (x,y,phi), using a set of weighted samples. 00049 * 00050 * This class also implements particle filtering for robot localization. See the MRPT 00051 * application "app/pf-localization" for an example of usage. 00052 * 00053 * \sa CMonteCarloLocalization3D, CPose2D, CPosePDF, CPoseGaussianPDF, CParticleFilterCapable 00054 */ 00055 class SLAM_IMPEXP CMonteCarloLocalization2D : 00056 public CPosePDFParticles, 00057 public PF_implementation<CPose2D> 00058 { 00059 public: 00060 TMonteCarloLocalizationParams options; //!< MCL parameters 00061 00062 /** Constructor 00063 * \param M The number of m_particles. 00064 */ 00065 CMonteCarloLocalization2D( size_t M = 1 ); 00066 00067 /** Destructor */ 00068 virtual ~CMonteCarloLocalization2D(); 00069 00070 /** Reset the PDF to an uniformly distributed one, but only in the free-space 00071 * of a given 2D occupancy-grid-map. Orientation is randomly generated in the whole 2*PI range. 00072 * \param theMap The occupancy grid map 00073 * \param freeCellsThreshold The minimum free-probability to consider a cell as empty (default is 0.7) 00074 * \param particlesCount If set to -1 the number of m_particles remains unchanged. 00075 * \param x_min The limits of the area to look for free cells. 00076 * \param x_max The limits of the area to look for free cells. 00077 * \param y_min The limits of the area to look for free cells. 00078 * \param y_max The limits of the area to look for free cells. 00079 * \param phi_min The limits of the area to look for free cells. 00080 * \param phi_max The limits of the area to look for free cells. 00081 * \sa resetDeterm32inistic 00082 * \exception std::exception On any error (no free cell found in map, map=NULL, etc...) 00083 */ 00084 void resetUniformFreeSpace( 00085 COccupancyGridMap2D *theMap, 00086 const double freeCellsThreshold = 0.7, 00087 const int particlesCount = -1, 00088 const double x_min = -1e10f, 00089 const double x_max = 1e10f, 00090 const double y_min = -1e10f, 00091 const double y_max = 1e10f, 00092 const double phi_min = -M_PI, 00093 const double phi_max = M_PI ); 00094 00095 /** Update the m_particles, predicting the posterior of robot pose and map after a movement command. 00096 * This method has additional configuration parameters in "options". 00097 * Performs the update stage of the RBPF, using the sensed Sensorial Frame: 00098 * 00099 * \param action This is a pointer to CActionCollection, containing the pose change the robot has been commanded. 00100 * \param observation This must be a pointer to a CSensoryFrame object, with robot sensed observations. 00101 * 00102 * \sa options 00103 */ 00104 void prediction_and_update_pfStandardProposal( 00105 const mrpt::slam::CActionCollection * action, 00106 const mrpt::slam::CSensoryFrame * observation, 00107 const bayes::CParticleFilter::TParticleFilterOptions &PF_options ); 00108 00109 /** Update the m_particles, predicting the posterior of robot pose and map after a movement command. 00110 * This method has additional configuration parameters in "options". 00111 * Performs the update stage of the RBPF, using the sensed Sensorial Frame: 00112 * 00113 * \param Action This is a pointer to CActionCollection, containing the pose change the robot has been commanded. 00114 * \param observation This must be a pointer to a CSensoryFrame object, with robot sensed observations. 00115 * 00116 * \sa options 00117 */ 00118 void prediction_and_update_pfAuxiliaryPFStandard( 00119 const mrpt::slam::CActionCollection * action, 00120 const mrpt::slam::CSensoryFrame * observation, 00121 const bayes::CParticleFilter::TParticleFilterOptions &PF_options ); 00122 00123 /** Update the m_particles, predicting the posterior of robot pose and map after a movement command. 00124 * This method has additional configuration parameters in "options". 00125 * Performs the update stage of the RBPF, using the sensed Sensorial Frame: 00126 * 00127 * \param Action This is a pointer to CActionCollection, containing the pose change the robot has been commanded. 00128 * \param observation This must be a pointer to a CSensoryFrame object, with robot sensed observations. 00129 * 00130 * \sa options 00131 */ 00132 void prediction_and_update_pfAuxiliaryPFOptimal( 00133 const mrpt::slam::CActionCollection * action, 00134 const mrpt::slam::CSensoryFrame * observation, 00135 const bayes::CParticleFilter::TParticleFilterOptions &PF_options ); 00136 00137 protected: 00138 /** \name Virtual methods that the PF_implementations assume exist. 00139 @{ */ 00140 /** Return a pointer to the last robot pose in the i'th particle (or NULL if it's a path and it's empty). */ 00141 const TPose3D * getLastPose(const size_t i) const; 00142 00143 void PF_SLAM_implementation_custom_update_particle_with_new_pose( 00144 CParticleDataContent *particleData, 00145 const TPose3D &newPose) const; 00146 00147 // We'll redefine this one: 00148 void PF_SLAM_implementation_replaceByNewParticleSet( 00149 CParticleList &old_particles, 00150 const vector<TPose3D> &newParticles, 00151 const vector_double &newParticlesWeight, 00152 const vector<size_t> &newParticlesDerivedFromIdx ) const; 00153 00154 /** Evaluate the observation likelihood for one particle at a given location */ 00155 double PF_SLAM_computeObservationLikelihoodForParticle( 00156 const CParticleFilter::TParticleFilterOptions &PF_options, 00157 const size_t particleIndexForMap, 00158 const CSensoryFrame &observation, 00159 const CPose3D &x ) const; 00160 /** @} */ 00161 00162 00163 }; // End of class def. 00164 00165 } // End of namespace 00166 } // End of namespace 00167 00168 #endif
| Page generated by Doxygen 1.6.1 for MRPT 0.9.0 SVN: at Mon Jun 7 06:47:58 UTC 2010 |
