class mrpt::maps::CMultiMetricMap

This class stores any customizable set of metric maps.

The internal metric maps can be accessed directly by the user as smart pointers with CMultiMetricMap::mapByIndex() or via iterator s. The utility of this container is to operate on several maps simultaneously: update them by inserting observations, evaluate the likelihood of one observation by fusing (multiplying) the likelihoods over the different maps, etc.

These kinds of metric maps can be kept inside (list may be incomplete, refer to classes derived from mrpt::maps::CMetricMap):

See CMultiMetricMap::setListOfMaps() for the method for initializing this class programmatically. See also TSetOfMetricMapInitializers::loadFromConfigFile for a template of “.ini”-like configuration file that can be used to define which maps to create and all their parameters. Alternatively, the list of maps is public so it can be directly manipulated/accessed in CMultiMetricMap::maps

Method #1: Using map definition structures

mrpt::maps::TSetOfMetricMapInitializers map_inits;
{
  mrpt::maps::COccupancyGridMap2D::TMapDefinition def;
  def.resolution = 0.05;
  def.insertionOpts.maxOccupancyUpdateCertainty = 0.8;
  def.insertionOpts.maxDistanceInsertion = 30;
  map_inits.push_back(def);
}
{
  mrpt::maps::CSimplePointsMap::TMapDefinition def;
  map_inits.push_back(def);
}
mrpt::maps::CMultiMetricMap theMap;
theMap.setListOfMaps(map_inits);

Method #2: Using a configuration file See TSetOfMetricMapInitializers::loadFromConfigFile() for details on expected file format.

mrpt::config::CConfigFile cfgFile("file.cfg");
mrpt::maps::TSetOfMetricMapInitializers map_inits;
map_inits.loadFromConfigFile(cfgFile, "MapDefinition");

mrpt::maps::CMultiMetricMap theMap;
theMap.setListOfMaps(map_inits);

Method #3: Manual manipulation

mrpt::maps::CMultiMetricMap theMap;
{
 auto ptMap = mrpt::maps::CSimplePointsMap::Create();
 theMap.maps.push_back(ptMap);
}

[New in MRPT 1.3.0]: likelihoodMapSelection, which selected the map to be used when computing the likelihood of an observation, has been removed. Use the enableObservationLikelihood property of each individual map declaration.

[New in MRPT 1.3.0]: enableInsertion_{pointsMap,...} have been also removed. Use the enableObservationInsertion property of each map declaration.

This class belongs to [mrpt-slam] instead of [mrpt-maps] due to the dependency on map classes in mrpt-vision.

See also:

CMetricMap

#include <mrpt/maps/CMultiMetricMap.h>

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

    typedef std::deque<mrpt::maps::CMetricMap::Ptr> TListMaps;
    typedef TListMaps::iterator iterator;
    typedef TListMaps::const_iterator const_iterator;

    //
fields

    TListMaps maps;

    // construction

    CMultiMetricMap();
    CMultiMetricMap(const TSetOfMetricMapInitializers& initializers);
    CMultiMetricMap(const CMultiMetricMap& o);
    CMultiMetricMap(CMultiMetricMap&&);

    //
methods

    iterator begin();
    const_iterator begin() const;
    iterator end();
    const_iterator end() const;
    mrpt::maps::CMetricMap::Ptr mapByIndex(size_t idx) const;

    template <typename T>
    T::Ptr mapByClass(size_t ith = 0) const;

    template <typename T>
    std::size_t countMapsByClass() const;

    CMultiMetricMap& operator = (const CMultiMetricMap& o);
    CMultiMetricMap& operator = (CMultiMetricMap&&);
    void setListOfMaps(const mrpt::maps::TSetOfMetricMapInitializers& init);
    virtual bool isEmpty() const;

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

    virtual float compute3DMatchingRatio(const mrpt::maps::CMetricMap* otherMap, const mrpt::poses::CPose3D& otherMapPose, const TMatchingRatioParams& params) const;
    virtual void saveMetricMapRepresentationToFile(const std::string& filNamePrefix) const;
    virtual void auxParticleFilterCleanUp();
    virtual void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr& outObj) const;
    virtual const mrpt::maps::CSimplePointsMap* getAsSimplePointsMap() const;
};

Inherited Members

public:
    //
methods

    virtual bool isEmpty() const = 0;
    virtual void saveMetricMapRepresentationToFile(const std::string& filNamePrefix) const = 0;
    virtual void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr& outObj) const = 0;

Fields

TListMaps maps

The list of metric maps in this object.

Use dynamic_cast or smart pointer-based downcast to access maps by their actual type. You can directly manipulate this list. Helper methods to initialize it are described in the docs of CMultiMetricMap

Construction

CMultiMetricMap()

Default ctor: empty list of maps.

CMultiMetricMap(const TSetOfMetricMapInitializers& initializers)

Constructor with a list of map initializers.

Parameters:

initializers

One internal map will be created for each entry in this “TSetOfMetricMapInitializers” struct.

CMultiMetricMap(const CMultiMetricMap& o)

Creates a deep copy.

CMultiMetricMap(CMultiMetricMap&&)

Move ctor.

Methods

mrpt::maps::CMetricMap::Ptr mapByIndex(size_t idx) const

Gets the i-th map On out-of-bounds.

template <typename T>
T::Ptr mapByClass(size_t ith = 0) const

Returns the i’th map of a given class (or of a derived class), or empty smart pointer if there is no such map.

Example:

 COccupancyGridMap2D::Ptr obs =
multimap.mapByClass<COccupancyGridMap2D>();

By default (ith=0), the first match is returned.

template <typename T>
std::size_t countMapsByClass() const

Count how many maps exist of the given class (or derived class)

CMultiMetricMap& operator = (const CMultiMetricMap& o)

Creates a deep copy.

CMultiMetricMap& operator = (CMultiMetricMap&&)

Move operator.

void setListOfMaps(const mrpt::maps::TSetOfMetricMapInitializers& init)

Sets the list of internal map according to the passed list of map initializers (current maps will be deleted)

virtual bool isEmpty() const

Returns true if all maps returns true in their isEmpty() method.

virtual void determineMatching2D(
    const mrpt::maps::CMetricMap* otherMap,
    const mrpt::poses::CPose2D& otherMapPose,
    mrpt::tfest::TMatchingPairList& correspondences,
    const mrpt::maps::TMatchingParams& params,
    mrpt::maps::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

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

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).

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 void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr& outObj) const

Returns a 3D object representing the map.

See also:

genericMapParams, TMapGenericParams::enableSaveAs3DObject

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