<!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::CMultiMetricMapPDF::TPredictionParams Struct 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.6.2-20100208 --> <script type="text/javascript"><!-- var searchBox = new SearchBox("searchBox", "search",false,'Search'); --></script> <div class="navigation" id="top"> <div class="tabs"> <ul> <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="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> <div id="MSearchBox" class="MSearchBoxInactive"> <img id="MSearchSelect" src="search/search.png" onmouseover="return searchBox.OnSearchSelectShow()" onmouseout="return searchBox.OnSearchSelectHide()" alt=""/> <input type="text" id="MSearchField" value="Search" accesskey="S" onfocus="searchBox.OnSearchFieldFocus(true)" onblur="searchBox.OnSearchFieldFocus(false)" onkeyup="searchBox.OnSearchFieldChange(event)"/> <a id="MSearchClose" href="javascript:searchBox.CloseResultsWindow()"><img id="MSearchCloseImg" border="0" src="search/close.png" alt=""/></a> </div> </li> </ul> </div> <div class="tabs"> <ul> <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"><a class="el" href="namespacemrpt.html">mrpt</a>::<a class="el" href="namespacemrpt_1_1slam.html">slam</a>::<a class="el" href="classmrpt_1_1slam_1_1_c_multi_metric_map_p_d_f.html">CMultiMetricMapPDF</a>::<a class="el" href="structmrpt_1_1slam_1_1_c_multi_metric_map_p_d_f_1_1_t_prediction_params.html">TPredictionParams</a> </div> </div> <div class="contents"> <h1>mrpt::slam::CMultiMetricMapPDF::TPredictionParams Struct Reference</h1><!-- doxytag: class="mrpt::slam::CMultiMetricMapPDF::TPredictionParams" --><!-- doxytag: inherits="mrpt::utils::CLoadableOptions" --> <p>The struct for passing extra simulation parameters to the prediction/update stage when running a particle filter. <a href="#_details">More...</a></p> <p><code>#include <<a class="el" href="_c_multi_metric_map_p_d_f_8h_source.html">mrpt/slam/CMultiMetricMapPDF.h</a>></code></p> <div class="dynheader"> Inheritance diagram for mrpt::slam::CMultiMetricMapPDF::TPredictionParams:</div> <div class="dynsection"> <div class="center"><img src="structmrpt_1_1slam_1_1_c_multi_metric_map_p_d_f_1_1_t_prediction_params__inherit__graph.png" border="0" usemap="#mrpt_1_1slam_1_1_c_multi_metric_map_p_d_f_1_1_t_prediction_params_inherit__map" alt="Inheritance graph"/></div> <map name="mrpt_1_1slam_1_1_c_multi_metric_map_p_d_f_1_1_t_prediction_params_inherit__map" id="mrpt_1_1slam_1_1_c_multi_metric_map_p_d_f_1_1_t_prediction_params_inherit__map"> <area shape="rect" id="node2" 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..." alt="" coords="76,5,271,35"/></map> <center><span class="legend">[<a href="graph_legend.html">legend</a>]</span></center></div> <div class="dynheader"> Collaboration diagram for mrpt::slam::CMultiMetricMapPDF::TPredictionParams:</div> <div class="dynsection"> <div class="center"><img src="structmrpt_1_1slam_1_1_c_multi_metric_map_p_d_f_1_1_t_prediction_params__coll__graph.png" border="0" usemap="#mrpt_1_1slam_1_1_c_multi_metric_map_p_d_f_1_1_t_prediction_params_coll__map" alt="Collaboration graph"/></div> <map name="mrpt_1_1slam_1_1_c_multi_metric_map_p_d_f_1_1_t_prediction_params_coll__map" id="mrpt_1_1slam_1_1_c_multi_metric_map_p_d_f_1_1_t_prediction_params_coll__map"> <area shape="rect" id="node2" 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..." alt="" coords="5,75,200,104"/><area shape="rect" id="node4" href="classmrpt_1_1slam_1_1_c_i_c_p_1_1_t_config_params.html" title="The ICP algorithm configuration data." alt="" coords="399,109,623,139"/><area shape="rect" id="node7" href="classmrpt_1_1slam_1_1_c_occupancy_grid_map2_d_1_1_t_likelihood_options.html" title="With this struct options are provided to the observation likelihood computation process..." alt="" coords="335,163,687,192"/><area shape="rect" id="node12" href="classmrpt_1_1slam_1_1_t_k_l_d_params.html" title="Option set for KLD algorithm." alt="" coords="425,5,596,35"/></map> <center><span class="legend">[<a href="graph_legend.html">legend</a>]</span></center></div> <p><a href="structmrpt_1_1slam_1_1_c_multi_metric_map_p_d_f_1_1_t_prediction_params-members.html">List of all members.</a></p> <table border="0" cellpadding="0" cellspacing="0"> <tr><td colspan="2"><h2>Public Member Functions</h2></td></tr> <tr><td class="memItemLeft" align="right" valign="top"> </td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1slam_1_1_c_multi_metric_map_p_d_f_1_1_t_prediction_params.html#aa132be2517f82a14c521c95dd5bd6e3d">TPredictionParams</a> ()</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Default settings method. <a href="#aa132be2517f82a14c521c95dd5bd6e3d"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">void </td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1slam_1_1_c_multi_metric_map_p_d_f_1_1_t_prediction_params.html#a882f0d24b30d9e5c10e64c47e39a03c0">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 &section)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">See <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...">utils::CLoadableOptions</a>. <a href="#a882f0d24b30d9e5c10e64c47e39a03c0"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">void </td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1slam_1_1_c_multi_metric_map_p_d_f_1_1_t_prediction_params.html#a4a4f7a0dd8eb956bae088ec0e2ad264e">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">See <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...">utils::CLoadableOptions</a>. <a href="#a4a4f7a0dd8eb956bae088ec0e2ad264e"></a><br/></td></tr> <tr><td colspan="2"><h2>Public Attributes</h2></td></tr> <tr><td class="memItemLeft" align="right" valign="top">int </td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1slam_1_1_c_multi_metric_map_p_d_f_1_1_t_prediction_params.html#a13284bda04d15caab4e40fc52121c216">pfOptimalProposal_mapSelection</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">[pf optimal proposal only] Only for PF algorithm=2 (Exact "pfOptimalProposal") Select the map on which to calculate the optimal proposal distribution. <a href="#a13284bda04d15caab4e40fc52121c216"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">float </td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1slam_1_1_c_multi_metric_map_p_d_f_1_1_t_prediction_params.html#aef437a4d66bf83acba12c1d2d0aa477c">ICPGlobalAlign_MinQuality</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">[prediction stage][pf optimal proposal only] If useICPGlobalAlign_withGrid=true, this is the minimum quality ratio [0,1] of the alignment such as it will be accepted. <a href="#aef437a4d66bf83acba12c1d2d0aa477c"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="classmrpt_1_1slam_1_1_c_occupancy_grid_map2_d_1_1_t_likelihood_options.html">COccupancyGridMap2D::TLikelihoodOptions</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1slam_1_1_c_multi_metric_map_p_d_f_1_1_t_prediction_params.html#a0c3cbf8b7029f4ab53ae10ddb873acce">update_gridMapLikelihoodOptions</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">[update stage] If the likelihood is computed through the occupancy grid map, then this structure is passed to the map when updating the particles weights in the update stage. <a href="#a0c3cbf8b7029f4ab53ae10ddb873acce"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="classmrpt_1_1slam_1_1_t_k_l_d_params.html">TKLDParams</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1slam_1_1_c_multi_metric_map_p_d_f_1_1_t_prediction_params.html#ab3e3a662e5ba7ccdf0553dbb5abd1bb3">KLD_params</a></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p_1_1_t_config_params.html">CICP::TConfigParams</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1slam_1_1_c_multi_metric_map_p_d_f_1_1_t_prediction_params.html#aefbff11417cf3ec52be038276c892dfb">icp_params</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">ICP parameters, used only when "PF_algorithm=2" in the particle filter. <a href="#aefbff11417cf3ec52be038276c892dfb"></a><br/></td></tr> </table> <hr/><a name="_details"></a><h2>Detailed Description</h2> <p>The struct for passing extra simulation parameters to the prediction/update stage when running a particle filter. </p> <dl class="see"><dt><b>See also:</b></dt><dd><a class="el" href="classmrpt_1_1bayes_1_1_c_particle_filter_capable.html#a0b464ec72adbfc8a9aea3cf4aa6bdf9e" title="Performs the prediction stage of the Particle Filter.">prediction_and_update</a> </dd></dl> <p>Definition at line <a class="el" href="_c_multi_metric_map_p_d_f_8h_source.html#l00139">139</a> of file <a class="el" href="_c_multi_metric_map_p_d_f_8h_source.html">CMultiMetricMapPDF.h</a>.</p> <hr/><h2>Constructor & Destructor Documentation</h2> <a class="anchor" id="aa132be2517f82a14c521c95dd5bd6e3d"></a><!-- doxytag: member="mrpt::slam::CMultiMetricMapPDF::TPredictionParams::TPredictionParams" ref="aa132be2517f82a14c521c95dd5bd6e3d" args="()" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">mrpt::slam::CMultiMetricMapPDF::TPredictionParams::TPredictionParams </td> <td>(</td> <td class="paramname"></td> <td> ) </td> <td></td> </tr> </table> </div> <div class="memdoc"> <p>Default settings method. </p> </div> </div> <hr/><h2>Member Function Documentation</h2> <a class="anchor" id="a4a4f7a0dd8eb956bae088ec0e2ad264e"></a><!-- doxytag: member="mrpt::slam::CMultiMetricMapPDF::TPredictionParams::dumpToTextStream" ref="a4a4f7a0dd8eb956bae088ec0e2ad264e" args="(CStream &out) const " --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::CMultiMetricMapPDF::TPredictionParams::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> ) </td> <td> const<code> [virtual]</code></td> </tr> </table> </div> <div class="memdoc"> <p>See <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...">utils::CLoadableOptions</a>. </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="a882f0d24b30d9e5c10e64c47e39a03c0"></a><!-- doxytag: member="mrpt::slam::CMultiMetricMapPDF::TPredictionParams::loadFromConfigFile" ref="a882f0d24b30d9e5c10e64c47e39a03c0" args="(const mrpt::utils::CConfigFileBase &source, const std::string &section)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::CMultiMetricMapPDF::TPredictionParams::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>section</em></td><td> </td> </tr> <tr> <td></td> <td>)</td> <td></td><td></td><td><code> [virtual]</code></td> </tr> </table> </div> <div class="memdoc"> <p>See <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...">utils::CLoadableOptions</a>. </p> <p>Implements <a class="el" href="classmrpt_1_1utils_1_1_c_loadable_options.html#ae2373fce5f2c8d3f0bdad21433becad2">mrpt::utils::CLoadableOptions</a>.</p> </div> </div> <hr/><h2>Member Data Documentation</h2> <a class="anchor" id="aefbff11417cf3ec52be038276c892dfb"></a><!-- doxytag: member="mrpt::slam::CMultiMetricMapPDF::TPredictionParams::icp_params" ref="aefbff11417cf3ec52be038276c892dfb" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p_1_1_t_config_params.html">CICP::TConfigParams</a> <a class="el" href="structmrpt_1_1slam_1_1_c_multi_metric_map_p_d_f_1_1_t_prediction_params.html#aefbff11417cf3ec52be038276c892dfb">mrpt::slam::CMultiMetricMapPDF::TPredictionParams::icp_params</a></td> </tr> </table> </div> <div class="memdoc"> <p>ICP parameters, used only when "PF_algorithm=2" in the particle filter. </p> <p>Definition at line <a class="el" href="_c_multi_metric_map_p_d_f_8h_source.html#l00177">177</a> of file <a class="el" href="_c_multi_metric_map_p_d_f_8h_source.html">CMultiMetricMapPDF.h</a>.</p> </div> </div> <a class="anchor" id="aef437a4d66bf83acba12c1d2d0aa477c"></a><!-- doxytag: member="mrpt::slam::CMultiMetricMapPDF::TPredictionParams::ICPGlobalAlign_MinQuality" ref="aef437a4d66bf83acba12c1d2d0aa477c" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">float <a class="el" href="structmrpt_1_1slam_1_1_c_multi_metric_map_p_d_f_1_1_t_prediction_params.html#aef437a4d66bf83acba12c1d2d0aa477c">mrpt::slam::CMultiMetricMapPDF::TPredictionParams::ICPGlobalAlign_MinQuality</a></td> </tr> </table> </div> <div class="memdoc"> <p>[prediction stage][pf optimal proposal only] If useICPGlobalAlign_withGrid=true, this is the minimum quality ratio [0,1] of the alignment such as it will be accepted. </p> <p>Otherwise, raw odometry is used for those bad cases (default=0.7). </p> <p>Definition at line <a class="el" href="_c_multi_metric_map_p_d_f_8h_source.html#l00169">169</a> of file <a class="el" href="_c_multi_metric_map_p_d_f_8h_source.html">CMultiMetricMapPDF.h</a>.</p> </div> </div> <a class="anchor" id="ab3e3a662e5ba7ccdf0553dbb5abd1bb3"></a><!-- doxytag: member="mrpt::slam::CMultiMetricMapPDF::TPredictionParams::KLD_params" ref="ab3e3a662e5ba7ccdf0553dbb5abd1bb3" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="classmrpt_1_1slam_1_1_t_k_l_d_params.html">TKLDParams</a> <a class="el" href="structmrpt_1_1slam_1_1_c_multi_metric_map_p_d_f_1_1_t_prediction_params.html#ab3e3a662e5ba7ccdf0553dbb5abd1bb3">mrpt::slam::CMultiMetricMapPDF::TPredictionParams::KLD_params</a></td> </tr> </table> </div> <div class="memdoc"> <p>Definition at line <a class="el" href="_c_multi_metric_map_p_d_f_8h_source.html#l00175">175</a> of file <a class="el" href="_c_multi_metric_map_p_d_f_8h_source.html">CMultiMetricMapPDF.h</a>.</p> </div> </div> <a class="anchor" id="a13284bda04d15caab4e40fc52121c216"></a><!-- doxytag: member="mrpt::slam::CMultiMetricMapPDF::TPredictionParams::pfOptimalProposal_mapSelection" ref="a13284bda04d15caab4e40fc52121c216" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">int <a class="el" href="structmrpt_1_1slam_1_1_c_multi_metric_map_p_d_f_1_1_t_prediction_params.html#a13284bda04d15caab4e40fc52121c216">mrpt::slam::CMultiMetricMapPDF::TPredictionParams::pfOptimalProposal_mapSelection</a></td> </tr> </table> </div> <div class="memdoc"> <p>[pf optimal proposal only] Only for PF algorithm=2 (Exact "pfOptimalProposal") Select the map on which to calculate the optimal proposal distribution. </p> <p>Values: 0: Gridmap -> Uses Scan matching-based approximation (based on Stachniss' work) 1: Landmarks -> Uses matching to approximate optimal 2: Beacons -> Used for exact optimal proposal in RO-SLAM 3: Pointsmap -> Uses Scan matching-based approximation with a map of points (based on Stachniss' work) Default = 0 </p> <p>Definition at line <a class="el" href="_c_multi_metric_map_p_d_f_8h_source.html#l00164">164</a> of file <a class="el" href="_c_multi_metric_map_p_d_f_8h_source.html">CMultiMetricMapPDF.h</a>.</p> </div> </div> <a class="anchor" id="a0c3cbf8b7029f4ab53ae10ddb873acce"></a><!-- doxytag: member="mrpt::slam::CMultiMetricMapPDF::TPredictionParams::update_gridMapLikelihoodOptions" ref="a0c3cbf8b7029f4ab53ae10ddb873acce" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="classmrpt_1_1slam_1_1_c_occupancy_grid_map2_d_1_1_t_likelihood_options.html">COccupancyGridMap2D::TLikelihoodOptions</a> <a class="el" href="structmrpt_1_1slam_1_1_c_multi_metric_map_p_d_f_1_1_t_prediction_params.html#a0c3cbf8b7029f4ab53ae10ddb873acce">mrpt::slam::CMultiMetricMapPDF::TPredictionParams::update_gridMapLikelihoodOptions</a></td> </tr> </table> </div> <div class="memdoc"> <p>[update stage] If the likelihood is computed through the occupancy grid map, then this structure is passed to the map when updating the particles weights in the update stage. </p> <p>Definition at line <a class="el" href="_c_multi_metric_map_p_d_f_8h_source.html#l00173">173</a> of file <a class="el" href="_c_multi_metric_map_p_d_f_8h_source.html">CMultiMetricMapPDF.h</a>.</p> </div> </div> </div> <!--- window showing the filter options --> <div id="MSearchSelectWindow" onmouseover="return searchBox.OnSearchSelectShow()" onmouseout="return searchBox.OnSearchSelectHide()" onkeydown="return searchBox.OnSearchSelectKey(event)"> <a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(0)"><span class="SelectionMark"> </span>All</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(1)"><span class="SelectionMark"> </span>Classes</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(2)"><span class="SelectionMark"> </span>Namespaces</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(3)"><span class="SelectionMark"> </span>Files</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(4)"><span class="SelectionMark"> </span>Functions</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(5)"><span class="SelectionMark"> </span>Variables</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(6)"><span class="SelectionMark"> </span>Typedefs</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(7)"><span class="SelectionMark"> </span>Enumerations</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(8)"><span class="SelectionMark"> </span>Enumerator</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(9)"><span class="SelectionMark"> </span>Friends</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(10)"><span class="SelectionMark"> </span>Defines</a></div> <!-- iframe showing the search results (closed by default) --> <div id="MSearchResultsWindow"> <iframe src="" frameborder="0" name="MSearchResults" id="MSearchResults"> </iframe> </div> <br><hr><br> <table border="0" width="100%"> <tr> <td> Page generated by <a href="http://www.doxygen.org" target="_blank">Doxygen 1.6.2-20100208</a> for MRPT 0.9.0 SVN: at Wed Jul 14 12:48:09 UTC 2010</td><td></td> <td width="100"> </td> <td width="150"> </td></tr> </table> </body></html>