class mrpt::slam::CICP
Overview
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 mrpt::tfest::se2_l2_robust()
For further details on the implemented methods, check the web: https://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)
3-D ICP : Only the icpClassic variant is implemented for 3-D point-cloud alignment (see Align3DPDF()). For production-quality, feature-rich 3-D ICP with support for different point-to-plane and point-to-line metrics, robust kernels, and multi-layer maps, use the independent mp2p_icp library (https://github.com/MOLAorg/mp2p_icp) which is the recommended replacement for 3-D scan matching in MRPT 3.
See also:
#include <mrpt/slam/CICP.h> class CICP: public mrpt::slam::CMetricMapsAlignmentAlgorithm { public: // structs struct TReturnInfo; // classes class TConfigParams; // fields TConfigParams options; // construction CICP(); CICP(const TConfigParams& icpParams); // methods virtual mrpt::poses::CPosePDF::Ptr AlignPDF( const mrpt::maps::CMetricMap* m1, const mrpt::maps::CMetricMap* m2, const mrpt::poses::CPosePDFGaussian& initialEstimationPDF, mrpt::optional_ref<TMetricMapAlignmentResult> outInfo = std::nullopt ); virtual mrpt::poses::CPose3DPDF::Ptr Align3DPDF( const mrpt::maps::CMetricMap* m1, const mrpt::maps::CMetricMap* m2, const mrpt::poses::CPose3DPDFGaussian& initialEstimationPDF, mrpt::optional_ref<TMetricMapAlignmentResult> outInfo = std::nullopt ); mrpt::poses::CPosePDF::Ptr Align(const mrpt::maps::CMetricMap* m1, const mrpt::maps::CMetricMap* m2, const mrpt::poses::CPose2D& grossEst, mrpt::optional_ref<TMetricMapAlignmentResult> outInfo = std::nullopt); mrpt::poses::CPose3DPDF::Ptr Align3D(const mrpt::maps::CMetricMap* m1, const mrpt::maps::CMetricMap* m2, const mrpt::poses::CPose3D& grossEst, mrpt::optional_ref<TMetricMapAlignmentResult> outInfo = std::nullopt); };
Inherited Members
public: // structs struct TMsg; // methods COutputLogger& operator = (const COutputLogger&); COutputLogger& operator = (COutputLogger&&); virtual mrpt::poses::CPosePDF::Ptr AlignPDF( const mrpt::maps::CMetricMap* m1, const mrpt::maps::CMetricMap* m2, const mrpt::poses::CPosePDFGaussian& initialEstimationPDF, mrpt::optional_ref<TMetricMapAlignmentResult> outInfo = std::nullopt ) = 0; virtual mrpt::poses::CPose3DPDF::Ptr Align3DPDF( const mrpt::maps::CMetricMap* m1, const mrpt::maps::CMetricMap* m2, const mrpt::poses::CPose3DPDFGaussian& initialEstimationPDF, mrpt::optional_ref<TMetricMapAlignmentResult> outInfo = std::nullopt ) = 0;
Fields
TConfigParams options
The options employed by the ICP align.
Construction
CICP()
Constructor with the default options.
CICP(const TConfigParams& icpParams)
Constructor that directly set the ICP params from a given struct.
See also:
Methods
virtual mrpt::poses::CPosePDF::Ptr AlignPDF( const mrpt::maps::CMetricMap* m1, const mrpt::maps::CMetricMap* m2, const mrpt::poses::CPosePDFGaussian& initialEstimationPDF, mrpt::optional_ref<TMetricMapAlignmentResult> outInfo = std::nullopt )
See base method docs.
This class offers an implementation for the case of “m1” being a point map and “m2” either an occupancy grid or a point map.
This method can be configurated with “CICP::options”
The output PDF is a CPosePDFGaussian if “doRANSAC=false”, or a CPosePDFSOG otherwise.
See also:
CMetricMapsAlignmentAlgorithm, CICP::options, CICP::TReturnInfo
mrpt::poses::CPosePDF::Ptr Align(const mrpt::maps::CMetricMap* m1, const mrpt::maps::CMetricMap* m2, const mrpt::poses::CPose2D& grossEst, mrpt::optional_ref<TMetricMapAlignmentResult> outInfo = std::nullopt)
The method for aligning a pair of metric maps, for SE(2) relative poses.
The meaning of some parameters and the kind of the maps to be aligned are implementation dependant, so look at the derived classes for instructions. The target is to find a PDF for the pose displacement between maps, thus the pose of m2 relative to m1. This pose is returned as a PDF rather than a single value.
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Parameters:
m1 |
[IN] The first map |
m2 |
[IN] The second map. The pose of this map respect to m1 is to be estimated. |
grossEst |
[IN] An initial gross estimation for the displacement. If a given algorithm doesn’t need it, set to |
runningTime |
[OUT] A pointer to a container for obtaining the algorithm running time in seconds, or nullptr if you don’t need it. |
info |
[OUT] See derived classes for details, or nullptr if it isn’t needed. |
Returns:
A smart pointer to the output estimated pose PDF.
A smart pointer to the output estimated pose PDF.
See also:
mrpt::poses::CPose3DPDF::Ptr Align3D(const mrpt::maps::CMetricMap* m1, const mrpt::maps::CMetricMap* m2, const mrpt::poses::CPose3D& grossEst, mrpt::optional_ref<TMetricMapAlignmentResult> outInfo = std::nullopt)
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Returns:
A smart pointer to the output estimated pose PDF.
See also: