Main MRPT website > C++ reference
MRPT logo
List of all members | Public Types | Public Member Functions | Public Attributes | Static Protected Member Functions | Protected Attributes
mrpt::slam::TSetOfMetricMapInitializers Class Reference

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 404 of file CMultiMetricMap.h.

#include <mrpt/slam/CMultiMetricMap.h>

Inheritance diagram for mrpt::slam::TSetOfMetricMapInitializers:
Inheritance graph
[legend]

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. More...
 
void dumpToTextStream (CStream &out) const
 This method dumps the options of the multi-metric map AND those of every internal map. More...
 
void loadFromConfigFileName (const std::string &config_file, const std::string &section)
 Behaves like loadFromConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to load the file. More...
 
virtual void saveToConfigFile (mrpt::utils::CConfigFileBase &target, const std::string &section) const
 This method saves the options to a ".ini"-like file or memory-stored string list. More...
 
void saveToConfigFileName (const std::string &config_file, const std::string &section) const
 Behaves like saveToConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to save the file. More...
 
void dumpToConsole () const
 Just like dumpToTextStream() but sending the text to the console (std::cout) More...
 

Public Attributes

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

Static Protected Member Functions

static void dumpVar_int (CStream &out, const char *varName, int v)
 Used to print variable info from dumpToTextStream with the macro LOADABLEOPTS_DUMP_VAR. More...
 
static void dumpVar_float (CStream &out, const char *varName, float v)
 
static void dumpVar_double (CStream &out, const char *varName, double v)
 
static void dumpVar_bool (CStream &out, const char *varName, bool v)
 
static void dumpVar_string (CStream &out, const char *varName, const std::string &v)
 

Protected Attributes

std::deque< TMetricMapInitializerm_list
 

Member Typedef Documentation

◆ const_iterator

Definition at line 414 of file CMultiMetricMap.h.

◆ iterator

Definition at line 413 of file CMultiMetricMap.h.

Constructor & Destructor Documentation

◆ TSetOfMetricMapInitializers()

mrpt::slam::TSetOfMetricMapInitializers::TSetOfMetricMapInitializers ( )
inline

Definition at line 425 of file CMultiMetricMap.h.

Member Function Documentation

◆ begin() [1/2]

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

Definition at line 416 of file CMultiMetricMap.h.

◆ begin() [2/2]

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

Definition at line 417 of file CMultiMetricMap.h.

◆ clear()

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

Definition at line 422 of file CMultiMetricMap.h.

◆ dumpToConsole()

void mrpt::utils::CLoadableOptions::dumpToConsole ( ) const
inherited

Just like dumpToTextStream() but sending the text to the console (std::cout)

◆ dumpToTextStream()

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.

Reimplemented from mrpt::utils::CLoadableOptions.

◆ dumpVar_bool()

static void mrpt::utils::CLoadableOptions::dumpVar_bool ( CStream out,
const char *  varName,
bool  v 
)
staticprotectedinherited

◆ dumpVar_double()

static void mrpt::utils::CLoadableOptions::dumpVar_double ( CStream out,
const char *  varName,
double  v 
)
staticprotectedinherited

◆ dumpVar_float()

static void mrpt::utils::CLoadableOptions::dumpVar_float ( CStream out,
const char *  varName,
float  v 
)
staticprotectedinherited

◆ dumpVar_int()

static void mrpt::utils::CLoadableOptions::dumpVar_int ( CStream out,
const char *  varName,
int  v 
)
staticprotectedinherited

Used to print variable info from dumpToTextStream with the macro LOADABLEOPTS_DUMP_VAR.

◆ dumpVar_string()

static void mrpt::utils::CLoadableOptions::dumpVar_string ( CStream out,
const char *  varName,
const std::string &  v 
)
staticprotectedinherited

◆ end() [1/2]

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

Definition at line 419 of file CMultiMetricMap.h.

◆ end() [2/2]

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

Definition at line 420 of file CMultiMetricMap.h.

◆ loadFromConfigFile()

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>
octoMap_count=<Number of mrpt::slam::COctoMap maps>
colourOctoMap_count=<Number of mrpt::slam::CColourOctoMap maps>
gasGrid_count=<Number of mrpt::slam::CGasConcentrationGridMap2D maps>
wifiGrid_count=<Number of mrpt::slam::CWirelessPowerGridMap2D 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>
reflectivityMap_count=<Number of mrpt::slam::CReflectivityGridMap2D maps>
colourPointsMap_count=<0 or 1, for creating a mrpt::slam::CColouredPointsMap map>
weightedPointsMap_count=<0 or 1, for creating a mrpt::slam::CWeightedPointsMap map>
// Selection of map for likelihood. Either a numeric value or the textual enum
// enum value of slam::CMultiMetricMap::TOptions::TMapSelectionForLikelihood (e.g: either "-1" or "fuseAll", ect...)
likelihoodMapSelection = -1
// Enables (1 or "true") / Disables (0 or "false") insertion into specific maps (Defaults are all "true"):
enableInsertion_pointsMap=<0/1>
enableInsertion_landmarksMap=<0/1>
enableInsertion_gridMaps=<0/1>
enableInsertion_gasGridMaps=<0/1>
enableInsertion_wifiGridMaps=<0/1>
enableInsertion_beaconMap=<0/1>
enableInsertion_heightMap=<0/1>
enableInsertion_reflectivityMap=<0/1>
enableInsertion_colourPointsMap=<0/1>
enableInsertion_weightedPointsMap=<0/1>
enableInsertion_octoMaps=<0/1>
enableInsertion_colourOctoMaps=<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>
// ====================================================
// 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 CSimplePointsMap ##:
[<sectionName>+"_pointsMap_##_insertOpts"]
<See CPointsMap::TInsertionOptions>
// Likelihood Options for CSimplePointsMap ##:
[<sectionName>+"_pointsMap_##_likelihoodOpts"]
<See CPointsMap::TLikelihoodOptions>
// ====================================================
// Creation Options for CGasConcentrationGridMap2D ##:
[<sectionName>+"_gasGrid_##_creationOpts"]
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"]
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>+"_reflectivityGrid_##_creationOpts"]
min_x=<value> // See CReflectivityGridMap2D::CReflectivityGridMap2D
max_x=<value>
min_y=<value>
max_y=<value>
resolution=<value>
// Insertion Options for HeightGridMap ##:
[<sectionName>+"_reflectivityGrid_##_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 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")
Note
Examples of map definitions can be found in the '.ini' files provided in the demo directories: "share/mrpt/config-files/"

Implements mrpt::utils::CLoadableOptions.

◆ loadFromConfigFileName()

void mrpt::utils::CLoadableOptions::loadFromConfigFileName ( const std::string &  config_file,
const std::string &  section 
)
inherited

Behaves like loadFromConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to load the file.

See also
loadFromConfigFile

◆ push_back()

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

Definition at line 411 of file CMultiMetricMap.h.

◆ saveToConfigFile()

virtual void mrpt::utils::CLoadableOptions::saveToConfigFile ( mrpt::utils::CConfigFileBase target,
const std::string &  section 
) const
inlinevirtualinherited

◆ saveToConfigFileName()

void mrpt::utils::CLoadableOptions::saveToConfigFileName ( const std::string &  config_file,
const std::string &  section 
) const
inherited

Behaves like saveToConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to save the file.

See also
saveToConfigFile, loadFromConfigFileName

◆ size()

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

Definition at line 410 of file CMultiMetricMap.h.

Member Data Documentation

◆ m_list

std::deque<TMetricMapInitializer> mrpt::slam::TSetOfMetricMapInitializers::m_list
protected

Definition at line 407 of file CMultiMetricMap.h.

◆ options

CMultiMetricMap::TOptions mrpt::slam::TSetOfMetricMapInitializers::options

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

Definition at line 431 of file CMultiMetricMap.h.




Page generated by Doxygen 1.8.14 for MRPT 1.1.0 SVN: at lun oct 28 00:54:49 CET 2019 Hosted on:
SourceForge.net Logo