<!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>mrpt::slam::CLogOddsGridMap2D 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.7.5 --> <script type="text/javascript"> var searchBox = new SearchBox("searchBox", "search",false,'Search'); </script> <div id="navrow1" 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> <div id="MSearchBox" class="MSearchBoxInactive"> <div 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> </div><div class="right"></div> </div> </li> </ul> </div> <div id="navrow2" 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="inherits.html"><span>Class Hierarchy</span></a></li> <li><a href="functions.html"><span>Class Members</span></a></li> </ul> </div> <div id="nav-path" class="navpath"> <ul> <li class="navelem"><a class="el" href="namespacemrpt.html">mrpt</a> </li> <li class="navelem"><a class="el" href="namespacemrpt_1_1slam.html">slam</a> </li> <li class="navelem"><a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html">CLogOddsGridMap2D</a> </li> </ul> </div> </div> <div class="header"> <div class="summary"> <a href="#pub-types">Public Types</a> | <a href="#pub-static-methods">Static Public Member Functions</a> </div> <div class="headertitle"> <div class="title">mrpt::slam::CLogOddsGridMap2D Struct Reference<div class="ingroups"><a class="el" href="group__mrpt__maps__grp.html">[mrpt-maps]</a></div></div> </div> </div> <div class="contents"> <!-- doxytag: class="mrpt::slam::CLogOddsGridMap2D" --><hr/><a name="details" id="details"></a><h2>Detailed Description</h2> <div class="textblock"><p>A generic provider of log-odds grid-map maintainance functions. </p> <p>Map cells must be type TCELL, which can be only:</p> <ul> <li>int8_t or</li> <li>int16_t</li> </ul> <dl class="see"><dt><b>See also:</b></dt><dd><a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html" title="One static instance of this struct should exist in any class implementing CLogOddsGridMap2D to hold t...">CLogOddsGridMapLUT</a>, See derived classes for usage examples. </dd></dl> </div> <p><code>#include <<a class="el" href="_c_log_odds_grid_map2_d_8h_source.html">mrpt/slam/CLogOddsGridMap2D.h</a>></code></p> <div class="dynheader"> Inheritance diagram for mrpt::slam::CLogOddsGridMap2D:</div> <div class="dyncontent"> <div class="center"><img src="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d__inherit__graph.png" border="0" usemap="#mrpt_1_1slam_1_1_c_log_odds_grid_map2_d_inherit__map" alt="Inheritance graph"/></div> <map name="mrpt_1_1slam_1_1_c_log_odds_grid_map2_d_inherit__map" id="mrpt_1_1slam_1_1_c_log_odds_grid_map2_d_inherit__map"> <area shape="rect" id="node3" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html" title="mrpt::slam::CLogOddsGridMap2D\< int8_t \>" alt="" coords="5,96,280,123"/><area shape="rect" id="node7" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html" title="mrpt::slam::CLogOddsGridMap2D\< int16_t \>" alt="" coords="305,96,587,123"/><area shape="rect" id="node5" href="classmrpt_1_1slam_1_1_c_reflectivity_grid_map2_d.html" title="A 2D grid map representing the reflectivity of the environment (for example, measured with an IR prox..." alt="" coords="25,173,259,200"/><area shape="rect" id="node9" href="classmrpt_1_1slam_1_1_c_occupancy_grid_map2_d.html" title="A class for storing an occupancy grid map." alt="" coords="329,173,563,200"/></map> <center><span class="legend">[<a href="graph_legend.html">legend</a>]</span></center></div> <p><a href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d-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 TCELL </td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">cell_t</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">The type of cells. <a href="#a303720ae1a3a6e0dd66a6f5000563c31"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">typedef <br class="typebreak"/> detail::logoddscell_traits<br class="typebreak"/> < TCELL > </td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a3b3f3dea9c21f268423707ebb8133073">traits_t</a></td></tr> <tr><td colspan="2"><h2><a name="pub-static-methods"></a> Static Public Member Functions</h2></td></tr> <tr><td class="memItemLeft" align="right" valign="top">static void </td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#aacbad0750e1daee9c87ed58554e3a5a1">updateCell_fast_occupied</a> (const unsigned x, const unsigned y, const <a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">cell_t</a> logodd_obs, const <a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">cell_t</a> thres, <a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">cell_t</a> *mapArray, const unsigned _size_x)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Performs the Bayesian fusion of a new observation of a cell, without checking for grid limits nor updateInfoChangeOnly. <a href="#aacbad0750e1daee9c87ed58554e3a5a1"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">static void </td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a691e592dbefe70ea33969acf2821b9c6">updateCell_fast_occupied</a> (<a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">cell_t</a> *theCell, const <a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">cell_t</a> logodd_obs, const <a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">cell_t</a> thres)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Performs the Bayesian fusion of a new observation of a cell, without checking for grid limits nor updateInfoChangeOnly. <a href="#a691e592dbefe70ea33969acf2821b9c6"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">static void </td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a7921809b8a25ce16cdfd230193f88909">updateCell_fast_free</a> (const unsigned x, const unsigned y, const <a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">cell_t</a> logodd_obs, const <a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">cell_t</a> thres, <a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">cell_t</a> *mapArray, const unsigned _size_x)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Performs the Bayesian fusion of a new observation of a cell, without checking for grid limits nor updateInfoChangeOnly. <a href="#a7921809b8a25ce16cdfd230193f88909"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">static void </td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a25e9bc67e0e81242ee3359d8155a2e02">updateCell_fast_free</a> (<a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">cell_t</a> *theCell, const <a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">cell_t</a> logodd_obs, const <a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">cell_t</a> thres)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Performs the Bayesian fusion of a new observation of a cell, without checking for grid limits nor updateInfoChangeOnly. <a href="#a25e9bc67e0e81242ee3359d8155a2e02"></a><br/></td></tr> </table> <hr/><h2>Member Typedef Documentation</h2> <a class="anchor" id="a303720ae1a3a6e0dd66a6f5000563c31"></a><!-- doxytag: member="mrpt::slam::CLogOddsGridMap2D::cell_t" ref="a303720ae1a3a6e0dd66a6f5000563c31" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">typedef TCELL <a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">mrpt::slam::CLogOddsGridMap2D::cell_t</a></td> </tr> </table> </div> <div class="memdoc"> <p>The type of cells. </p> <p>Definition at line <a class="el" href="_c_log_odds_grid_map2_d_8h_source.html#l00069">69</a> of file <a class="el" href="_c_log_odds_grid_map2_d_8h_source.html">CLogOddsGridMap2D.h</a>.</p> </div> </div> <a class="anchor" id="a3b3f3dea9c21f268423707ebb8133073"></a><!-- doxytag: member="mrpt::slam::CLogOddsGridMap2D::traits_t" ref="a3b3f3dea9c21f268423707ebb8133073" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">typedef detail::logoddscell_traits<TCELL> <a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a3b3f3dea9c21f268423707ebb8133073">mrpt::slam::CLogOddsGridMap2D::traits_t</a></td> </tr> </table> </div> <div class="memdoc"> <p>Definition at line <a class="el" href="_c_log_odds_grid_map2_d_8h_source.html#l00070">70</a> of file <a class="el" href="_c_log_odds_grid_map2_d_8h_source.html">CLogOddsGridMap2D.h</a>.</p> </div> </div> <hr/><h2>Member Function Documentation</h2> <a class="anchor" id="a7921809b8a25ce16cdfd230193f88909"></a><!-- doxytag: member="mrpt::slam::CLogOddsGridMap2D::updateCell_fast_free" ref="a7921809b8a25ce16cdfd230193f88909" args="(const unsigned x, const unsigned y, const cell_t logodd_obs, const cell_t thres, cell_t *mapArray, const unsigned _size_x)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">static void mrpt::slam::CLogOddsGridMap2D::updateCell_fast_free </td> <td>(</td> <td class="paramtype">const unsigned </td> <td class="paramname"><em>x</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const unsigned </td> <td class="paramname"><em>y</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">cell_t</a> </td> <td class="paramname"><em>logodd_obs</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">cell_t</a> </td> <td class="paramname"><em>thres</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype"><a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">cell_t</a> * </td> <td class="paramname"><em>mapArray</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const unsigned </td> <td class="paramname"><em>_size_x</em> </td> </tr> <tr> <td></td> <td>)</td> <td></td><td><code> [inline, static]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Performs the Bayesian fusion of a new observation of a cell, without checking for grid limits nor updateInfoChangeOnly. </p> <p>This method increases the "free-ness" of a cell, managing possible saturation. </p> <dl><dt><b>Parameters:</b></dt><dd> <table class="params"> <tr><td class="paramname">x</td><td>Cell index in X axis. </td></tr> <tr><td class="paramname">y</td><td>Cell index in Y axis. </td></tr> <tr><td class="paramname">logodd_obs</td><td>Observation of the cell, in log-odd form as transformed by p2l. </td></tr> <tr><td class="paramname">thres</td><td>This must be CELLTYPE_MAX-logodd_obs </td></tr> </table> </dd> </dl> <dl class="see"><dt><b>See also:</b></dt><dd><a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#aacbad0750e1daee9c87ed58554e3a5a1" title="Performs the Bayesian fusion of a new observation of a cell, without checking for grid limits nor upd...">updateCell_fast_occupied</a> </dd></dl> <p>Definition at line <a class="el" href="_c_log_odds_grid_map2_d_8h_source.html#l00119">119</a> of file <a class="el" href="_c_log_odds_grid_map2_d_8h_source.html">CLogOddsGridMap2D.h</a>.</p> </div> </div> <a class="anchor" id="a25e9bc67e0e81242ee3359d8155a2e02"></a><!-- doxytag: member="mrpt::slam::CLogOddsGridMap2D::updateCell_fast_free" ref="a25e9bc67e0e81242ee3359d8155a2e02" args="(cell_t *theCell, const cell_t logodd_obs, const cell_t thres)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">static void mrpt::slam::CLogOddsGridMap2D::updateCell_fast_free </td> <td>(</td> <td class="paramtype"><a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">cell_t</a> * </td> <td class="paramname"><em>theCell</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">cell_t</a> </td> <td class="paramname"><em>logodd_obs</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">cell_t</a> </td> <td class="paramname"><em>thres</em> </td> </tr> <tr> <td></td> <td>)</td> <td></td><td><code> [inline, static]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Performs the Bayesian fusion of a new observation of a cell, without checking for grid limits nor updateInfoChangeOnly. </p> <p>This method increases the "free-ness" of a cell, managing possible saturation. </p> <dl><dt><b>Parameters:</b></dt><dd> <table class="params"> <tr><td class="paramname">x</td><td>Cell index in X axis. </td></tr> <tr><td class="paramname">y</td><td>Cell index in Y axis. </td></tr> <tr><td class="paramname">logodd_obs</td><td>Observation of the cell, in log-odd form as transformed by p2l. </td></tr> <tr><td class="paramname">thres</td><td>This must be CELLTYPE_MAX-logodd_obs </td></tr> </table> </dd> </dl> <dl class="see"><dt><b>See also:</b></dt><dd><a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#aacbad0750e1daee9c87ed58554e3a5a1" title="Performs the Bayesian fusion of a new observation of a cell, without checking for grid limits nor upd...">updateCell_fast_occupied</a> </dd></dl> <p>Definition at line <a class="el" href="_c_log_odds_grid_map2_d_8h_source.html#l00141">141</a> of file <a class="el" href="_c_log_odds_grid_map2_d_8h_source.html">CLogOddsGridMap2D.h</a>.</p> </div> </div> <a class="anchor" id="aacbad0750e1daee9c87ed58554e3a5a1"></a><!-- doxytag: member="mrpt::slam::CLogOddsGridMap2D::updateCell_fast_occupied" ref="aacbad0750e1daee9c87ed58554e3a5a1" args="(const unsigned x, const unsigned y, const cell_t logodd_obs, const cell_t thres, cell_t *mapArray, const unsigned _size_x)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">static void mrpt::slam::CLogOddsGridMap2D::updateCell_fast_occupied </td> <td>(</td> <td class="paramtype">const unsigned </td> <td class="paramname"><em>x</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const unsigned </td> <td class="paramname"><em>y</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">cell_t</a> </td> <td class="paramname"><em>logodd_obs</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">cell_t</a> </td> <td class="paramname"><em>thres</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype"><a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">cell_t</a> * </td> <td class="paramname"><em>mapArray</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const unsigned </td> <td class="paramname"><em>_size_x</em> </td> </tr> <tr> <td></td> <td>)</td> <td></td><td><code> [inline, static]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Performs the Bayesian fusion of a new observation of a cell, without checking for grid limits nor updateInfoChangeOnly. </p> <p>This method increases the "occupancy-ness" of a cell, managing possible saturation. </p> <dl><dt><b>Parameters:</b></dt><dd> <table class="params"> <tr><td class="paramname">x</td><td>Cell index in X axis. </td></tr> <tr><td class="paramname">y</td><td>Cell index in Y axis. </td></tr> <tr><td class="paramname">logodd_obs</td><td>Observation of the cell, in log-odd form as transformed by p2l. </td></tr> <tr><td class="paramname">thres</td><td>This must be CELLTYPE_MIN+logodd_obs </td></tr> </table> </dd> </dl> <dl class="see"><dt><b>See also:</b></dt><dd>updateCell, <a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a7921809b8a25ce16cdfd230193f88909" title="Performs the Bayesian fusion of a new observation of a cell, without checking for grid limits nor upd...">updateCell_fast_free</a> </dd></dl> <p>Definition at line <a class="el" href="_c_log_odds_grid_map2_d_8h_source.html#l00080">80</a> of file <a class="el" href="_c_log_odds_grid_map2_d_8h_source.html">CLogOddsGridMap2D.h</a>.</p> </div> </div> <a class="anchor" id="a691e592dbefe70ea33969acf2821b9c6"></a><!-- doxytag: member="mrpt::slam::CLogOddsGridMap2D::updateCell_fast_occupied" ref="a691e592dbefe70ea33969acf2821b9c6" args="(cell_t *theCell, const cell_t logodd_obs, const cell_t thres)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">static void mrpt::slam::CLogOddsGridMap2D::updateCell_fast_occupied </td> <td>(</td> <td class="paramtype"><a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">cell_t</a> * </td> <td class="paramname"><em>theCell</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">cell_t</a> </td> <td class="paramname"><em>logodd_obs</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">cell_t</a> </td> <td class="paramname"><em>thres</em> </td> </tr> <tr> <td></td> <td>)</td> <td></td><td><code> [inline, static]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Performs the Bayesian fusion of a new observation of a cell, without checking for grid limits nor updateInfoChangeOnly. </p> <p>This method increases the "occupancy-ness" of a cell, managing possible saturation. </p> <dl><dt><b>Parameters:</b></dt><dd> <table class="params"> <tr><td class="paramname">theCell</td><td>The cell to modify </td></tr> <tr><td class="paramname">logodd_obs</td><td>Observation of the cell, in log-odd form as transformed by p2l. </td></tr> <tr><td class="paramname">thres</td><td>This must be CELLTYPE_MIN+logodd_obs </td></tr> </table> </dd> </dl> <dl class="see"><dt><b>See also:</b></dt><dd>updateCell, <a class="el" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a7921809b8a25ce16cdfd230193f88909" title="Performs the Bayesian fusion of a new observation of a cell, without checking for grid limits nor upd...">updateCell_fast_free</a> </dd></dl> <p>Definition at line <a class="el" href="_c_log_odds_grid_map2_d_8h_source.html#l00101">101</a> of file <a class="el" href="_c_log_odds_grid_map2_d_8h_source.html">CLogOddsGridMap2D.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.5</a> for MRPT 0.9.5 SVN: at Sun Sep 25 17:20:18 UTC 2011</td><td></td> <td width="100"> </td> <td width="150"> </td></tr> </table> </body></html>