struct mola::RelocalizationLikelihood_SE2

Overview

Takes a global metric map, an observation, and a SE(2) ROI, and evaluates the likelihood of the observation in a regular SE(2) lattice.

This is based on mrpt maps observationLikelihood() evaluation, so the main parameters that determine the way likelihood is computed must be defined on before hand within each of the metric map layers of the input reference map.

At present this algorithm is useful for these sensor/map types:

  • observations: pointclouds/2d_scan, reference_map: 2D gridmap

  • observations: pointclouds, reference_map: pointclouds

    Todo Implement likelihood of observations GNNS datum within georeferenced maps.

#include <relocalization.h>

struct RelocalizationLikelihood_SE2
{
    // structs

    struct Input;
    struct Output;

    // methods

    static Output run(const Input& in);
};