Several implementations of ICP (Iterative closest point) algorithms for aligning two point maps.
See CICP::AlignPDF for the entry point of the algorithm, and CICP::TConfigParams for all the parameters to the method. The algorithm has been exteneded with multihypotheses-support for the correspondences, which generates a Sum-of-Gaussians (SOG) PDF as output. See scanmatching::robustRigidTransformation.
For further details on the method, check the wiki: http://www.mrpt.org/Scan_Matching_Algorithms
For a paper explaining the used equations, see for example: J. Martinez, J. Gonzalez, J. Morales, A. Mandow, A. Garcia-Cerezo, "Genetic and ICP Laser Point Matching for 2D Mobile Robot Motion Estimation", Journal of Field Robotics, vol. 23, no. 1, 2006. ( http://babel.isa.uma.es/~jlblanco/papers/martinez2006gil.pdf )
#include <mrpt/slam/CICP.h>
Classes | |
class | TConfigParams |
The ICP algorithm configuration data. More... | |
struct | TReturnInfo |
The ICP algorithm return information. More... | |
Public Member Functions | |
CICP () | |
Constructor with the default options. | |
CICP (const TConfigParams &icpParams) | |
Constructor that directly set the ICP params from a given struct. | |
virtual | ~CICP () |
Destructor. | |
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. | |
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. | |
Public Attributes | |
TConfigParams | options |
The options employed by the ICP align. | |
Protected Member Functions | |
float | kernel (const float &x2, const float &rho2) |
Computes:
| |
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. | |
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. | |
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. | |
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. |
mrpt::slam::CICP::CICP | ( | ) | [inline] |
mrpt::slam::CICP::CICP | ( | const TConfigParams & | icpParams | ) | [inline] |
virtual mrpt::slam::CICP::~CICP | ( | ) | [inline, virtual] |
CPose3DPDFPtr mrpt::slam::CICP::Align3DPDF | ( | const CMetricMap * | m1, |
const CMetricMap * | m2, | ||
const CPose3DPDFGaussian & | initialEstimationPDF, | ||
float * | runningTime = NULL , |
||
void * | info = NULL |
||
) | [virtual] |
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.
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. |
Implements mrpt::slam::CMetricMapsAlignmentAlgorithm.
CPosePDFPtr mrpt::slam::CICP::AlignPDF | ( | const CMetricMap * | m1, |
const CMetricMap * | m2, | ||
const CPosePDFGaussian & | initialEstimationPDF, | ||
float * | runningTime = NULL , |
||
void * | info = NULL |
||
) | [virtual] |
An implementation of CMetricMapsAlignmentAlgorithm for the case of a point maps and a occupancy grid/point map.
This method computes the PDF of the displacement (relative pose) between two maps: the relative pose of m2 with respect to m1. This pose is returned as a PDF rather than a single value.
m1 | [IN] The first map (CAN BE A mrpt::poses::CPointsMap derived class or a mrpt::slam::COccupancyGrid2D class) |
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. |
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] A pointer to a CICP::TReturnInfo, or NULL if it isn't needed. |
Implements mrpt::slam::CMetricMapsAlignmentAlgorithm.
CPose3DPDFPtr mrpt::slam::CICP::ICP3D_Method_Classic | ( | const CMetricMap * | m1, |
const CMetricMap * | m2, | ||
const CPose3DPDFGaussian & | initialEstimationPDF, | ||
TReturnInfo & | outInfo | ||
) | [protected] |
The internal method implementing CICP::Align3DPDF when options.ICP_algorithm is icpClassic.
CPosePDFPtr mrpt::slam::CICP::ICP_Method_Classic | ( | const CMetricMap * | m1, |
const CMetricMap * | m2, | ||
const CPosePDFGaussian & | initialEstimationPDF, | ||
TReturnInfo & | outInfo | ||
) | [protected] |
The internal method implementing CICP::AlignPDF when options.ICP_algorithm is icpClassic.
CPosePDFPtr mrpt::slam::CICP::ICP_Method_IKF | ( | const CMetricMap * | m1, |
const CMetricMap * | m2, | ||
const CPosePDFGaussian & | initialEstimationPDF, | ||
TReturnInfo & | outInfo | ||
) | [protected] |
The internal method implementing CICP::AlignPDF when options.ICP_algorithm is icpIKF.
CPosePDFPtr mrpt::slam::CICP::ICP_Method_LM | ( | const CMetricMap * | m1, |
const CMetricMap * | m2, | ||
const CPosePDFGaussian & | initialEstimationPDF, | ||
TReturnInfo & | outInfo | ||
) | [protected] |
The internal method implementing CICP::AlignPDF when options.ICP_algorithm is icpLevenbergMarquardt.
float mrpt::slam::CICP::kernel | ( | const float & | x2, |
const float & | rho2 | ||
) | [protected] |
Computes:
or just return the input if options.useKernel = false.
Page generated by Doxygen 1.7.3 for MRPT 0.9.4 SVN:exported at Tue Jan 25 21:56:31 UTC 2011 |