Class TSetOfMetricMapInitializers
Defined in File TMetricMapInitializer.h
Inheritance Relationships
Base Type
public mrpt::config::CLoadableOptions
Class Documentation
-
class TSetOfMetricMapInitializers : public mrpt::config::CLoadableOptions
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
Public Types
-
using iterator = std::deque<TMetricMapInitializer::Ptr>::iterator
-
using const_iterator = std::deque<TMetricMapInitializer::Ptr>::const_iterator
Public Functions
-
inline TSetOfMetricMapInitializers()
-
template<typename MAP_DEFINITION>
inline void push_back(const MAP_DEFINITION &o)
-
inline void push_back(const TMetricMapInitializer::Ptr &o)
-
inline size_t size() const
-
inline const_iterator begin() const
-
inline const_iterator end() const
-
inline void clear()
-
virtual void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ionName) override
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> 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 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”)
Note
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 §ion) const override
-
virtual void dumpToTextStream(std::ostream &out) const override
This method dumps the options of the multi-metric map AND those of every internal map.
Protected Attributes
-
std::deque<TMetricMapInitializer::Ptr> m_list
-
using iterator = std::deque<TMetricMapInitializer::Ptr>::iterator