MRPT logo

mrpt::slam::TSetOfMetricMapInitializers Class Reference

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

#include <mrpt/slam/CMultiMetricMap.h>

Inheritance diagram for mrpt::slam::TSetOfMetricMapInitializers:

mrpt::utils::CLoadableOptions

List of all members.

Public Types

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

Public Member Functions

size_t size () const
void push_back (const TMetricMapInitializer &o)
iterator begin ()
const_iterator begin () const
iterator end ()
const_iterator end () const
void clear ()
 TSetOfMetricMapInitializers ()
void loadFromConfigFile (const mrpt::utils::CConfigFileBase &source, const std::string &sectionName)
 Loads the configuration for the set of internal maps from a textual definition in an INI-like file.
void dumpToTextStream (CStream &out) const
 This method dumps the options of the multi-metric map AND those of every internal map.

Public Attributes

CMultiMetricMap::TOptions options
 This options will be loaded when creating the set of maps in CMultiMetricMap (See CMultiMetricMap::TOptions).

Protected Attributes

std::deque< TMetricMapInitializerm_list


Detailed Description

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, utils::CLoadableOptions

Definition at line 458 of file CMultiMetricMap.h.


Member Typedef Documentation

Definition at line 468 of file CMultiMetricMap.h.

Definition at line 467 of file CMultiMetricMap.h.


Constructor & Destructor Documentation

mrpt::slam::TSetOfMetricMapInitializers::TSetOfMetricMapInitializers (  )  [inline]

Definition at line 479 of file CMultiMetricMap.h.


Member Function Documentation

const_iterator mrpt::slam::TSetOfMetricMapInitializers::begin (  )  const [inline]

Definition at line 471 of file CMultiMetricMap.h.

iterator mrpt::slam::TSetOfMetricMapInitializers::begin (  )  [inline]

Definition at line 470 of file CMultiMetricMap.h.

void mrpt::slam::TSetOfMetricMapInitializers::clear ( void   )  [inline]

Definition at line 476 of file CMultiMetricMap.h.

void mrpt::slam::TSetOfMetricMapInitializers::dumpToTextStream ( CStream out  )  const [virtual]

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

Implements mrpt::utils::CLoadableOptions.

const_iterator mrpt::slam::TSetOfMetricMapInitializers::end (  )  const [inline]

Definition at line 474 of file CMultiMetricMap.h.

iterator mrpt::slam::TSetOfMetricMapInitializers::end (  )  [inline]

Definition at line 473 of file CMultiMetricMap.h.

void mrpt::slam::TSetOfMetricMapInitializers::loadFromConfigFile ( const mrpt::utils::CConfigFileBase source,
const std::string &  sectionName 
) [virtual]

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 utils::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::slam::COccupancyGridMap2D maps>
  gasGrid_count=<Number of mrpt::slam::CGasConcentrationGridMap2D maps>
  landmarksMap_count=<0 or 1, for creating a mrpt::slam::CLandmarksMap map>
  beaconMap_count=<0 or 1, for creating a mrpt::slam::CBeaconMap map>
  pointsMap_count=<Number of mrpt::slam::CSimplePointsMap map>
  heightMap_count=<Number of mrpt::slam::CHeightGridMap2D maps>
  colourPointsMap_count=<0 or 1, for creating a mrpt::slam::CColouredPointsMap map>

  ; Selection of map for likelihood: (fuseAll=-1, occGrid=0, points=1,landmarks=2,gasGrid=3,4=landmarks SOG, 5=beacon map, 6=height map)
  likelihoodMapSelection=[-1, 6]

  ; Enables (1) / Disables (0) insertion into specific maps:
  enableInsertion_pointsMap=<0/1>
  enableInsertion_landmarksMap=<0/1>
  enableInsertion_gridMaps=<0/1>
  enableInsertion_gasGridMaps=<0/1>
  enableInsertion_beaconMap=<0/1>
  enableInsertion_heightMap=<0/1>
  enableInsertion_colourPointsMap=<0/1>

 ; Creation Options for OccupancyGridMap ##:
 [<sectionName>+"_occupancyGrid_##_creationOpts"]
  min_x=<value>
  max_x=<value>
  min_y=<value>
  max_y=<value>
  resolution=<value>

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

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



 ; Insertion Options for CSimplePointsMap ##:
 [<sectionName>+"_pointsMap_##_insertOpts"]
  <See CPointsMap::TInsertionOptions>


 ; 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 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>


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


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

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

Implements mrpt::utils::CLoadableOptions.

void mrpt::slam::TSetOfMetricMapInitializers::push_back ( const TMetricMapInitializer o  )  [inline]

Definition at line 465 of file CMultiMetricMap.h.

size_t mrpt::slam::TSetOfMetricMapInitializers::size (  )  const [inline]

Definition at line 464 of file CMultiMetricMap.h.


Member Data Documentation

Definition at line 461 of file CMultiMetricMap.h.

This options will be loaded when creating the set of maps in CMultiMetricMap (See CMultiMetricMap::TOptions).

Definition at line 485 of file CMultiMetricMap.h.




Page generated by Doxygen 1.5.9 for MRPT 0.7.1 SVN: at Mon Aug 17 22:21:34 EDT 2009