<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN"> <html><head><meta http-equiv="Content-Type" content="text/html;charset=iso-8859-1"> <title>The MRPT project: mrpt::slam::TSetOfMetricMapInitializers Class Reference</title> <link href="doxygen.css" rel="stylesheet" type="text/css"> <link href="tabs.css" rel="stylesheet" type="text/css"> </head><body> <div align="left"><a href="http://www.mrpt.org/">Main MRPT website</a> > <b>C++ reference</b> </div> <div align="right"> <a href="index.html"><img border="0" src="mrpt_logo.png" alt="MRPT logo"></a> </div> <!-- Generated by Doxygen 1.7.2 --> <script type="text/javascript"><!-- var searchBox = new SearchBox("searchBox", "search",false,'Search'); --></script> <div class="navigation" id="top"> <div class="tabs"> <ul class="tablist"> <li><a href="index.html"><span>Main Page</span></a></li> <li><a href="pages.html"><span>Related Pages</span></a></li> <li><a href="modules.html"><span>Modules</span></a></li> <li><a href="namespaces.html"><span>Namespaces</span></a></li> <li class="current"><a href="annotated.html"><span>Classes</span></a></li> <li><a href="files.html"><span>Files</span></a></li> <li id="searchli"> <div id="MSearchBox" class="MSearchBoxInactive"> <span class="left"> <form id="FSearchBox" action="search.php" method="get"> <img id="MSearchSelect" src="search/mag.png" alt=""/> <input type="text" id="MSearchField" name="query" value="Search" size="20" accesskey="S" onfocus="searchBox.OnSearchFieldFocus(true)" onblur="searchBox.OnSearchFieldFocus(false)"/> </form> </span><span class="right"></span> </div> </li> </ul> </div> <div class="tabs2"> <ul class="tablist"> <li><a href="annotated.html"><span>Class List</span></a></li> <li><a href="classes.html"><span>Class Index</span></a></li> <li><a href="hierarchy.html"><span>Class Hierarchy</span></a></li> <li><a href="functions.html"><span>Class Members</span></a></li> </ul> </div> <div class="navpath"> <ul> <li><a class="el" href="namespacemrpt.html">mrpt</a> </li> <li><a class="el" href="namespacemrpt_1_1slam.html">slam</a> </li> <li><a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html">TSetOfMetricMapInitializers</a> </li> </ul> </div> </div> <div class="header"> <div class="summary"> <a href="#pub-types">Public Types</a> | <a href="#pub-methods">Public Member Functions</a> | <a href="#pub-attribs">Public Attributes</a> | <a href="#pro-attribs">Protected Attributes</a> </div> <div class="headertitle"> <h1>mrpt::slam::TSetOfMetricMapInitializers Class Reference</h1> </div> </div> <div class="contents"> <!-- doxytag: class="mrpt::slam::TSetOfMetricMapInitializers" --><!-- doxytag: inherits="mrpt::utils::CLoadableOptions" --><hr/><a name="_details"></a><h2>Detailed Description</h2> <p>A set of <a class="el" href="structmrpt_1_1slam_1_1_t_metric_map_initializer.html" title="Each structure of this kind will determine the kind (and initial configuration) of one map to be buil...">TMetricMapInitializer</a> structures, passed to the constructor <a class="el" href="classmrpt_1_1slam_1_1_c_multi_metric_map.html#a739659c0385be2fbcbf695431f4da92f" title="Constructor.">CMultiMetricMap::CMultiMetricMap</a> See the comments for <a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a48e5c339561ec695921aa7db6291c0e1" title="Loads the configuration for the set of internal maps from a textual definition in an INI-like file...">TSetOfMetricMapInitializers::loadFromConfigFile</a>, and "CMultiMetricMap::setListOfMaps" for effectively creating the list of desired maps. </p> <dl class="see"><dt><b>See also:</b></dt><dd><a class="el" href="classmrpt_1_1slam_1_1_c_multi_metric_map.html#a739659c0385be2fbcbf695431f4da92f" title="Constructor.">CMultiMetricMap::CMultiMetricMap</a>, <a class="el" href="classmrpt_1_1utils_1_1_c_loadable_options.html" title="This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...">utils::CLoadableOptions</a> </dd></dl> <p>Definition at line <a class="el" href="_c_multi_metric_map_8h_source.html#l00417">417</a> of file <a class="el" href="_c_multi_metric_map_8h_source.html">CMultiMetricMap.h</a>.</p> <p><code>#include <<a class="el" href="_c_multi_metric_map_8h_source.html">mrpt/slam/CMultiMetricMap.h</a>></code></p> <!-- startSectionHeader --><div class="dynheader"> Inheritance diagram for mrpt::slam::TSetOfMetricMapInitializers:<!-- endSectionHeader --></div> <!-- startSectionSummary --><!-- endSectionSummary --><!-- startSectionContent --><div class="dyncontent"> <div class="center"><img src="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers__inherit__graph.png" border="0" usemap="#mrpt_1_1slam_1_1_t_set_of_metric_map_initializers_inherit__map" alt="Inheritance graph"/></div> <map name="mrpt_1_1slam_1_1_t_set_of_metric_map_initializers_inherit__map" id="mrpt_1_1slam_1_1_t_set_of_metric_map_initializers_inherit__map"> </map> <center><span class="legend">[<a href="graph_legend.html">legend</a>]</span></center><!-- endSectionContent --></div> <p><a href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers-members.html">List of all members.</a></p> <table class="memberdecls"> <tr><td colspan="2"><h2><a name="pub-types"></a> Public Types</h2></td></tr> <tr><td class="memItemLeft" align="right" valign="top">typedef std::deque<br class="typebreak"/> < <a class="el" href="structmrpt_1_1slam_1_1_t_metric_map_initializer.html">TMetricMapInitializer</a> ><br class="typebreak"/> ::<a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a8d0f738ef0afc55effc0f815538ca984">iterator</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a8d0f738ef0afc55effc0f815538ca984">iterator</a></td></tr> <tr><td class="memItemLeft" align="right" valign="top">typedef std::deque<br class="typebreak"/> < <a class="el" href="structmrpt_1_1slam_1_1_t_metric_map_initializer.html">TMetricMapInitializer</a> ><br class="typebreak"/> ::<a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a4e9a96b31cb1761f07615baffae6d8f6">const_iterator</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a4e9a96b31cb1761f07615baffae6d8f6">const_iterator</a></td></tr> <tr><td colspan="2"><h2><a name="pub-methods"></a> Public Member Functions</h2></td></tr> <tr><td class="memItemLeft" align="right" valign="top">size_t </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a3a5b34d7d9d696696a2e7fc5cea417a7">size</a> () const </td></tr> <tr><td class="memItemLeft" align="right" valign="top">void </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a553ed89696aa33990d08c2c4b39ca65b">push_back</a> (const <a class="el" href="structmrpt_1_1slam_1_1_t_metric_map_initializer.html">TMetricMapInitializer</a> &o)</td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a8d0f738ef0afc55effc0f815538ca984">iterator</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a98137fc7997147ffa1713af24961e76a">begin</a> ()</td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a4e9a96b31cb1761f07615baffae6d8f6">const_iterator</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a96119e42b2f27ed76a47d7abf696f859">begin</a> () const </td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a8d0f738ef0afc55effc0f815538ca984">iterator</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a0f32b5411b61f31ebddeb0877d0a6df2">end</a> ()</td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a4e9a96b31cb1761f07615baffae6d8f6">const_iterator</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a124c2edf48a421a801e3238175fc7666">end</a> () const </td></tr> <tr><td class="memItemLeft" align="right" valign="top">void </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a3364f6249885df265b8b51b3aa897b97">clear</a> ()</td></tr> <tr><td class="memItemLeft" align="right" valign="top"> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a040d1f789af9a2355003d54e08a116ba">TSetOfMetricMapInitializers</a> ()</td></tr> <tr><td class="memItemLeft" align="right" valign="top">void </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a48e5c339561ec695921aa7db6291c0e1">loadFromConfigFile</a> (const <a class="el" href="classmrpt_1_1utils_1_1_c_config_file_base.html">mrpt::utils::CConfigFileBase</a> &source, const std::string &sectionName)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Loads the configuration for the set of internal maps from a textual definition in an INI-like file. <a href="#a48e5c339561ec695921aa7db6291c0e1"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">void </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a3f84190d33393e4db90c2f2ef974b862">dumpToTextStream</a> (<a class="el" href="classmrpt_1_1utils_1_1_c_stream.html">CStream</a> &out) const </td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">This method dumps the options of the multi-metric map AND those of every internal map. <a href="#a3f84190d33393e4db90c2f2ef974b862"></a><br/></td></tr> <tr><td colspan="2"><h2><a name="pub-attribs"></a> Public Attributes</h2></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="structmrpt_1_1slam_1_1_c_multi_metric_map_1_1_t_options.html">CMultiMetricMap::TOptions</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a9514fdc98b98a7b185b44d17df3d6f82">options</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">This options will be loaded when creating the set of maps in <a class="el" href="classmrpt_1_1slam_1_1_c_multi_metric_map.html" title="This class stores any customizable set of metric maps.">CMultiMetricMap</a> (See <a class="el" href="structmrpt_1_1slam_1_1_c_multi_metric_map_1_1_t_options.html" title="Some options for this class:">CMultiMetricMap::TOptions</a>) <a href="#a9514fdc98b98a7b185b44d17df3d6f82"></a><br/></td></tr> <tr><td colspan="2"><h2><a name="pro-attribs"></a> Protected Attributes</h2></td></tr> <tr><td class="memItemLeft" align="right" valign="top">std::deque< <a class="el" href="structmrpt_1_1slam_1_1_t_metric_map_initializer.html">TMetricMapInitializer</a> > </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a3b348c4018cd73db5e5539968ee54a05">m_list</a></td></tr> </table> <hr/><h2>Member Typedef Documentation</h2> <a class="anchor" id="a4e9a96b31cb1761f07615baffae6d8f6"></a><!-- doxytag: member="mrpt::slam::TSetOfMetricMapInitializers::const_iterator" ref="a4e9a96b31cb1761f07615baffae6d8f6" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">typedef std::deque<<a class="el" href="structmrpt_1_1slam_1_1_t_metric_map_initializer.html">TMetricMapInitializer</a>>::<a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a4e9a96b31cb1761f07615baffae6d8f6">const_iterator</a> <a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a4e9a96b31cb1761f07615baffae6d8f6">mrpt::slam::TSetOfMetricMapInitializers::const_iterator</a></td> </tr> </table> </div> <div class="memdoc"> <p>Definition at line <a class="el" href="_c_multi_metric_map_8h_source.html#l00427">427</a> of file <a class="el" href="_c_multi_metric_map_8h_source.html">CMultiMetricMap.h</a>.</p> </div> </div> <a class="anchor" id="a8d0f738ef0afc55effc0f815538ca984"></a><!-- doxytag: member="mrpt::slam::TSetOfMetricMapInitializers::iterator" ref="a8d0f738ef0afc55effc0f815538ca984" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">typedef std::deque<<a class="el" href="structmrpt_1_1slam_1_1_t_metric_map_initializer.html">TMetricMapInitializer</a>>::<a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a8d0f738ef0afc55effc0f815538ca984">iterator</a> <a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a8d0f738ef0afc55effc0f815538ca984">mrpt::slam::TSetOfMetricMapInitializers::iterator</a></td> </tr> </table> </div> <div class="memdoc"> <p>Definition at line <a class="el" href="_c_multi_metric_map_8h_source.html#l00426">426</a> of file <a class="el" href="_c_multi_metric_map_8h_source.html">CMultiMetricMap.h</a>.</p> </div> </div> <hr/><h2>Constructor & Destructor Documentation</h2> <a class="anchor" id="a040d1f789af9a2355003d54e08a116ba"></a><!-- doxytag: member="mrpt::slam::TSetOfMetricMapInitializers::TSetOfMetricMapInitializers" ref="a040d1f789af9a2355003d54e08a116ba" args="()" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">mrpt::slam::TSetOfMetricMapInitializers::TSetOfMetricMapInitializers </td> <td>(</td> <td class="paramname"> )</td> <td><code> [inline]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Definition at line <a class="el" href="_c_multi_metric_map_8h_source.html#l00438">438</a> of file <a class="el" href="_c_multi_metric_map_8h_source.html">CMultiMetricMap.h</a>.</p> </div> </div> <hr/><h2>Member Function Documentation</h2> <a class="anchor" id="a98137fc7997147ffa1713af24961e76a"></a><!-- doxytag: member="mrpt::slam::TSetOfMetricMapInitializers::begin" ref="a98137fc7997147ffa1713af24961e76a" args="()" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a8d0f738ef0afc55effc0f815538ca984">iterator</a> mrpt::slam::TSetOfMetricMapInitializers::begin </td> <td>(</td> <td class="paramname"> )</td> <td><code> [inline]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Definition at line <a class="el" href="_c_multi_metric_map_8h_source.html#l00429">429</a> of file <a class="el" href="_c_multi_metric_map_8h_source.html">CMultiMetricMap.h</a>.</p> </div> </div> <a class="anchor" id="a96119e42b2f27ed76a47d7abf696f859"></a><!-- doxytag: member="mrpt::slam::TSetOfMetricMapInitializers::begin" ref="a96119e42b2f27ed76a47d7abf696f859" args="() const " --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a4e9a96b31cb1761f07615baffae6d8f6">const_iterator</a> mrpt::slam::TSetOfMetricMapInitializers::begin </td> <td>(</td> <td class="paramname"> )</td> <td> const<code> [inline]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Definition at line <a class="el" href="_c_multi_metric_map_8h_source.html#l00430">430</a> of file <a class="el" href="_c_multi_metric_map_8h_source.html">CMultiMetricMap.h</a>.</p> </div> </div> <a class="anchor" id="a3364f6249885df265b8b51b3aa897b97"></a><!-- doxytag: member="mrpt::slam::TSetOfMetricMapInitializers::clear" ref="a3364f6249885df265b8b51b3aa897b97" args="()" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::TSetOfMetricMapInitializers::clear </td> <td>(</td> <td class="paramtype">void </td> <td class="paramname"> )</td> <td><code> [inline]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Definition at line <a class="el" href="_c_multi_metric_map_8h_source.html#l00435">435</a> of file <a class="el" href="_c_multi_metric_map_8h_source.html">CMultiMetricMap.h</a>.</p> </div> </div> <a class="anchor" id="a3f84190d33393e4db90c2f2ef974b862"></a><!-- doxytag: member="mrpt::slam::TSetOfMetricMapInitializers::dumpToTextStream" ref="a3f84190d33393e4db90c2f2ef974b862" args="(CStream &out) const " --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::TSetOfMetricMapInitializers::dumpToTextStream </td> <td>(</td> <td class="paramtype"><a class="el" href="classmrpt_1_1utils_1_1_c_stream.html">CStream</a> & </td> <td class="paramname"> <em>out</em> )</td> <td> const<code> [virtual]</code></td> </tr> </table> </div> <div class="memdoc"> <p>This method dumps the options of the multi-metric map AND those of every internal map. </p> <p>Implements <a class="el" href="classmrpt_1_1utils_1_1_c_loadable_options.html#adbe314b74deedfe953290ebf48750883">mrpt::utils::CLoadableOptions</a>.</p> </div> </div> <a class="anchor" id="a0f32b5411b61f31ebddeb0877d0a6df2"></a><!-- doxytag: member="mrpt::slam::TSetOfMetricMapInitializers::end" ref="a0f32b5411b61f31ebddeb0877d0a6df2" args="()" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a8d0f738ef0afc55effc0f815538ca984">iterator</a> mrpt::slam::TSetOfMetricMapInitializers::end </td> <td>(</td> <td class="paramname"> )</td> <td><code> [inline]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Definition at line <a class="el" href="_c_multi_metric_map_8h_source.html#l00432">432</a> of file <a class="el" href="_c_multi_metric_map_8h_source.html">CMultiMetricMap.h</a>.</p> </div> </div> <a class="anchor" id="a124c2edf48a421a801e3238175fc7666"></a><!-- doxytag: member="mrpt::slam::TSetOfMetricMapInitializers::end" ref="a124c2edf48a421a801e3238175fc7666" args="() const " --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a4e9a96b31cb1761f07615baffae6d8f6">const_iterator</a> mrpt::slam::TSetOfMetricMapInitializers::end </td> <td>(</td> <td class="paramname"> )</td> <td> const<code> [inline]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Definition at line <a class="el" href="_c_multi_metric_map_8h_source.html#l00433">433</a> of file <a class="el" href="_c_multi_metric_map_8h_source.html">CMultiMetricMap.h</a>.</p> </div> </div> <a class="anchor" id="a48e5c339561ec695921aa7db6291c0e1"></a><!-- doxytag: member="mrpt::slam::TSetOfMetricMapInitializers::loadFromConfigFile" ref="a48e5c339561ec695921aa7db6291c0e1" args="(const mrpt::utils::CConfigFileBase &source, const std::string &sectionName)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::TSetOfMetricMapInitializers::loadFromConfigFile </td> <td>(</td> <td class="paramtype">const <a class="el" href="classmrpt_1_1utils_1_1_c_config_file_base.html">mrpt::utils::CConfigFileBase</a> & </td> <td class="paramname"> <em>source</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const std::string & </td> <td class="paramname"> <em>sectionName</em> </td> </tr> <tr> <td></td> <td>)</td> <td></td><td><code> [virtual]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Loads the configuration for the set of internal maps from a textual definition in an INI-like file. </p> <p>The format of the ini file is defined in <a class="el" href="classmrpt_1_1utils_1_1_c_config_file.html" title="This class allows loading and storing values and vectors of different types from ".ini" files easily.">utils::CConfigFile</a>. The list of maps and their options will be loaded from a handle of sections:</p> <div class="fragment"><pre class="fragment"> [<sectionName>] ; Creation of maps: occupancyGrid_count=<Number of <a class="code" href="classmrpt_1_1slam_1_1_c_occupancy_grid_map2_d.html" title="A class for storing an occupancy grid map.">mrpt::slam::COccupancyGridMap2D</a> maps> gasGrid_count=<Number of <a class="code" href="classmrpt_1_1slam_1_1_c_gas_concentration_grid_map2_d.html" title="CGasConcentrationGridMap2D represents a PDF of gas concentrations over a 2D area.">mrpt::slam::CGasConcentrationGridMap2D</a> maps> landmarksMap_count=<0 or 1, <span class="keywordflow">for</span> creating a <a class="code" href="classmrpt_1_1slam_1_1_c_landmarks_map.html" title="A class for storing a map of 3D probabilistic landmarks.">mrpt::slam::CLandmarksMap</a> map> beaconMap_count=<0 or 1, <span class="keywordflow">for</span> creating a <a class="code" href="classmrpt_1_1slam_1_1_c_beacon_map.html" title="A class for storing a map of 3D probabilistic beacons, using a Montecarlo, Gaussian, or Sum of Gaussians (SOG) representation (for range-only SLAM).">mrpt::slam::CBeaconMap</a> map> pointsMap_count=<Number of <a class="code" href="classmrpt_1_1slam_1_1_c_simple_points_map.html" title="A cloud of points in 2D or 3D, which can be built from a sequence of laser scans.">mrpt::slam::CSimplePointsMap</a> map> heightMap_count=<Number of <a class="code" href="classmrpt_1_1slam_1_1_c_height_grid_map2_d.html" title="A mesh representation of a surface which keeps the estimated height for each (x,y) location...">mrpt::slam::CHeightGridMap2D</a> maps> colourPointsMap_count=<0 or 1, <span class="keywordflow">for</span> creating a <a class="code" href="classmrpt_1_1slam_1_1_c_coloured_points_map.html" title="A map of 2D/3D points with individual colours (RGB).">mrpt::slam::CColouredPointsMap</a> map> ; Selection of map <span class="keywordflow">for</span> 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 <span class="preprocessor">##:</span> <span class="preprocessor"></span> [<sectionName>+<span class="stringliteral">"_occupancyGrid_##_creationOpts"</span>] min_x=<value> max_x=<value> min_y=<value> max_y=<value> resolution=<value> ; Insertion Options <span class="keywordflow">for</span> OccupancyGridMap ##: [<sectionName>+<span class="stringliteral">"_occupancyGrid_##_insertOpts"</span>] <See COccupancyGridMap2D::TInsertionOptions> ; Likelihood Options <span class="keywordflow">for</span> OccupancyGridMap ##: [<sectionName>+<span class="stringliteral">"_occupancyGrid_##_likelihoodOpts"</span>] <See COccupancyGridMap2D::TLikelihoodOptions> ; Insertion Options <span class="keywordflow">for</span> CSimplePointsMap ##: [<sectionName>+<span class="stringliteral">"_pointsMap_##_insertOpts"</span>] <See CPointsMap::TInsertionOptions> ; Likelihood Options <span class="keywordflow">for</span> CSimplePointsMap ##: [<sectionName>+<span class="stringliteral">"_pointsMap_##_likelihoodOpts"</span>] <See CPointsMap::TLikelihoodOptions> ; Creation Options <span class="keywordflow">for</span> CGasConcentrationGridMap2D ##: [<sectionName>+<span class="stringliteral">"_gasGrid_##_creationOpts"</span>] mapType= <0-1> ; See <a class="code" href="classmrpt_1_1slam_1_1_c_gas_concentration_grid_map2_d.html#a54eafd796fc89f88c882f486cfb27663" title="Constructor.">CGasConcentrationGridMap2D::CGasConcentrationGridMap2D</a> min_x=<value> max_x=<value> min_y=<value> max_y=<value> resolution=<value> ; Insertion Options <span class="keywordflow">for</span> CGasConcentrationGridMap2D ##: [<sectionName>+<span class="stringliteral">"_gasGrid_##_insertOpts"</span>] <See CGasConcentrationGridMap2D::TInsertionOptions> ; Creation Options <span class="keywordflow">for</span> CLandmarksMap ##: [<sectionName>+<span class="stringliteral">"_landmarksMap_##_creationOpts"</span>] 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 <span class="keywordflow">for</span> CLandmarksMap ##: [<sectionName>+<span class="stringliteral">"_landmarksMap_##_insertOpts"</span>] <See CLandmarksMap::TInsertionOptions> ; Likelihood Options <span class="keywordflow">for</span> CLandmarksMap ##: [<sectionName>+<span class="stringliteral">"_landmarksMap_##_likelihoodOpts"</span>] <See CLandmarksMap::TLikelihoodOptions> ; Insertion Options <span class="keywordflow">for</span> CBeaconMap ##: [<sectionName>+<span class="stringliteral">"_beaconMap_##_insertOpts"</span>] <See CBeaconMap::TInsertionOptions> ; Likelihood Options <span class="keywordflow">for</span> CBeaconMap ##: [<sectionName>+<span class="stringliteral">"_beaconMap_##_likelihoodOpts"</span>] <See CBeaconMap::TLikelihoodOptions> ; Creation Options <span class="keywordflow">for</span> HeightGridMap ##: [<sectionName>+<span class="stringliteral">"_heightGrid_##_creationOpts"</span>] mapType= <0-1> ; See <a class="code" href="classmrpt_1_1slam_1_1_c_height_grid_map2_d.html#a232b61acd9b094b2fd9dd329089566ce" title="Constructor.">CHeightGridMap2D::CHeightGridMap2D</a> min_x=<value> max_x=<value> min_y=<value> max_y=<value> resolution=<value> ; Insertion Options <span class="keywordflow">for</span> HeightGridMap ##: [<sectionName>+<span class="stringliteral">"_heightGrid_##_insertOpts"</span>] <See CHeightGridMap2D::TInsertionOptions> ; Insertion Options <span class="keywordflow">for</span> CColouredPointsMap ##: [<sectionName>+<span class="stringliteral">"_colourPointsMap_##_insertOpts"</span>] <See CPointsMap::TInsertionOptions> ; Color Options <span class="keywordflow">for</span> CColouredPointsMap ##: [<sectionName>+<span class="stringliteral">"_colourPointsMap_##_colorOpts"</span>] <See CColouredPointsMap::TColourOptions> ; Likelihood Options <span class="keywordflow">for</span> CSimplePointsMap ##: [<sectionName>+<span class="stringliteral">"_colourPointsMap_##_likelihoodOpts"</span>] <See CPointsMap::TLikelihoodOptions> </pre></div><p>Where:</p> <ul> <li>##: Represents the index of the map (e.g. "00","01",...)</li> <li>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") </li> </ul> <p>Implements <a class="el" href="classmrpt_1_1utils_1_1_c_loadable_options.html#ae2373fce5f2c8d3f0bdad21433becad2">mrpt::utils::CLoadableOptions</a>.</p> </div> </div> <a class="anchor" id="a553ed89696aa33990d08c2c4b39ca65b"></a><!-- doxytag: member="mrpt::slam::TSetOfMetricMapInitializers::push_back" ref="a553ed89696aa33990d08c2c4b39ca65b" args="(const TMetricMapInitializer &o)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::TSetOfMetricMapInitializers::push_back </td> <td>(</td> <td class="paramtype">const <a class="el" href="structmrpt_1_1slam_1_1_t_metric_map_initializer.html">TMetricMapInitializer</a> & </td> <td class="paramname"> <em>o</em> )</td> <td><code> [inline]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Definition at line <a class="el" href="_c_multi_metric_map_8h_source.html#l00424">424</a> of file <a class="el" href="_c_multi_metric_map_8h_source.html">CMultiMetricMap.h</a>.</p> </div> </div> <a class="anchor" id="a3a5b34d7d9d696696a2e7fc5cea417a7"></a><!-- doxytag: member="mrpt::slam::TSetOfMetricMapInitializers::size" ref="a3a5b34d7d9d696696a2e7fc5cea417a7" args="() const " --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">size_t mrpt::slam::TSetOfMetricMapInitializers::size </td> <td>(</td> <td class="paramname"> )</td> <td> const<code> [inline]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Definition at line <a class="el" href="_c_multi_metric_map_8h_source.html#l00423">423</a> of file <a class="el" href="_c_multi_metric_map_8h_source.html">CMultiMetricMap.h</a>.</p> </div> </div> <hr/><h2>Member Data Documentation</h2> <a class="anchor" id="a3b348c4018cd73db5e5539968ee54a05"></a><!-- doxytag: member="mrpt::slam::TSetOfMetricMapInitializers::m_list" ref="a3b348c4018cd73db5e5539968ee54a05" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">std::deque<<a class="el" href="structmrpt_1_1slam_1_1_t_metric_map_initializer.html">TMetricMapInitializer</a>> <a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a3b348c4018cd73db5e5539968ee54a05">mrpt::slam::TSetOfMetricMapInitializers::m_list</a><code> [protected]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Definition at line <a class="el" href="_c_multi_metric_map_8h_source.html#l00420">420</a> of file <a class="el" href="_c_multi_metric_map_8h_source.html">CMultiMetricMap.h</a>.</p> </div> </div> <a class="anchor" id="a9514fdc98b98a7b185b44d17df3d6f82"></a><!-- doxytag: member="mrpt::slam::TSetOfMetricMapInitializers::options" ref="a9514fdc98b98a7b185b44d17df3d6f82" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="structmrpt_1_1slam_1_1_c_multi_metric_map_1_1_t_options.html">CMultiMetricMap::TOptions</a> <a class="el" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html#a9514fdc98b98a7b185b44d17df3d6f82">mrpt::slam::TSetOfMetricMapInitializers::options</a></td> </tr> </table> </div> <div class="memdoc"> <p>This options will be loaded when creating the set of maps in <a class="el" href="classmrpt_1_1slam_1_1_c_multi_metric_map.html" title="This class stores any customizable set of metric maps.">CMultiMetricMap</a> (See <a class="el" href="structmrpt_1_1slam_1_1_c_multi_metric_map_1_1_t_options.html" title="Some options for this class:">CMultiMetricMap::TOptions</a>) </p> <p>Definition at line <a class="el" href="_c_multi_metric_map_8h_source.html#l00444">444</a> of file <a class="el" href="_c_multi_metric_map_8h_source.html">CMultiMetricMap.h</a>.</p> </div> </div> </div> <br><hr><br> <table border="0" width="100%"> <tr> <td> Page generated by <a href="http://www.doxygen.org" target="_blank">Doxygen 1.7.2</a> for MRPT 0.9.4 SVN: at Mon Jan 10 22:30:30 UTC 2011</td><td></td> <td width="100"> </td> <td width="150"> </td></tr> </table> </body></html>