class mrpt::maps::CBeaconMap

Overview

A class for storing a map of 3D probabilistic beacons, using a Montecarlo, Gaussian, or Sum of Gaussians (SOG) representation (for range-only SLAM).

The individual beacons are defined as mrpt::maps::CBeacon objects.

When invoking CBeaconMap::insertObservation(), landmarks will be extracted and fused into the map. The only currently supported observation type is mrpt::obs::CObservationBeaconRanges. See insertionOptions and likelihoodOptions for parameters used when creating and fusing beacon landmarks.

Use “TInsertionOptions::insertAsMonteCarlo” to select between 2 different behaviors:

  • Initial PDF of beacons: MonteCarlo, after convergence, pass to Gaussians; or

  • Initial PDF of beacons: SOG, after convergence, a single Gaussian.

Refer to the papers: []

See also:

CMetricMap

#include <mrpt/maps/CBeaconMap.h>

class CBeaconMap: public mrpt::maps::CMetricMap
{
public:
    // typedefs

    typedef std::deque<CBeacon> TSequenceBeacons;
    typedef std::deque<CBeacon>::iterator iterator;
    typedef std::deque<CBeacon>::const_iterator const_iterator;

    // structs

    struct TInsertionOptions;
    struct TLikelihoodOptions;

    // fields

    mrpt::maps::CBeaconMap::TLikelihoodOptions likelihoodOptions;
    mrpt::maps::CBeaconMap::TInsertionOptions insertionOptions;
    mrpt::maps::CBeaconMap::TInsertionOptions insertionOpts;
    mrpt::maps::CBeaconMap::TLikelihoodOptions likelihoodOpts;
    TMapGenericParams genericMapParams;

    // construction

    CBeaconMap();

    // methods

    void resize(size_t N);
    virtual std::string asString() const;
    const CBeacon& operator [] (size_t i) const;
    const CBeacon& get(size_t i) const;
    CBeacon& operator [] (size_t i);
    CBeacon& get(size_t i);
    iterator begin();
    const_iterator begin() const;
    iterator end();
    const_iterator end() const;
    void push_back(const CBeacon& m);
    virtual float compute3DMatchingRatio(const mrpt::maps::CMetricMap* otherMap, const mrpt::poses::CPose3D& otherMapPose, const TMatchingRatioParams& params) const;

    bool saveToMATLABScript3D(
        const std::string& file,
        const char* style = "b",
        float confInterval = 0.95f
        ) const;

    size_t size() const;

    virtual void determineMatching2D(
        const mrpt::maps::CMetricMap* otherMap,
        const mrpt::poses::CPose2D& otherMapPose,
        mrpt::tfest::TMatchingPairList& correspondences,
        const TMatchingParams& params,
        TMatchingExtraResults& extraResults
        ) const;

    void computeMatchingWith3DLandmarks(
        const mrpt::maps::CBeaconMap* otherMap,
        mrpt::tfest::TMatchingPairList& correspondences,
        float& correspondencesRatio,
        std::vector<bool>& otherCorrespondences
        ) const;

    void changeCoordinatesReference(const mrpt::poses::CPose3D& newOrg);
    void changeCoordinatesReference(const mrpt::poses::CPose3D& newOrg, const mrpt::maps::CBeaconMap* otherMap);
    virtual bool isEmpty() const;

    void simulateBeaconReadings(
        const mrpt::poses::CPose3D& in_robotPose,
        const mrpt::poses::CPoint3D& in_sensorLocationOnRobot,
        mrpt::obs::CObservationBeaconRanges& out_Observations
        ) const;

    virtual void saveMetricMapRepresentationToFile(const std::string& filNamePrefix) const;
    void saveToTextFile(const std::string& fil) const;
    virtual void getVisualizationInto(mrpt::opengl::CSetOfObjects& outObj) const;
    const CBeacon* getBeaconByID(CBeacon::TBeaconID id) const;
    CBeacon* getBeaconByID(CBeacon::TBeaconID id);
    void clear();
    virtual auto boundingBox() const;
    void loadFromSimpleMap(const mrpt::maps::CSimpleMap& Map);
    bool insertObservation(const mrpt::obs::CObservation& obs, const std::optional<const mrpt::poses::CPose3D>& robotPose = std::nullopt);
    bool insertObservationPtr(const mrpt::obs::CObservation::Ptr& obs, const std::optional<const mrpt::poses::CPose3D>& robotPose = std::nullopt);
    double computeObservationLikelihood(const mrpt::obs::CObservation& obs, const mrpt::poses::CPose3D& takenFrom) const;
    virtual bool canComputeObservationLikelihood(const mrpt::obs::CObservation& obs) const;
    double computeObservationsLikelihood(const mrpt::obs::CSensoryFrame& sf, const mrpt::poses::CPose3D& takenFrom);
    bool canComputeObservationsLikelihood(const mrpt::obs::CSensoryFrame& sf) const;

    virtual void determineMatching3D(
        const mrpt::maps::CMetricMap* otherMap,
        const mrpt::poses::CPose3D& otherMapPose,
        mrpt::tfest::TMatchingPairList& correspondences,
        const TMatchingParams& params,
        TMatchingExtraResults& extraResults
        ) const;

    virtual void auxParticleFilterCleanUp();
    virtual float squareDistanceToClosestCorrespondence(float x0, float y0) const;
    virtual const mrpt::maps::CSimplePointsMap* getAsSimplePointsMap() const;
    std::shared_ptr<mrpt::opengl::CSetOfObjects> getVisualization() const;
};

Inherited Members

public:
    // methods

    virtual bool isEmpty() const = 0;
    virtual void saveMetricMapRepresentationToFile(const std::string& filNamePrefix) const = 0;
    virtual std::string asString() const = 0;
    virtual void getVisualizationInto(mrpt::opengl::CSetOfObjects& o) const = 0;

Fields

mrpt::maps::CBeaconMap::TInsertionOptions insertionOpts

Observations insertion options.

mrpt::maps::CBeaconMap::TLikelihoodOptions likelihoodOpts

Probabilistic observation likelihood options.

TMapGenericParams genericMapParams

Common params to all maps.

Construction

CBeaconMap()

Constructor.

Methods

void resize(size_t N)

Resize the number of SOG modes.

virtual std::string asString() const

Returns a short description of the map.

const CBeacon& operator [] (size_t i) const

Access to individual beacons.

const CBeacon& get(size_t i) const

Access to individual beacons.

CBeacon& operator [] (size_t i)

Access to individual beacons.

CBeacon& get(size_t i)

Access to individual beacons.

void push_back(const CBeacon& m)

Inserts a copy of the given mode into the SOG.

virtual float compute3DMatchingRatio(
    const mrpt::maps::CMetricMap* otherMap,
    const mrpt::poses::CPose3D& otherMapPose,
    const TMatchingRatioParams& params
    ) const

Computes the ratio in [0,1] of correspondences between “this” and the “otherMap” map, whose 6D pose relative to “this” is “otherMapPose” In the case of a multi-metric map, this returns the average between the maps.

This method always return 0 for grid maps.

Parameters:

otherMap

[IN] The other map to compute the matching with.

otherMapPose

[IN] The 6D pose of the other map as seen from “this”.

params

[IN] Matching parameters

Returns:

The matching ratio [0,1]

See also:

determineMatching2D

bool saveToMATLABScript3D(
    const std::string& file,
    const char* style = "b",
    float confInterval = 0.95f
    ) const

Save to a MATLAB script which displays 3D error ellipses for the map.

Parameters:

file

The name of the file to save the script to.

style

The MATLAB-like string for the style of the lines (see ‘help plot’ in MATLAB for possibilities)

stdCount

The ellipsoids will be drawn from the center to a given confidence interval in [0,1], e.g. 2 sigmas=0.95 (default is 2std = 0.95 confidence intervals)

Returns:

Returns false if any error occurred, true elsewere.

size_t size() const

Returns the stored landmarks count.

virtual void determineMatching2D(
    const mrpt::maps::CMetricMap* otherMap,
    const mrpt::poses::CPose2D& otherMapPose,
    mrpt::tfest::TMatchingPairList& correspondences,
    const TMatchingParams& params,
    TMatchingExtraResults& extraResults
    ) const

Computes the matching between this and another 2D point map, which includes finding:

  • The set of points pairs in each map

  • The mean squared distance between corresponding pairs.

The algorithm is:

  • For each point in “otherMap”:

    • Transform the point according to otherMapPose

    • Search with a KD-TREE the closest correspondences in “this” map.

    • Add to the set of candidate matchings, if it passes all the thresholds in params.

This method is the most time critical one into ICP-like algorithms.

Parameters:

otherMap

[IN] The other map to compute the matching with.

otherMapPose

[IN] The pose of the other map as seen from “this”.

params

[IN] Parameters for the determination of pairings.

correspondences

[OUT] The detected matchings pairs.

extraResults

[OUT] Other results.

See also:

compute3DMatchingRatio

void computeMatchingWith3DLandmarks(
    const mrpt::maps::CBeaconMap* otherMap,
    mrpt::tfest::TMatchingPairList& correspondences,
    float& correspondencesRatio,
    std::vector<bool>& otherCorrespondences
    ) const

Perform a search for correspondences between “this” and another lansmarks map: Firsly, the landmarks’ descriptor is used to find correspondences, then inconsistent ones removed by looking at their 3D poses.

Parameters:

otherMap

[IN] The other map.

correspondences

[OUT] The matched pairs between maps.

correspondencesRatio

[OUT] This is NumberOfMatchings / NumberOfLandmarksInTheAnotherMap

otherCorrespondences

[OUT] Will be returned with a vector containing “true” for the indexes of the other map’s landmarks with a correspondence.

void changeCoordinatesReference(const mrpt::poses::CPose3D& newOrg)

Changes the reference system of the map to a given 3D pose.

void changeCoordinatesReference(
    const mrpt::poses::CPose3D& newOrg,
    const mrpt::maps::CBeaconMap* otherMap
    )

Changes the reference system of the map “otherMap” and save the result in “this” map.

virtual bool isEmpty() const

Returns true if the map is empty/no observation has been inserted.

void simulateBeaconReadings(
    const mrpt::poses::CPose3D& in_robotPose,
    const mrpt::poses::CPoint3D& in_sensorLocationOnRobot,
    mrpt::obs::CObservationBeaconRanges& out_Observations
    ) const

Simulates a reading toward each of the beacons in the landmarks map, if any.

Parameters:

in_robotPose

This robot pose is used to simulate the ranges to each beacon.

in_sensorLocationOnRobot

The 3D position of the sensor on the robot

out_Observations

The results will be stored here. NOTICE that the fields “CObservationBeaconRanges::minSensorDistance”,”CObservationBeaconRanges::maxSensorDistance” and “CObservationBeaconRanges::stdError” MUST BE FILLED OUT before calling this function. An observation will be generated for each beacon in the map, but notice that some of them may be missed if out of the sensor maximum range.

virtual void saveMetricMapRepresentationToFile(const std::string& filNamePrefix) const

This virtual method saves the map to a file “filNamePrefix”+< some_file_extension >, as an image or in any other applicable way (Notice that other methods to save the map may be implemented in classes implementing this virtual interface).

In the case of this class, these files are generated:

  • “filNamePrefix”+”_3D.m”: A script for MATLAB for drawing landmarks as 3D ellipses.

  • “filNamePrefix”+”_3D.3DScene”: A 3D scene with a “ground plane grid” and the set of ellipsoids in 3D.

  • “filNamePrefix”+”_covs.m”: A textual representation (see saveToTextFile)

void saveToTextFile(const std::string& fil) const

Save a text file with a row per beacon, containing this 11 elements:

  • X Y Z: Mean values

  • VX VY VZ: Variances of each dimension (C11, C22, C33)

  • DET2D DET3D: Determinant of the 2D and 3D covariance matrixes.

  • C12, C13, C23: Cross covariances

virtual void getVisualizationInto(mrpt::opengl::CSetOfObjects& outObj) const

Returns a 3D object representing the map.

const CBeacon* getBeaconByID(CBeacon::TBeaconID id) const

Returns a pointer to the beacon with the given ID, or nullptr if it does not exist.

CBeacon* getBeaconByID(CBeacon::TBeaconID id)

Returns a pointer to the beacon with the given ID, or nullptr if it does not exist.

void clear()

Erase all the contents of the map.

virtual auto boundingBox() const

Returns the bounding box of the metric map, or (0,0,0)-(0,0,0) (the default value of mrpt::math::TBoundingBoxf() if not implemented in the derived class or the map is empty.

void loadFromSimpleMap(const mrpt::maps::CSimpleMap& Map)

Load the map contents from a CSimpleMap object, erasing all previous content of the map.

This is done invoking insertObservation() for each observation at the mean 3D robot pose of each pose-observations pair in the CSimpleMap object.

Parameters:

std::exception

Some internal steps in invoked methods can raise exceptions on invalid parameters, etc…

See also:

insertObservation, CSimpleMap

bool insertObservation(
    const mrpt::obs::CObservation& obs,
    const std::optional<const mrpt::poses::CPose3D>& robotPose = std::nullopt
    )

Insert the observation information into this map.

This method must be implemented in derived classes. See: Maps and observations compatibility matrices

Parameters:

obs

The observation

robotPose

The 3D pose of the robot mobile base in the map reference system, or NULL (default) if you want to use the origin.

See also:

CObservation::insertObservationInto

bool insertObservationPtr(
    const mrpt::obs::CObservation::Ptr& obs,
    const std::optional<const mrpt::poses::CPose3D>& robotPose = std::nullopt
    )

A wrapper for smart pointers, just calls the non-smart pointer version.

See: Maps and observations compatibility matrices

double computeObservationLikelihood(const mrpt::obs::CObservation& obs, const mrpt::poses::CPose3D& takenFrom) const

Computes the log-likelihood of a given observation given an arbitrary robot 3D pose.

See: Maps and observations compatibility matrices

Parameters:

takenFrom

The robot’s pose the observation is supposed to be taken from.

obs

The observation.

Returns:

This method returns a log-likelihood.

See also:

Used in particle filter algorithms, see: CMultiMetricMapPDF::update

virtual bool canComputeObservationLikelihood(const mrpt::obs::CObservation& obs) const

Returns true if this map is able to compute a sensible likelihood function for this observation (i.e.

an occupancy grid map cannot with an image). See: Maps and observations compatibility matrices

Parameters:

obs

The observation.

See also:

computeObservationLikelihood, genericMapParams.enableObservationLikelihood

double computeObservationsLikelihood(const mrpt::obs::CSensoryFrame& sf, const mrpt::poses::CPose3D& takenFrom)

Returns the sum of the log-likelihoods of each individual observation within a mrpt::obs::CSensoryFrame.

See: Maps and observations compatibility matrices

Parameters:

takenFrom

The robot’s pose the observation is supposed to be taken from.

sf

The set of observations in a CSensoryFrame.

Returns:

This method returns a log-likelihood.

See also:

canComputeObservationsLikelihood

bool canComputeObservationsLikelihood(const mrpt::obs::CSensoryFrame& sf) const

Returns true if this map is able to compute a sensible likelihood function for this observation (i.e.

an occupancy grid map cannot with an image). See: Maps and observations compatibility matrices

Parameters:

sf

The observations.

See also:

canComputeObservationLikelihood

virtual void determineMatching3D(
    const mrpt::maps::CMetricMap* otherMap,
    const mrpt::poses::CPose3D& otherMapPose,
    mrpt::tfest::TMatchingPairList& correspondences,
    const TMatchingParams& params,
    TMatchingExtraResults& extraResults
    ) const

Computes the matchings between this and another 3D points map - method used in 3D-ICP.

This method finds the set of point pairs in each map.

The method is the most time critical one into ICP-like algorithms.

The algorithm is:

  • For each point in “otherMap”:

    • Transform the point according to otherMapPose

    • Search with a KD-TREE the closest correspondences in “this” map.

    • Add to the set of candidate matchings, if it passes all the thresholds in params.

Parameters:

otherMap

[IN] The other map to compute the matching with.

otherMapPose

[IN] The pose of the other map as seen from “this”.

params

[IN] Parameters for the determination of pairings.

correspondences

[OUT] The detected matchings pairs.

extraResults

[OUT] Other results.

See also:

compute3DMatchingRatio

virtual void auxParticleFilterCleanUp()

This method is called at the end of each “prediction-update-map insertion” cycle within “mrpt::slam::CMetricMapBuilderRBPF::processActionObservation”.

This method should normally do nothing, but in some cases can be used to free auxiliary cached variables.

virtual float squareDistanceToClosestCorrespondence(float x0, float y0) const

Returns the square distance from the 2D point (x0,y0) to the closest correspondence in the map.

virtual const mrpt::maps::CSimplePointsMap* getAsSimplePointsMap() const

If the map is a simple points map or it’s a multi-metric map that contains EXACTLY one simple points map, return it.

Otherwise, return nullptr

std::shared_ptr<mrpt::opengl::CSetOfObjects> getVisualization() const

Creates 3D primitives representing this objects.

This is equivalent to getVisualizationInto() but creating, and returning by value, a new rpt::opengl::CSetOfObjects::Ptr shared pointer.

See also:

getVisualizationInto()