class mrpt::maps::TSetOfMetricMapInitializers

A set of TMetricMapInitializer structures, passed to the constructor CMultiMetricMap::CMultiMetricMap See the comments for TSetOfMetricMapInitializers::loadFromConfigFile, and “CMultiMetricMap::setListOfMaps” for effectively creating the list of desired maps.

See also:

CMultiMetricMap::CMultiMetricMap, CLoadableOptions

#include <mrpt/maps/TMetricMapInitializer.h>

class TSetOfMetricMapInitializers: public mrpt::config::CLoadableOptions
{
public:
    // typedefs

    typedef std::deque<TMetricMapInitializer::Ptr>::iterator iterator;
    typedef std::deque<TMetricMapInitializer::Ptr>::const_iterator const_iterator;

    // construction

    TSetOfMetricMapInitializers();

    //
methods

    template <typename MAP_DEFINITION>
    void push_back(const MAP_DEFINITION& o);

    void push_back(const TMetricMapInitializer::Ptr& o);
    size_t size() const;
    iterator begin();
    iterator end();
    const_iterator begin() const;
    const_iterator end() const;
    void clear();
    virtual void loadFromConfigFile(const mrpt::config::CConfigFileBase& source, const std::string& sectionName);
    virtual void saveToConfigFile(mrpt::config::CConfigFileBase& target, const std::string& section) const;
    virtual void dumpToTextStream(std::ostream& out) const;
};

Inherited Members

public:
    //
methods

    virtual void loadFromConfigFile(const mrpt::config::CConfigFileBase& source, const std::string& section) = 0;
    void loadFromConfigFileName(const std::string& config_file, const std::string& section);
    virtual void saveToConfigFile(mrpt::config::CConfigFileBase& target, const std::string& section) const;
    void saveToConfigFileName(const std::string& config_file, const std::string& section) const;
    void dumpToConsole() const;
    virtual void dumpToTextStream(std::ostream& out) const;

Methods

virtual void loadFromConfigFile(const mrpt::config::CConfigFileBase& source, const std::string& sectionName)

Loads the configuration for the set of internal maps from a textual definition in an INI-like file.

The format of the ini file is defined in CConfigFile. The list of maps and their options will be loaded from a handle of sections:

 [<sectionName>]
  // Creation of maps:
  occupancyGrid_count=<Number of mrpt::maps::COccupancyGridMap2D maps>
  octoMap_count=<Number of mrpt::maps::COctoMap maps>
  colourOctoMap_count=<Number of mrpt::slam::CColourOctoMap maps>
  gasGrid_count=<Number of mrpt::maps::CGasConcentrationGridMap2D maps>
  wifiGrid_count=<Number of mrpt::maps::CWirelessPowerGridMap2D maps>
  beaconMap_count=<0 or 1, for creating a mrpt::maps::CBeaconMap map>
  pointsMap_count=<Number of mrpt::maps::CSimplePointsMap map>
  heightMap_count=<Number of mrpt::maps::CHeightGridMap2D maps>
  reflectivityMap_count=<Number of mrpt::maps::CReflectivityGridMap2D
*maps>
  colourPointsMap_count=<0 or 1, for creating a
*mrpt::maps::CColouredPointsMap map>
  weightedPointsMap_count=<0 or 1, for creating a
*mrpt::maps::CWeightedPointsMap map>
  mrpt::maps::CVoxelMap_count=[0|1]
  mrpt::maps::CVoxelMapRGB_count=[0|1]

 // ====================================================
 //  Creation Options for OccupancyGridMap ##:
 [<sectionName>+"_occupancyGrid_##_creationOpts"]
  min_x=<value>
  max_x=<value>
  min_y=<value>
  max_y=<value>
  resolution=<value>
  # Common params for all maps:
  #enableSaveAs3DObject        = {true|false}
  #enableObservationLikelihood = {true|false}
  #enableObservationInsertion  = {true|false}

 // Insertion Options for OccupancyGridMap ##:
 [<sectionName>+"_occupancyGrid_##_insertOpts"]
  <See COccupancyGridMap2D::TInsertionOptions>

 // Likelihood Options for OccupancyGridMap ##:
 [<sectionName>+"_occupancyGrid_##_likelihoodOpts"]
  <See COccupancyGridMap2D::TLikelihoodOptions>

 // ====================================================
 //  Creation Options for OctoMap ##:
 [<sectionName>+"_octoMap_##_creationOpts"]
  resolution=<value>

 // Insertion Options for OctoMap ##:
 [<sectionName>+"_octoMap_##_insertOpts"]
  <See COctoMap::TInsertionOptions>

 // Likelihood Options for OctoMap ##:
 [<sectionName>+"_octoMap_##_likelihoodOpts"]
  <See COctoMap::TLikelihoodOptions>

 // ====================================================
 //  Creation Options for ColourOctoMap ##:
 [<sectionName>+"_colourOctoMap_##_creationOpts"]
  resolution=<value>

 // Insertion Options for ColourOctoMap ##:
 [<sectionName>+"_colourOctoMap_##_insertOpts"]
  <See CColourOctoMap::TInsertionOptions>

 // Likelihood Options for ColourOctoMap ##:
 [<sectionName>+"_colourOctoMap_##_likelihoodOpts"]
  <See CColourOctoMap::TLikelihoodOptions>


 // ====================================================
 // Insertion Options for mrpt::maps::CSimplePointsMap ##:
 [<sectionName>+"_pointsMap_##_insertOpts"]
  <See CPointsMap::TInsertionOptions>

 // Likelihood Options for mrpt::maps::CSimplePointsMap ##:
 [<sectionName>+"_pointsMap_##_likelihoodOpts"]
  <See CPointsMap::TLikelihoodOptions>


 // ====================================================
 // Creation Options for CGasConcentrationGridMap2D ##:
 [<sectionName>+"_gasGrid_##_creationOpts"]
  mapType= <0-1> ; See
*CGasConcentrationGridMap2D::CGasConcentrationGridMap2D
  min_x=<value>
  max_x=<value>
  min_y=<value>
  max_y=<value>
  resolution=<value>

 // Insertion Options for CGasConcentrationGridMap2D ##:
 [<sectionName>+"_gasGrid_##_insertOpts"]
  <See CGasConcentrationGridMap2D::TInsertionOptions>

 // ====================================================
 // Creation Options for CWirelessPowerGridMap2D ##:
 [<sectionName>+"_wifiGrid_##_creationOpts"]
  mapType= <0-1> ; See CWirelessPowerGridMap2D::CWirelessPowerGridMap2D
  min_x=<value>
  max_x=<value>
  min_y=<value>
  max_y=<value>
  resolution=<value>

 // Insertion Options for CWirelessPowerGridMap2D ##:
 [<sectionName>+"_wifiGrid_##_insertOpts"]
  <See CWirelessPowerGridMap2D::TInsertionOptions>


 // ====================================================
 // Creation Options for CLandmarksMap ##:
 [<sectionName>+"_landmarksMap_##_creationOpts"]
  nBeacons=<# of beacons>
  beacon_001_ID=67      ; The ID and 3D coordinates of each beacon
  beacon_001_X=<x>
  beacon_001_Y=<x>
  beacon_001_Z=<x>

 // Insertion Options for CLandmarksMap ##:
 [<sectionName>+"_landmarksMap_##_insertOpts"]
  <See CLandmarksMap::TInsertionOptions>

 // Likelihood Options for CLandmarksMap ##:
 [<sectionName>+"_landmarksMap_##_likelihoodOpts"]
  <See CLandmarksMap::TLikelihoodOptions>


 // ====================================================
 // Insertion Options for CBeaconMap ##:
 [<sectionName>+"_beaconMap_##_insertOpts"]
  <See CBeaconMap::TInsertionOptions>

 // Likelihood Options for CBeaconMap ##:
 [<sectionName>+"_beaconMap_##_likelihoodOpts"]
  <See CBeaconMap::TLikelihoodOptions>

 // ====================================================
 // Creation Options for HeightGridMap ##:
 [<sectionName>+"_heightGrid_##_creationOpts"]
  mapType= <0-1> // See CHeightGridMap2D::CHeightGridMap2D
  min_x=<value>
  max_x=<value>
  min_y=<value>
  max_y=<value>
  resolution=<value>

 // Insertion Options for HeightGridMap ##:
 [<sectionName>+"_heightGrid_##_insertOpts"]
  <See CHeightGridMap2D::TInsertionOptions>


 // ====================================================
 // Creation Options for ReflectivityGridMap ##:
 [<sectionName>+"_reflectivityMap_##_creationOpts"]
  min_x=<value>  // See CReflectivityGridMap2D::CReflectivityGridMap2D
  max_x=<value>
  min_y=<value>
  max_y=<value>
  resolution=<value>

 // Insertion Options for HeightGridMap ##:
 [<sectionName>+"_reflectivityMap_##_insertOpts"]
  <See CReflectivityGridMap2D::TInsertionOptions>


 // ====================================================
 // Insertion Options for CColouredPointsMap ##:
 [<sectionName>+"_colourPointsMap_##_insertOpts"]
  <See CPointsMap::TInsertionOptions>


 // Color Options for CColouredPointsMap ##:
 [<sectionName>+"_colourPointsMap_##_colorOpts"]
  <See CColouredPointsMap::TColourOptions>

 // Likelihood Options for mrpt::maps::CSimplePointsMap ##:
 [<sectionName>+"_colourPointsMap_##_likelihoodOpts"]
  <See CPointsMap::TLikelihoodOptions>


 // ====================================================
 // Insertion Options for CWeightedPointsMap ##:
 [<sectionName>+"_weightedPointsMap_##_insertOpts"]
  <See CPointsMap::TInsertionOptions>


 // Likelihood Options for CWeightedPointsMap ##:
 [<sectionName>+"_weightedPointsMap_##_likelihoodOpts"]
  <See CPointsMap::TLikelihoodOptions>

Where:

  • ##: Represents the index of the map (e.g. “00”,”01”,…)

  • By default, the variables into each “TOptions” structure of the maps are defined in textual form by the same name of the corresponding C++ variable (e.g. “float resolution;” -> “resolution=0.10”)

Examples of map definitions can be found in the ‘.ini’ files provided in the demo directories: “share/mrpt/config-files/”

virtual void saveToConfigFile(mrpt::config::CConfigFileBase& target, const std::string& section) const

This method saves the options to a “.ini”-like file or memory-stored string list.

See also:

loadFromConfigFile, saveToConfigFileName

virtual void dumpToTextStream(std::ostream& out) const

This method dumps the options of the multi-metric map AND those of every internal map.