Several implementations of ICP (Iterative closest point) algorithms for aligning two point maps or a point map wrt a grid map.
CICP::AlignPDF() or CICP::Align() are the two main entry points of the algorithm.
To choose among existing ICP algorithms or customizing their parameters, see CICP::TConfigParams and the member options.
There exists an extension of the original ICP algorithm that provides multihypotheses-support for the correspondences, and which generates a Sum-of-Gaussians (SOG) PDF as output. See scanmatching::robustRigidTransformation.
For further details on the implemented methods, check the web: http://www.mrpt.org/Iterative_Closest_Point_(ICP)_and_other_matching_algorithms
For a paper explaining some of the basic equations, see for example: J. Martinez, J. Gonzalez, J. Morales, A. Mandow, A. Garcia-Cerezo, "Mobile robot motion estimation by 2D scan matching with genetic and iterative closest point algorithms", Journal of Field Robotics, vol. 23, no. 1, pp. 21-34, 2006. ( http://babel.isa.uma.es/~jlblanco/papers/martinez2006gil.pdf )
- See also
- CMetricMapsAlignmentAlgorithm
Definition at line 52 of file CICP.h.
|
| CICP () |
| Constructor with the default options. More...
|
|
| CICP (const TConfigParams &icpParams) |
| Constructor that directly set the ICP params from a given struct. More...
|
|
virtual | ~CICP () |
| Destructor. More...
|
|
CPosePDFPtr | AlignPDF (const CMetricMap *m1, const CMetricMap *m2, const CPosePDFGaussian &initialEstimationPDF, float *runningTime=NULL, void *info=NULL) |
| An implementation of CMetricMapsAlignmentAlgorithm for the case of a point maps and a occupancy grid/point map. More...
|
|
CPose3DPDFPtr | Align3DPDF (const CMetricMap *m1, const CMetricMap *m2, const CPose3DPDFGaussian &initialEstimationPDF, float *runningTime=NULL, void *info=NULL) |
| Align a pair of metric maps, aligning the full 6D pose. More...
|
|
CPosePDFPtr | Align (const CMetricMap *m1, const CMetricMap *m2, const CPose2D &grossEst, float *runningTime=NULL, void *info=NULL) |
| The method for aligning a pair of metric maps, aligning only 2D + orientation. More...
|
|
CPose3DPDFPtr | Align3D (const CMetricMap *m1, const CMetricMap *m2, const CPose3D &grossEst, float *runningTime=NULL, void *info=NULL) |
| The method for aligning a pair of metric maps, aligning the full 6D pose. More...
|
|
|
float | kernel (const float &x2, const float &rho2) |
| Computes:
or just return the input if options.useKernel = false. More...
|
|
CPosePDFPtr | ICP_Method_Classic (const CMetricMap *m1, const CMetricMap *m2, const CPosePDFGaussian &initialEstimationPDF, TReturnInfo &outInfo) |
| The internal method implementing CICP::AlignPDF when options.ICP_algorithm is icpClassic. More...
|
|
CPosePDFPtr | ICP_Method_LM (const CMetricMap *m1, const CMetricMap *m2, const CPosePDFGaussian &initialEstimationPDF, TReturnInfo &outInfo) |
| The internal method implementing CICP::AlignPDF when options.ICP_algorithm is icpLevenbergMarquardt. More...
|
|
CPosePDFPtr | ICP_Method_IKF (const CMetricMap *m1, const CMetricMap *m2, const CPosePDFGaussian &initialEstimationPDF, TReturnInfo &outInfo) |
| The internal method implementing CICP::AlignPDF when options.ICP_algorithm is icpIKF. More...
|
|
CPose3DPDFPtr | ICP3D_Method_Classic (const CMetricMap *m1, const CMetricMap *m2, const CPose3DPDFGaussian &initialEstimationPDF, TReturnInfo &outInfo) |
| The internal method implementing CICP::Align3DPDF when options.ICP_algorithm is icpClassic. More...
|
|
Align a pair of metric maps, aligning the full 6D pose.
The meaning of some parameters are implementation dependant, so look at the derived classes for more details. The goal is to find a PDF for the pose displacement between maps, that is, the pose of m2 relative to m1. This pose is returned as a PDF rather than a single value.
- Note
- This method can be configurated with a "options" structure in the implementation classes.
- Parameters
-
m1 | [IN] The first map (MUST BE A COccupancyGridMap2D derived class) |
m2 | [IN] The second map. (MUST BE A CPointsMap derived class) The pose of this map respect to m1 is to be estimated. |
initialEstimationPDF | [IN] An initial gross estimation for the displacement. |
runningTime | [OUT] A pointer to a container for obtaining the algorithm running time in seconds, or NULL if you don't need it. |
info | [OUT] See derived classes for details, or NULL if it isn't needed. |
- Returns
- A smart pointer to the output estimated pose PDF.
- See also
- CICP
Implements mrpt::slam::CMetricMapsAlignmentAlgorithm.