Main MRPT website > C++ reference
MRPT logo
CICP.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 CICP_H
10 #define CICP_H
11 
14 
15 namespace mrpt
16 {
17  namespace slam
18  {
19  using namespace poses;
20 
21  /** The ICP algorithm selection, used in mrpt::slam::CICP::options.
22  * For details on the algorithms refer to http://www.mrpt.org/Scan_Matching_Algorithms
23  * \ingroup mrpt_slam_grp
24  */
26  {
30  };
31 
32  /** Several implementations of ICP (Iterative closest point) algorithms for aligning two point maps or a point map wrt a grid map.
33  *
34  * CICP::AlignPDF() or CICP::Align() are the two main entry points of the algorithm.
35  *
36  * To choose among existing ICP algorithms or customizing their parameters, see CICP::TConfigParams and the member \a options.
37  *
38  * There exists an extension of the original ICP algorithm that provides multihypotheses-support for the correspondences, and which generates a Sum-of-Gaussians (SOG)
39  * PDF as output. See scanmatching::robustRigidTransformation.
40  *
41  * For further details on the implemented methods, check the web:
42  * http://www.mrpt.org/Iterative_Closest_Point_(ICP)_and_other_matching_algorithms
43  *
44  * For a paper explaining some of the basic equations, see for example:
45  * J. Martinez, J. Gonzalez, J. Morales, A. Mandow, A. Garcia-Cerezo,
46  * "Mobile robot motion estimation by 2D scan matching with genetic and iterative closest point algorithms",
47  * Journal of Field Robotics, vol. 23, no. 1, pp. 21-34, 2006. ( http://babel.isa.uma.es/~jlblanco/papers/martinez2006gil.pdf )
48  *
49  * \sa CMetricMapsAlignmentAlgorithm
50  * \ingroup mrpt_slam_grp
51  */
53  {
54  public:
55  /** The ICP algorithm configuration data
56  */
58  {
59  public:
60  TConfigParams(); //!< Initializer for default values:
61 
62  void loadFromConfigFile(
63  const mrpt::utils::CConfigFileBase &source,
64  const std::string &section); //!< See utils::CLoadableOptions
65 
66  void dumpToTextStream(CStream &out) const; //!<See utils::CLoadableOptions
67 
68 
69  /** The algorithm to use (default: icpClassic)
70  * See http://www.mrpt.org/Scan_Matching_Algorithms for details.
71  */
73 
74  bool onlyClosestCorrespondences; //!< The usual approach: to consider only the closest correspondence for each local point (Default to true)
75  bool onlyUniqueRobust; //! Apart of "onlyClosestCorrespondences=true", if this option is enabled only the closest correspondence for each reference point will be kept (default=false).
76 
77  /** @name Termination criteria
78  @{ */
79  unsigned int maxIterations; //!< Maximum number of iterations to run.
80  float minAbsStep_trans; //!< If the correction in all translation coordinates (X,Y,Z) is below this threshold (in meters), iterations are terminated (Default:1e-6)
81  float minAbsStep_rot; //!< If the correction in all rotation coordinates (yaw,pitch,roll) is below this threshold (in radians), iterations are terminated (Default:1e-6)
82  /** @} */
83 
84  float thresholdDist,thresholdAng; //!< Initial threshold distance for two points to become a correspondence.
85  float ALFA; //!< The scale factor for threshold everytime convergence is achieved.
86  float smallestThresholdDist; //!< The size for threshold such that iterations will stop, since it is considered precise enough.
87 
88  /** This is the normalization constant \f$ \sigma^2_p \f$ that is used to scale the whole 3x3 covariance.
89  * This has a default value of \f$ (0.02)^2 \f$, that is, a 2cm sigma.
90  * See the paper: ....
91  */
93 
94  bool doRANSAC; //!< Perform a RANSAC step after the ICP convergence, to obtain a better estimation of the pose PDF.
95 
96  /** RANSAC-step options:
97  * \sa CICP::robustRigidTransformation
98  */
99  unsigned int ransac_minSetSize,ransac_maxSetSize,ransac_nSimulations;
100 
101  /** RANSAC-step options:
102  * \sa CICP::robustRigidTransformation
103  */
105 
106  /** RANSAC-step option: The standard deviation in X,Y of landmarks/points which are being matched (used to compute covariances in the SoG)
107  * \sa CICP::robustRigidTransformation
108  */
110 
111  /** RANSAC-step options:
112  * \sa CICP::robustRigidTransformation
113  */
115 
116  /** RANSAC-step options:
117  * \sa CICP::robustRigidTransformation
118  */
119  float ransac_fuseMaxDiffXY, ransac_fuseMaxDiffPhi;
120 
121  /** Cauchy kernel rho, for estimating the optimal transformation covariance, in meters (default = 0.07m). */
122  float kernel_rho;
123 
124  /** Whether to use kernel_rho to smooth distances, or use distances directly (default=true) */
126 
127  /** The size of the perturbance in x & y used to estimate the Jacobians of the square error (in LM & IKF methods, default=0.05).*/
129 
130  /** The initial value of the lambda parameter in the LM method (default=1e-4). */
132 
133  /** Skip the computation of the covariance (saves some time) (default=false) */
135 
136  /** Skip the (sometimes) expensive evaluation of the term 'quality' at ICP output (Default=true) */
138 
139  /** Decimation of the point cloud being registered against the reference one (default=5) - set to 1 to have the older (MRPT <0.9.5) behavior
140  * of not approximating ICP by ignoring the correspondence of some points. The speed-up comes from a decimation of the number of KD-tree queries,
141  * the most expensive step in ICP.
142  */
144 
145  };
146 
147  TConfigParams options; //!< The options employed by the ICP align.
148 
149 
150  /** Constructor with the default options */
151  CICP() : options() { }
152  /** Constructor that directly set the ICP params from a given struct \sa options */
153  CICP(const TConfigParams &icpParams) : options(icpParams) { }
154 
155  virtual ~CICP() { } //!< Destructor
156 
157 
158  /** The ICP algorithm return information.
159  */
161  {
163  cbSize(sizeof(TReturnInfo)),
164  nIterations(0),
165  goodness(0),
166  quality(0)
167  {
168  }
169 
170  /** Size in bytes of this struct: Must be set correctly before using it */
171  unsigned int cbSize;
172 
173  /** The number of executed iterations until convergence.
174  */
175  unsigned short nIterations;
176 
177  /** A goodness measure for the alignment, it is a [0,1] range indicator of percentage of correspondences.
178  */
179  float goodness;
180 
181  /** A measure of the 'quality' of the local minimum of the sqr. error found by the method.
182  * Higher values are better. Low values will be found in ill-conditioned situations (e.g. a corridor).
183  */
184  float quality;
185  };
186 
187  /** An implementation of CMetricMapsAlignmentAlgorithm for the case of a point maps and a occupancy grid/point map.
188  *
189  * This method computes the PDF of the displacement (relative pose) between
190  * two maps: <b>the relative pose of m2 with respect to m1</b>. This pose
191  * is returned as a PDF rather than a single value.
192  *
193  * \note This method can be configurated with "CICP::options"
194  * \note The output PDF is a CPosePDFGaussian if "doRANSAC=false", or a CPosePDFSOG otherwise.
195  *
196  * \param m1 [IN] The first map (CAN BE A mrpt::poses::CPointsMap derived class or a mrpt::slam::COccupancyGrid2D class)
197  * \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.
198  * \param initialEstimationPDF [IN] An initial gross estimation for the displacement.
199  * \param runningTime [OUT] A pointer to a container for obtaining the algorithm running time in seconds, or NULL if you don't need it.
200  * \param info [OUT] A pointer to a CICP::TReturnInfo, or NULL if it isn't needed.
201  *
202  * \return A smart pointer to the output estimated pose PDF.
203  *
204  * \sa CMetricMapsAlignmentAlgorithm, CICP::options, CICP::TReturnInfo
205  */
206  CPosePDFPtr AlignPDF(
207  const CMetricMap *m1,
208  const CMetricMap *m2,
209  const CPosePDFGaussian &initialEstimationPDF,
210  float *runningTime = NULL,
211  void *info = NULL );
212 
213  /** Align a pair of metric maps, aligning the full 6D pose.
214  * The meaning of some parameters are implementation dependant,
215  * so look at the derived classes for more details.
216  * The goal is to find a PDF for the pose displacement between
217  * maps, that is, <b>the pose of m2 relative to m1</b>. This pose
218  * is returned as a PDF rather than a single value.
219  *
220  * \note This method can be configurated with a "options" structure in the implementation classes.
221  *
222  * \param m1 [IN] The first map (MUST BE A COccupancyGridMap2D derived class)
223  * \param m2 [IN] The second map. (MUST BE A CPointsMap derived class) The pose of this map respect to m1 is to be estimated.
224  * \param initialEstimationPDF [IN] An initial gross estimation for the displacement.
225  * \param runningTime [OUT] A pointer to a container for obtaining the algorithm running time in seconds, or NULL if you don't need it.
226  * \param info [OUT] See derived classes for details, or NULL if it isn't needed.
227  *
228  * \return A smart pointer to the output estimated pose PDF.
229  * \sa CICP
230  */
231  CPose3DPDFPtr Align3DPDF(
232  const CMetricMap *m1,
233  const CMetricMap *m2,
234  const CPose3DPDFGaussian &initialEstimationPDF,
235  float *runningTime = NULL,
236  void *info = NULL );
237 
238 
239  protected:
240  /** Computes:
241  * \f[ K(x^2) = \frac{x^2}{x^2+\rho^2} \f]
242  * or just return the input if options.useKernel = false.
243  */
244  float kernel(const float &x2, const float &rho2);
245 
246  /** The internal method implementing CICP::AlignPDF when options.ICP_algorithm is icpClassic.
247  */
248  CPosePDFPtr ICP_Method_Classic(
249  const CMetricMap *m1,
250  const CMetricMap *m2,
251  const CPosePDFGaussian &initialEstimationPDF,
252  TReturnInfo &outInfo );
253 
254  /** The internal method implementing CICP::AlignPDF when options.ICP_algorithm is icpLevenbergMarquardt.
255  */
256  CPosePDFPtr ICP_Method_LM(
257  const CMetricMap *m1,
258  const CMetricMap *m2,
259  const CPosePDFGaussian &initialEstimationPDF,
260  TReturnInfo &outInfo );
261 
262  /** The internal method implementing CICP::AlignPDF when options.ICP_algorithm is icpIKF.
263  */
264  CPosePDFPtr ICP_Method_IKF(
265  const CMetricMap *m1,
266  const CMetricMap *m2,
267  const CPosePDFGaussian &initialEstimationPDF,
268  TReturnInfo &outInfo );
269 
270  /** The internal method implementing CICP::Align3DPDF when options.ICP_algorithm is icpClassic.
271  */
272  CPose3DPDFPtr ICP3D_Method_Classic(
273  const CMetricMap *m1,
274  const CMetricMap *m2,
275  const CPose3DPDFGaussian &initialEstimationPDF,
276  TReturnInfo &outInfo );
277 
278 
279  };
280 
281  } // End of namespace
282 } // End of namespace
283 
284 #endif
unsigned int cbSize
Size in bytes of this struct: Must be set correctly before using it.
Definition: CICP.h:171
float quality
A measure of the &#39;quality&#39; of the local minimum of the sqr.
Definition: CICP.h:184
The ICP algorithm configuration data.
Definition: CICP.h:57
float ransac_mahalanobisDistanceThreshold
RANSAC-step options:
Definition: CICP.h:104
TICPAlgorithm ICP_algorithm
The algorithm to use (default: icpClassic) See http://www.mrpt.org/Scan_Matching_Algorithms for detai...
Definition: CICP.h:72
Several implementations of ICP (Iterative closest point) algorithms for aligning two point maps or a ...
Definition: CICP.h:52
bool skip_quality_calculation
Skip the (sometimes) expensive evaluation of the term &#39;quality&#39; at ICP output (Default=true) ...
Definition: CICP.h:137
unsigned int ransac_nSimulations
Definition: CICP.h:99
float ALFA
The scale factor for threshold everytime convergence is achieved.
Definition: CICP.h:85
TConfigParams options
The options employed by the ICP align.
Definition: CICP.h:147
float kernel_rho
Cauchy kernel rho, for estimating the optimal transformation covariance, in meters (default = 0...
Definition: CICP.h:122
float minAbsStep_rot
If the correction in all rotation coordinates (yaw,pitch,roll) is below this threshold (in radians)...
Definition: CICP.h:81
uint32_t corresponding_points_decimation
Decimation of the point cloud being registered against the reference one (default=5) - set to 1 to ha...
Definition: CICP.h:143
This class allows loading and storing values and vectors of different types from a configuration text...
Declares a virtual base class for all metric maps storage classes.
Definition: CMetricMap.h:90
float goodness
A goodness measure for the alignment, it is a [0,1] range indicator of percentage of correspondences...
Definition: CICP.h:179
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
Definition: CStream.h:36
bool ransac_fuseByCorrsMatch
RANSAC-step options:
Definition: CICP.h:114
Declares a class that represents a Probability Density function (PDF) of a 2D pose ...
unsigned int maxIterations
Maximum number of iterations to run.
Definition: CICP.h:79
float covariance_varPoints
This is the normalization constant that is used to scale the whole 3x3 covariance.
Definition: CICP.h:92
bool doRANSAC
Perform a RANSAC step after the ICP convergence, to obtain a better estimation of the pose PDF...
Definition: CICP.h:94
CICP(const TConfigParams &icpParams)
Constructor that directly set the ICP params from a given struct.
Definition: CICP.h:153
TICPAlgorithm
The ICP algorithm selection, used in mrpt::slam::CICP::options.
Definition: CICP.h:25
bool onlyClosestCorrespondences
The usual approach: to consider only the closest correspondence for each local point (Default to true...
Definition: CICP.h:74
unsigned short nIterations
The number of executed iterations until convergence.
Definition: CICP.h:175
bool use_kernel
Whether to use kernel_rho to smooth distances, or use distances directly (default=true) ...
Definition: CICP.h:125
CICP()
Constructor with the default options.
Definition: CICP.h:151
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
bool skip_cov_calculation
Skip the computation of the covariance (saves some time) (default=false)
Definition: CICP.h:134
A base class for any algorithm able of maps alignment.
float smallestThresholdDist
The size for threshold such that iterations will stop, since it is considered precise enough...
Definition: CICP.h:86
The ICP algorithm return information.
Definition: CICP.h:160
float ransac_fuseMaxDiffXY
RANSAC-step options:
Definition: CICP.h:119
Declares a class that represents a Probability Density function (PDF) of a 3D pose ...
virtual ~CICP()
Destructor.
Definition: CICP.h:155
float LM_initial_lambda
The initial value of the lambda parameter in the LM method (default=1e-4).
Definition: CICP.h:131
float normalizationStd
RANSAC-step option: The standard deviation in X,Y of landmarks/points which are being matched (used t...
Definition: CICP.h:109
float minAbsStep_trans
If the correction in all translation coordinates (X,Y,Z) is below this threshold (in meters)...
Definition: CICP.h:80
float Axy_aprox_derivatives
The size of the perturbance in x & y used to estimate the Jacobians of the square error (in LM & IKF ...
Definition: CICP.h:128
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...



Page generated by Doxygen 1.8.14 for MRPT 1.1.0 SVN: at lun oct 28 00:54:49 CET 2019 Hosted on:
SourceForge.net Logo