#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 () | |
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. | |
Public Attributes | |
mrpt::slam::CICP::TConfigParams | options |
The ICP algorithm configuration data. | |
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. |
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 scan_matching::robustRigidTransformation.
For further details on the method, check the wiki: http://babel.isa.uma.es/mrpt/index.php/Scan_Matching_Algorithms
Definition at line 66 of file CICP.h.
virtual mrpt::slam::CICP::~CICP | ( | ) | [inline, virtual] |
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.
The output PDF is a CPosePDFGaussian if "doRANSAC=false", or a CPosePDFSOG otherwise.
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.
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.
The ICP algorithm configuration data.
Page generated by Doxygen 1.5.8 for MRPT 0.6.5 SVN:exported at Mon Jan 12 13:00:16 UTC 2009 |