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 CICP_H 00029 #define CICP_H 00030 00031 #include <mrpt/slam/CMetricMapsAlignmentAlgorithm.h> 00032 #include <mrpt/utils/CLoadableOptions.h> 00033 00034 namespace mrpt 00035 { 00036 namespace poses 00037 { 00038 class CPosePDFParticles; 00039 } 00040 00041 namespace slam 00042 { 00043 using namespace poses; 00044 00045 /** The ICP algorithm selection, used in mrpt::slam::CICP::options. 00046 * For details on the algorithms refer to http://www.mrpt.org/Scan_Matching_Algorithms 00047 */ 00048 enum TICPAlgorithm 00049 { 00050 icpClassic = 0, 00051 icpLevenbergMarquardt, 00052 icpIKF 00053 }; 00054 00055 /** Several implementations of ICP (Iterative closest point) algorithms for aligning two point maps. 00056 * 00057 * See CICP::AlignPDF for the entry point of the algorithm, and CICP::TConfigParams for all the parameters to the method. 00058 * The algorithm has been exteneded with multihypotheses-support for the correspondences, which generates a Sum-of-Gaussians (SOG) 00059 * PDF as output. See scan_matching::robustRigidTransformation. 00060 * 00061 * For further details on the method, check the wiki: 00062 * http://www.mrpt.org/Scan_Matching_Algorithms 00063 * 00064 * \sa CMetricMapsAlignmentAlgorithm 00065 */ 00066 class SLAM_IMPEXP CICP : public CMetricMapsAlignmentAlgorithm 00067 { 00068 public: 00069 /** The ICP algorithm configuration data 00070 */ 00071 class SLAM_IMPEXP TConfigParams : public utils::CLoadableOptions 00072 { 00073 public: 00074 /** Initializer for default values: 00075 */ 00076 TConfigParams(); 00077 00078 /** See utils::CLoadableOptions 00079 */ 00080 void loadFromConfigFile( 00081 const mrpt::utils::CConfigFileBase &source, 00082 const std::string §ion); 00083 00084 /** See utils::CLoadableOptions 00085 */ 00086 void dumpToTextStream(CStream &out) const; 00087 00088 00089 /** The algorithm to use (default: icpClassic) 00090 * See http://www.mrpt.org/Scan_Matching_Algorithms for details. 00091 */ 00092 TICPAlgorithm ICP_algorithm; 00093 00094 /** The usual approach: to consider only the closest correspondence for each local point (Default to true) 00095 */ 00096 bool onlyClosestCorrespondences; 00097 00098 /** Apart of "onlyClosestCorrespondences=true", if this option is enabled only the closest correspondence for each reference point will be kept (default=false). 00099 */ 00100 bool onlyUniqueRobust; 00101 00102 /** Maximum number of iterations to run. 00103 */ 00104 unsigned int maxIterations; 00105 00106 /** Initial threshold distance for two points to become a correspondence. 00107 */ 00108 float thresholdDist,thresholdAng; 00109 00110 /** The scale factor for threshold everytime convergence is achieved. 00111 */ 00112 float ALFA; 00113 00114 /** The size for threshold such that iterations will stop, since it is considered precise enough. 00115 */ 00116 float smallestThresholdDist; 00117 00118 /** This is the normalization constant \f$ \sigma^2_p \f$ that is used to scale the whole 3x3 covariance. 00119 * This has a default value of \f$ (0.02)^2 \f$, that is, a 2cm sigma. 00120 * See the paper: .... 00121 */ 00122 float covariance_varPoints; 00123 00124 /** Perform a RANSAC step after the ICP convergence, to obtain a better estimation of the pose PDF. 00125 */ 00126 bool doRANSAC; 00127 00128 /** RANSAC-step options: 00129 * \sa CICP::robustRigidTransformation 00130 */ 00131 unsigned int ransac_minSetSize,ransac_maxSetSize,ransac_nSimulations; 00132 00133 /** RANSAC-step options: 00134 * \sa CICP::robustRigidTransformation 00135 */ 00136 float ransac_mahalanobisDistanceThreshold; 00137 00138 /** RANSAC-step option: The standard deviation in X,Y of landmarks/points which are being matched (used to compute covariances in the SoG) 00139 * \sa CICP::robustRigidTransformation 00140 */ 00141 float normalizationStd; 00142 00143 /** RANSAC-step options: 00144 * \sa CICP::robustRigidTransformation 00145 */ 00146 bool ransac_fuseByCorrsMatch; 00147 00148 /** RANSAC-step options: 00149 * \sa CICP::robustRigidTransformation 00150 */ 00151 float ransac_fuseMaxDiffXY, ransac_fuseMaxDiffPhi; 00152 00153 /** Cauchy kernel rho, for estimating the optimal transformation covariance, in meters (default = 0.07m). 00154 */ 00155 float kernel_rho; 00156 00157 /** Whether to use kernel_rho to smooth distances, or use distances directly (default=true) 00158 */ 00159 bool use_kernel; 00160 00161 /** The size of the perturbance in x & y used to estimate the Jacobians of the square error (in LM & IKF methods, default=0.05). 00162 */ 00163 float Axy_aprox_derivatives; 00164 00165 /** The initial value of the lambda parameter in the LM method (default=1e-4). 00166 */ 00167 float LM_initial_lambda; 00168 00169 }; 00170 00171 TConfigParams options; //!< The options employed by the ICP align. 00172 00173 00174 /** Constructor with the default options */ 00175 CICP() : options() { } 00176 /** Constructor that directly set the ICP params from a given struct \sa options */ 00177 CICP(const TConfigParams &icpParams) : options(icpParams) { } 00178 00179 virtual ~CICP() { } //!< Destructor 00180 00181 00182 /** The ICP algorithm return information. 00183 */ 00184 struct SLAM_IMPEXP TReturnInfo 00185 { 00186 TReturnInfo() : 00187 cbSize(sizeof(TReturnInfo)), 00188 nIterations(0), 00189 goodness(0), 00190 quality(0) 00191 { 00192 } 00193 00194 /** Size in bytes of this struct: Must be set correctly before using it */ 00195 unsigned int cbSize; 00196 00197 /** The number of executed iterations until convergence. 00198 */ 00199 unsigned short nIterations; 00200 00201 /** A goodness measure for the alignment, it is a [0,1] range indicator of percentage of correspondences. 00202 */ 00203 float goodness; 00204 00205 /** A measure of the 'quality' of the local minimum of the sqr. error found by the method. 00206 * Higher values are better. Low values will be found in ill-conditioned situations (e.g. a corridor). 00207 */ 00208 float quality; 00209 }; 00210 00211 /** An implementation of CMetricMapsAlignmentAlgorithm for the case of a point maps and a occupancy grid/point map. 00212 * 00213 * This method computes the PDF of the displacement (relative pose) between 00214 * two maps: <b>the relative pose of m2 with respect to m1</b>. This pose 00215 * is returned as a PDF rather than a single value. 00216 * 00217 * \note This method can be configurated with "CICP::options" 00218 * \note The output PDF is a CPosePDFGaussian if "doRANSAC=false", or a CPosePDFSOG otherwise. 00219 * 00220 * \param m1 [IN] The first map (CAN BE A mrpt::poses::CPointsMap derived class or a mrpt::slam::COccupancyGrid2D class) 00221 * \param m2 [IN] The second map. (MUST BE A mrpt::poses::CPointsMap derived class)The pose of this map respect to m1 is to be estimated. 00222 * \param initialEstimationPDF [IN] An initial gross estimation for the displacement. 00223 * \param runningTime [OUT] A pointer to a container for obtaining the algorithm running time in seconds, or NULL if you don't need it. 00224 * \param info [OUT] A pointer to a CICP::TReturnInfo, or NULL if it isn't needed. 00225 * 00226 * \return A smart pointer to the output estimated pose PDF. 00227 * 00228 * \sa CMetricMapsAlignmentAlgorithm, CICP::options, CICP::TReturnInfo 00229 */ 00230 CPosePDFPtr AlignPDF( 00231 const CMetricMap *m1, 00232 const CMetricMap *m2, 00233 const CPosePDFGaussian &initialEstimationPDF, 00234 float *runningTime = NULL, 00235 void *info = NULL ); 00236 00237 /** Align a pair of metric maps, aligning the full 6D pose. 00238 * The meaning of some parameters are implementation dependant, 00239 * so look at the derived classes for more details. 00240 * The goal is to find a PDF for the pose displacement between 00241 * maps, that is, <b>the pose of m2 relative to m1</b>. This pose 00242 * is returned as a PDF rather than a single value. 00243 * 00244 * \note This method can be configurated with a "options" structure in the implementation classes. 00245 * 00246 * \param m1 [IN] The first map (MUST BE A COccupancyGridMap2D derived class) 00247 * \param m2 [IN] The second map. (MUST BE A CPointsMap derived class) The pose of this map respect to m1 is to be estimated. 00248 * \param initialEstimationPDF [IN] An initial gross estimation for the displacement. 00249 * \param runningTime [OUT] A pointer to a container for obtaining the algorithm running time in seconds, or NULL if you don't need it. 00250 * \param info [OUT] See derived classes for details, or NULL if it isn't needed. 00251 * 00252 * \return A smart pointer to the output estimated pose PDF. 00253 * \sa CICP 00254 */ 00255 CPose3DPDFPtr Align3DPDF( 00256 const CMetricMap *m1, 00257 const CMetricMap *m2, 00258 const CPose3DPDFGaussian &initialEstimationPDF, 00259 float *runningTime = NULL, 00260 void *info = NULL ); 00261 00262 00263 protected: 00264 /** Computes: 00265 * \f[ K(x^2) = \frac{x^2}{x^2+\rho^2} \f] 00266 * or just return the input if options.useKernel = false. 00267 */ 00268 float kernel(const float &x2, const float &rho2); 00269 00270 /** The internal method implementing CICP::AlignPDF when options.ICP_algorithm is icpClassic. 00271 */ 00272 CPosePDFPtr ICP_Method_Classic( 00273 const CMetricMap *m1, 00274 const CMetricMap *m2, 00275 const CPosePDFGaussian &initialEstimationPDF, 00276 TReturnInfo &outInfo ); 00277 00278 /** The internal method implementing CICP::AlignPDF when options.ICP_algorithm is icpLevenbergMarquardt. 00279 */ 00280 CPosePDFPtr ICP_Method_LM( 00281 const CMetricMap *m1, 00282 const CMetricMap *m2, 00283 const CPosePDFGaussian &initialEstimationPDF, 00284 TReturnInfo &outInfo ); 00285 00286 /** The internal method implementing CICP::AlignPDF when options.ICP_algorithm is icpIKF. 00287 */ 00288 CPosePDFPtr ICP_Method_IKF( 00289 const CMetricMap *m1, 00290 const CMetricMap *m2, 00291 const CPosePDFGaussian &initialEstimationPDF, 00292 TReturnInfo &outInfo ); 00293 00294 /** The internal method implementing CICP::Align3DPDF when options.ICP_algorithm is icpClassic. 00295 */ 00296 CPose3DPDFPtr ICP3D_Method_Classic( 00297 const CMetricMap *m1, 00298 const CMetricMap *m2, 00299 const CPose3DPDFGaussian &initialEstimationPDF, 00300 TReturnInfo &outInfo ); 00301 00302 00303 }; 00304 00305 } // End of namespace 00306 } // End of namespace 00307 00308 #endif
| Page generated by Doxygen 1.6.1 for MRPT 0.9.0 SVN: at Mon Jun 7 06:47:58 UTC 2010 |
