class mrpt::slam::CICP

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)

See also:

CMetricMapsAlignmentAlgorithm

#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
        );
};

Inherited Members

public:
    // structs

    struct TMsg;

    //
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
        ) = 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:

options

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