<!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>CLogOddsGridMap2D.h Source File</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><a href="annotated.html"><span>Classes</span></a></li> <li class="current"><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="files.html"><span>File List</span></a></li> <li><a href="globals.html"><span>File Members</span></a></li> </ul> </div> <div class="header"> <div class="headertitle"> <div class="title">CLogOddsGridMap2D.h</div> </div> </div> <div class="contents"> <a href="_c_log_odds_grid_map2_d_8h.html">Go to the documentation of this file.</a><div class="fragment"><pre class="fragment"><a name="l00001"></a>00001 <span class="comment">/* +---------------------------------------------------------------------------+</span> <a name="l00002"></a>00002 <span class="comment"> | The Mobile Robot Programming Toolkit (MRPT) C++ library |</span> <a name="l00003"></a>00003 <span class="comment"> | |</span> <a name="l00004"></a>00004 <span class="comment"> | http://www.mrpt.org/ |</span> <a name="l00005"></a>00005 <span class="comment"> | |</span> <a name="l00006"></a>00006 <span class="comment"> | Copyright (C) 2005-2011 University of Malaga |</span> <a name="l00007"></a>00007 <span class="comment"> | |</span> <a name="l00008"></a>00008 <span class="comment"> | This software was written by the Machine Perception and Intelligent |</span> <a name="l00009"></a>00009 <span class="comment"> | Robotics Lab, University of Malaga (Spain). |</span> <a name="l00010"></a>00010 <span class="comment"> | Contact: Jose-Luis Blanco <jlblanco@ctima.uma.es> |</span> <a name="l00011"></a>00011 <span class="comment"> | |</span> <a name="l00012"></a>00012 <span class="comment"> | This file is part of the MRPT project. |</span> <a name="l00013"></a>00013 <span class="comment"> | |</span> <a name="l00014"></a>00014 <span class="comment"> | MRPT is free software: you can redistribute it and/or modify |</span> <a name="l00015"></a>00015 <span class="comment"> | it under the terms of the GNU General Public License as published by |</span> <a name="l00016"></a>00016 <span class="comment"> | the Free Software Foundation, either version 3 of the License, or |</span> <a name="l00017"></a>00017 <span class="comment"> | (at your option) any later version. |</span> <a name="l00018"></a>00018 <span class="comment"> | |</span> <a name="l00019"></a>00019 <span class="comment"> | MRPT is distributed in the hope that it will be useful, |</span> <a name="l00020"></a>00020 <span class="comment"> | but WITHOUT ANY WARRANTY; without even the implied warranty of |</span> <a name="l00021"></a>00021 <span class="comment"> | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the |</span> <a name="l00022"></a>00022 <span class="comment"> | GNU General Public License for more details. |</span> <a name="l00023"></a>00023 <span class="comment"> | |</span> <a name="l00024"></a>00024 <span class="comment"> | You should have received a copy of the GNU General Public License |</span> <a name="l00025"></a>00025 <span class="comment"> | along with MRPT. If not, see <http://www.gnu.org/licenses/>. |</span> <a name="l00026"></a>00026 <span class="comment"> | |</span> <a name="l00027"></a>00027 <span class="comment"> +---------------------------------------------------------------------------+ */</span> <a name="l00028"></a>00028 <a name="l00029"></a>00029 <span class="preprocessor">#ifndef CLogOddsGridMap2D_H</span> <a name="l00030"></a>00030 <span class="preprocessor"></span><span class="preprocessor">#define CLogOddsGridMap2D_H</span> <a name="l00031"></a>00031 <span class="preprocessor"></span> <a name="l00032"></a>00032 <span class="preprocessor">#include <<a class="code" href="utils__defs_8h.html">mrpt/utils/utils_defs.h</a>></span> <a name="l00033"></a>00033 <a name="l00034"></a>00034 <span class="keyword">namespace </span>mrpt <a name="l00035"></a>00035 { <a name="l00036"></a>00036 <span class="keyword">namespace </span>slam <a name="l00037"></a>00037 { <a name="l00038"></a><a class="code" href="namespacemrpt_1_1slam_1_1detail.html">00038</a> <span class="keyword">namespace </span>detail <a name="l00039"></a>00039 { <a name="l00040"></a>00040 <span class="keyword">template</span> <<span class="keyword">typename</span> TCELL> <span class="keyword">struct </span>logoddscell_traits; <a name="l00041"></a>00041 <span class="comment">// Specializations:</span> <a name="l00042"></a>00042 <span class="keyword">template</span> <> <span class="keyword">struct </span>logoddscell_traits<int8_t> <a name="l00043"></a>00043 { <a name="l00044"></a><a class="code" href="structmrpt_1_1slam_1_1detail_1_1logoddscell__traits_3_01int8__t_01_4.html#a273e310bdf4055130b13697a6a1b8810">00044</a> <span class="keyword">static</span> <span class="keyword">const</span> int8_t CELLTYPE_MIN = -127; <span class="comment">// In mrpt <0.9.4 was -128 (!) - This is to make it compatible with all architectures.</span> <a name="l00045"></a><a class="code" href="structmrpt_1_1slam_1_1detail_1_1logoddscell__traits_3_01int8__t_01_4.html#afef0f3d598009646484ec6192f882b03">00045</a> <span class="keyword">static</span> <span class="keyword">const</span> int8_t CELLTYPE_MAX = 127; <a name="l00046"></a><a class="code" href="structmrpt_1_1slam_1_1detail_1_1logoddscell__traits_3_01int8__t_01_4.html#ab3c823ce3d8a7b15d7f4557ccf819cb7">00046</a> <span class="keyword">static</span> <span class="keyword">const</span> int8_t P2LTABLE_SIZE = CELLTYPE_MAX; <a name="l00047"></a><a class="code" href="structmrpt_1_1slam_1_1detail_1_1logoddscell__traits_3_01int8__t_01_4.html#ae4555ff3e5ba93479eec0e4604dd476a">00047</a> <span class="keyword">static</span> <span class="keyword">const</span> <span class="keywordtype">size_t</span> LOGODDS_LUT_ENTRIES = 1<<8; <a name="l00048"></a>00048 }; <a name="l00049"></a>00049 <span class="keyword">template</span> <> <span class="keyword">struct </span>logoddscell_traits<int16_t> <a name="l00050"></a>00050 { <a name="l00051"></a><a class="code" href="structmrpt_1_1slam_1_1detail_1_1logoddscell__traits_3_01int16__t_01_4.html#acbb137b12bed052aa7727741e641adff">00051</a> <span class="keyword">static</span> <span class="keyword">const</span> int16_t CELLTYPE_MIN = -32767; <span class="comment">// In mrpt <0.9.4 was -32768 (!).</span> <a name="l00052"></a><a class="code" href="structmrpt_1_1slam_1_1detail_1_1logoddscell__traits_3_01int16__t_01_4.html#a5b630484f04f81f48169f102900dede5">00052</a> <span class="keyword">static</span> <span class="keyword">const</span> int16_t CELLTYPE_MAX = 32767; <a name="l00053"></a><a class="code" href="structmrpt_1_1slam_1_1detail_1_1logoddscell__traits_3_01int16__t_01_4.html#ab5083aebd6a955903b15619d114d1905">00053</a> <span class="keyword">static</span> <span class="keyword">const</span> int16_t P2LTABLE_SIZE = CELLTYPE_MAX; <a name="l00054"></a><a class="code" href="structmrpt_1_1slam_1_1detail_1_1logoddscell__traits_3_01int16__t_01_4.html#a18a29a3802347cf9f8760aa0ff1a8af6">00054</a> <span class="keyword">static</span> <span class="keyword">const</span> <span class="keywordtype">size_t</span> LOGODDS_LUT_ENTRIES = 1<<16; <a name="l00055"></a>00055 }; <a name="l00056"></a>00056 } <a name="l00057"></a>00057 <span class="comment"></span> <a name="l00058"></a>00058 <span class="comment"> /** A generic provider of log-odds grid-map maintainance functions.</span> <a name="l00059"></a>00059 <span class="comment"> * Map cells must be type TCELL, which can be only:</span> <a name="l00060"></a>00060 <span class="comment"> * - int8_t or</span> <a name="l00061"></a>00061 <span class="comment"> * - int16_t</span> <a name="l00062"></a>00062 <span class="comment"> *</span> <a name="l00063"></a>00063 <span class="comment"> * \sa CLogOddsGridMapLUT, See derived classes for usage examples.</span> <a name="l00064"></a>00064 <span class="comment"> * \ingroup mrpt_maps_grp</span> <a name="l00065"></a>00065 <span class="comment"> */</span> <a name="l00066"></a>00066 <span class="keyword">template</span> <<span class="keyword">typename</span> TCELL> <a name="l00067"></a>00067 <span class="keyword">struct </span><a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html" title="A generic provider of log-odds grid-map maintainance functions.">CLogOddsGridMap2D</a> : <span class="keyword">public</span> detail::logoddscell_traits<TCELL> <a name="l00068"></a>00068 { <a name="l00069"></a><a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31">00069</a> <span class="keyword">typedef</span> TCELL <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31" title="The type of cells.">cell_t</a>; <span class="comment">//!< The type of cells</span> <a name="l00070"></a><a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a3b3f3dea9c21f268423707ebb8133073">00070</a> <span class="comment"></span> <span class="keyword">typedef</span> detail::logoddscell_traits<TCELL> <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a3b3f3dea9c21f268423707ebb8133073">traits_t</a>; <a name="l00071"></a>00071 <span class="comment"></span> <a name="l00072"></a>00072 <span class="comment"> /** Performs the Bayesian fusion of a new observation of a cell, without checking for grid limits nor updateInfoChangeOnly.</span> <a name="l00073"></a>00073 <span class="comment"> * This method increases the "occupancy-ness" of a cell, managing possible saturation.</span> <a name="l00074"></a>00074 <span class="comment"> * \param x Cell index in X axis.</span> <a name="l00075"></a>00075 <span class="comment"> * \param y Cell index in Y axis.</span> <a name="l00076"></a>00076 <span class="comment"> * \param logodd_obs Observation of the cell, in log-odd form as transformed by p2l.</span> <a name="l00077"></a>00077 <span class="comment"> * \param thres This must be CELLTYPE_MIN+logodd_obs</span> <a name="l00078"></a>00078 <span class="comment"> * \sa updateCell, updateCell_fast_free</span> <a name="l00079"></a>00079 <span class="comment"> */</span> <a name="l00080"></a><a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#aacbad0750e1daee9c87ed58554e3a5a1">00080</a> <span class="keyword">inline</span> <span class="keyword">static</span> <span class="keywordtype">void</span> <a class="code" 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>( <a name="l00081"></a>00081 <span class="keyword">const</span> <span class="keywordtype">unsigned</span> x, <a name="l00082"></a>00082 <span class="keyword">const</span> <span class="keywordtype">unsigned</span> <a class="code" href="namespace_eigen_1_1internal.html#a3d7a581aeb951248dc6fe114e9e05f07">y</a>, <a name="l00083"></a>00083 <span class="keyword">const</span> <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31" title="The type of cells.">cell_t</a> logodd_obs, <a name="l00084"></a>00084 <span class="keyword">const</span> <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31" title="The type of cells.">cell_t</a> thres, <a name="l00085"></a>00085 <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31" title="The type of cells.">cell_t</a> *mapArray, <a name="l00086"></a>00086 <span class="keyword">const</span> <span class="keywordtype">unsigned</span> _size_x) <a name="l00087"></a>00087 { <a name="l00088"></a>00088 <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31" title="The type of cells.">cell_t</a> *theCell = mapArray + (x+y*_size_x); <a name="l00089"></a>00089 <span class="keywordflow">if</span> (*theCell > thres ) <a name="l00090"></a>00090 *theCell -= logodd_obs; <a name="l00091"></a>00091 <span class="keywordflow">else</span> *theCell = <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a3b3f3dea9c21f268423707ebb8133073">traits_t</a>::CELLTYPE_MIN; <a name="l00092"></a>00092 } <a name="l00093"></a>00093 <span class="comment"></span> <a name="l00094"></a>00094 <span class="comment"> /** Performs the Bayesian fusion of a new observation of a cell, without checking for grid limits nor updateInfoChangeOnly.</span> <a name="l00095"></a>00095 <span class="comment"> * This method increases the "occupancy-ness" of a cell, managing possible saturation.</span> <a name="l00096"></a>00096 <span class="comment"> * \param theCell The cell to modify</span> <a name="l00097"></a>00097 <span class="comment"> * \param logodd_obs Observation of the cell, in log-odd form as transformed by p2l.</span> <a name="l00098"></a>00098 <span class="comment"> * \param thres This must be CELLTYPE_MIN+logodd_obs</span> <a name="l00099"></a>00099 <span class="comment"> * \sa updateCell, updateCell_fast_free</span> <a name="l00100"></a>00100 <span class="comment"> */</span> <a name="l00101"></a><a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a691e592dbefe70ea33969acf2821b9c6">00101</a> <span class="keyword">inline</span> <span class="keyword">static</span> <span class="keywordtype">void</span> <a class="code" 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>( <a name="l00102"></a>00102 <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31" title="The type of cells.">cell_t</a> *theCell, <a name="l00103"></a>00103 <span class="keyword">const</span> <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31" title="The type of cells.">cell_t</a> logodd_obs, <a name="l00104"></a>00104 <span class="keyword">const</span> <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31" title="The type of cells.">cell_t</a> thres ) <a name="l00105"></a>00105 { <a name="l00106"></a>00106 <span class="keywordflow">if</span> (*theCell > thres ) <a name="l00107"></a>00107 *theCell -= logodd_obs; <a name="l00108"></a>00108 <span class="keywordflow">else</span> *theCell = <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a3b3f3dea9c21f268423707ebb8133073">traits_t</a>::CELLTYPE_MIN; <a name="l00109"></a>00109 } <a name="l00110"></a>00110 <span class="comment"></span> <a name="l00111"></a>00111 <span class="comment"> /** Performs the Bayesian fusion of a new observation of a cell, without checking for grid limits nor updateInfoChangeOnly.</span> <a name="l00112"></a>00112 <span class="comment"> * This method increases the "free-ness" of a cell, managing possible saturation.</span> <a name="l00113"></a>00113 <span class="comment"> * \param x Cell index in X axis.</span> <a name="l00114"></a>00114 <span class="comment"> * \param y Cell index in Y axis.</span> <a name="l00115"></a>00115 <span class="comment"> * \param logodd_obs Observation of the cell, in log-odd form as transformed by p2l.</span> <a name="l00116"></a>00116 <span class="comment"> * \param thres This must be CELLTYPE_MAX-logodd_obs</span> <a name="l00117"></a>00117 <span class="comment"> * \sa updateCell_fast_occupied</span> <a name="l00118"></a>00118 <span class="comment"> */</span> <a name="l00119"></a><a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a7921809b8a25ce16cdfd230193f88909">00119</a> <span class="keyword">inline</span> <span class="keyword">static</span> <span class="keywordtype">void</span> <a class="code" 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>( <a name="l00120"></a>00120 <span class="keyword">const</span> <span class="keywordtype">unsigned</span> x, <a name="l00121"></a>00121 <span class="keyword">const</span> <span class="keywordtype">unsigned</span> <a class="code" href="namespace_eigen_1_1internal.html#a3d7a581aeb951248dc6fe114e9e05f07">y</a>, <a name="l00122"></a>00122 <span class="keyword">const</span> <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31" title="The type of cells.">cell_t</a> logodd_obs, <a name="l00123"></a>00123 <span class="keyword">const</span> <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31" title="The type of cells.">cell_t</a> thres, <a name="l00124"></a>00124 <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31" title="The type of cells.">cell_t</a> *mapArray, <a name="l00125"></a>00125 <span class="keyword">const</span> <span class="keywordtype">unsigned</span> _size_x) <a name="l00126"></a>00126 { <a name="l00127"></a>00127 <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31" title="The type of cells.">cell_t</a> *theCell = mapArray + (x+y*_size_x); <a name="l00128"></a>00128 <span class="keywordflow">if</span> (*theCell < thres ) <a name="l00129"></a>00129 *theCell += logodd_obs; <a name="l00130"></a>00130 <span class="keywordflow">else</span> *theCell = <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a3b3f3dea9c21f268423707ebb8133073">traits_t</a>::CELLTYPE_MAX; <a name="l00131"></a>00131 } <a name="l00132"></a>00132 <span class="comment"></span> <a name="l00133"></a>00133 <span class="comment"> /** Performs the Bayesian fusion of a new observation of a cell, without checking for grid limits nor updateInfoChangeOnly.</span> <a name="l00134"></a>00134 <span class="comment"> * This method increases the "free-ness" of a cell, managing possible saturation.</span> <a name="l00135"></a>00135 <span class="comment"> * \param x Cell index in X axis.</span> <a name="l00136"></a>00136 <span class="comment"> * \param y Cell index in Y axis.</span> <a name="l00137"></a>00137 <span class="comment"> * \param logodd_obs Observation of the cell, in log-odd form as transformed by p2l.</span> <a name="l00138"></a>00138 <span class="comment"> * \param thres This must be CELLTYPE_MAX-logodd_obs</span> <a name="l00139"></a>00139 <span class="comment"> * \sa updateCell_fast_occupied</span> <a name="l00140"></a>00140 <span class="comment"> */</span> <a name="l00141"></a><a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a25e9bc67e0e81242ee3359d8155a2e02">00141</a> <span class="keyword">inline</span> <span class="keyword">static</span> <span class="keywordtype">void</span> <a class="code" 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>( <a name="l00142"></a>00142 <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31" title="The type of cells.">cell_t</a> *theCell, <a name="l00143"></a>00143 <span class="keyword">const</span> <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31" title="The type of cells.">cell_t</a> logodd_obs, <a name="l00144"></a>00144 <span class="keyword">const</span> <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a303720ae1a3a6e0dd66a6f5000563c31" title="The type of cells.">cell_t</a> thres) <a name="l00145"></a>00145 { <a name="l00146"></a>00146 <span class="keywordflow">if</span> (*theCell < thres ) <a name="l00147"></a>00147 *theCell += logodd_obs; <a name="l00148"></a>00148 <span class="keywordflow">else</span> *theCell = <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map2_d.html#a3b3f3dea9c21f268423707ebb8133073">traits_t</a>::CELLTYPE_MAX; <a name="l00149"></a>00149 } <a name="l00150"></a>00150 <a name="l00151"></a>00151 }; <span class="comment">// end of CLogOddsGridMap2D</span> <a name="l00152"></a>00152 <span class="comment"></span> <a name="l00153"></a>00153 <span class="comment"> /** One static instance of this struct should exist in any class implementing CLogOddsGridMap2D to hold the Look-up-tables (LUTs) for log-odss Bayesian update.</span> <a name="l00154"></a>00154 <span class="comment"> * Map cells must be type TCELL, which can be only:</span> <a name="l00155"></a>00155 <span class="comment"> * - int8_t or</span> <a name="l00156"></a>00156 <span class="comment"> * - int16_t</span> <a name="l00157"></a>00157 <span class="comment"> *</span> <a name="l00158"></a>00158 <span class="comment"> * \sa CLogOddsGridMap2D, see derived classes for usage examples.</span> <a name="l00159"></a>00159 <span class="comment"> * \ingroup mrpt_maps_grp</span> <a name="l00160"></a>00160 <span class="comment"> */</span> <a name="l00161"></a>00161 <span class="keyword">template</span> <<span class="keyword">typename</span> TCELL> <a name="l00162"></a>00162 <span class="keyword">struct </span>CLogOddsGridMapLUT : <span class="keyword">public</span> detail::logoddscell_traits<TCELL> <a name="l00163"></a>00163 { <a name="l00164"></a><a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a7e029b03177c28b86c27ad95e9591d9a">00164</a> <span class="keyword">typedef</span> TCELL <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a7e029b03177c28b86c27ad95e9591d9a" title="The type of.">cell_t</a>; <span class="comment">//!< The type of</span> <a name="l00165"></a><a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a37f190d1b41eeefcf4e72c7d7aabb94b">00165</a> <span class="comment"></span> <span class="keyword">typedef</span> detail::logoddscell_traits<TCELL> <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a37f190d1b41eeefcf4e72c7d7aabb94b">traits_t</a>; <a name="l00166"></a>00166 <span class="comment"></span> <a name="l00167"></a>00167 <span class="comment"> /** A lookup table to compute occupancy probabilities in [0,1] from integer log-odds values in the cells, using \f$ p(m_{xy}) = \frac{1}{1+exp(-log_odd)} \f$.</span> <a name="l00168"></a>00168 <span class="comment"> */</span> <a name="l00169"></a><a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a3265c02c0b3ebf54d853750ffec4af59">00169</a> std<a class="code" href="classstd_1_1vector.html">::vector<float></a> <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a3265c02c0b3ebf54d853750ffec4af59" title="A lookup table to compute occupancy probabilities in [0,1] from integer log-odds values in the cells...">logoddsTable</a>; <a name="l00170"></a>00170 <span class="comment"></span> <a name="l00171"></a>00171 <span class="comment"> /** A lookup table to compute occupancy probabilities in the range [0,255] from integer log-odds values in the cells, using \f$ p(m_{xy}) = \frac{1}{1+exp(-log_odd)} \f$.</span> <a name="l00172"></a>00172 <span class="comment"> * This is used to speed-up conversions to grayscale images.</span> <a name="l00173"></a>00173 <span class="comment"> */</span> <a name="l00174"></a><a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a41a70c78a08d77b9a338922261b0763a">00174</a> std<a class="code" href="classstd_1_1vector.html">::vector<uint8_t></a> <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a41a70c78a08d77b9a338922261b0763a" title="A lookup table to compute occupancy probabilities in the range [0,255] from integer log-odds values i...">logoddsTable_255</a>; <a name="l00175"></a>00175 <span class="comment"></span> <a name="l00176"></a>00176 <span class="comment"> /** A lookup table for passing from float to log-odds as cell_t. */</span> <a name="l00177"></a><a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#aae8e647e1113fd0849bdca1b72816b99">00177</a> std<a class="code" href="classstd_1_1vector.html">::vector<cell_t></a> <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#aae8e647e1113fd0849bdca1b72816b99" title="A lookup table for passing from float to log-odds as cell_t.">p2lTable</a>; <a name="l00178"></a>00178 <span class="comment"></span> <a name="l00179"></a>00179 <span class="comment"> /** Constructor: computes all the required stuff. */</span> <a name="l00180"></a><a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a2ed63f4696719638d38afabad9788d58">00180</a> <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a2ed63f4696719638d38afabad9788d58" title="Constructor: computes all the required stuff.">CLogOddsGridMapLUT</a>() <a name="l00181"></a>00181 { <a name="l00182"></a>00182 <a class="code" href="mrpt__macros_8h.html#a45b840af519f33816311acdbb28d7c10">MRPT_START</a> <a name="l00183"></a>00183 <a name="l00184"></a>00184 <span class="comment">// The factor for converting log2-odds into integers:</span> <a name="l00185"></a>00185 <span class="keyword">static</span> <span class="keyword">const</span> <span class="keywordtype">double</span> LOGODD_K = 16; <a name="l00186"></a>00186 <span class="keyword">static</span> <span class="keyword">const</span> <span class="keywordtype">double</span> LOGODD_K_INV = 1.0/LOGODD_K; <a name="l00187"></a>00187 <a name="l00188"></a>00188 <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a3265c02c0b3ebf54d853750ffec4af59" title="A lookup table to compute occupancy probabilities in [0,1] from integer log-odds values in the cells...">logoddsTable</a>.resize( traits_t::LOGODDS_LUT_ENTRIES ); <a name="l00189"></a>00189 <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a41a70c78a08d77b9a338922261b0763a" title="A lookup table to compute occupancy probabilities in the range [0,255] from integer log-odds values i...">logoddsTable_255</a>.resize( traits_t::LOGODDS_LUT_ENTRIES ); <a name="l00190"></a>00190 <span class="keywordflow">for</span> (<span class="keywordtype">int</span> i=traits_t::CELLTYPE_MIN;i<=<a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a37f190d1b41eeefcf4e72c7d7aabb94b">traits_t</a>::CELLTYPE_MAX;i++) <a name="l00191"></a>00191 { <a name="l00192"></a>00192 <span class="keywordtype">float</span> f = 1.0f / (1.0f + exp( - i * LOGODD_K_INV ) ); <a name="l00193"></a>00193 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> idx = -<a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a37f190d1b41eeefcf4e72c7d7aabb94b">traits_t</a>::CELLTYPE_MIN+i; <a name="l00194"></a>00194 <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a3265c02c0b3ebf54d853750ffec4af59" title="A lookup table to compute occupancy probabilities in [0,1] from integer log-odds values in the cells...">logoddsTable</a>[idx] = f; <a name="l00195"></a>00195 <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a41a70c78a08d77b9a338922261b0763a" title="A lookup table to compute occupancy probabilities in the range [0,255] from integer log-odds values i...">logoddsTable_255</a>[idx] = (uint8_t)(f*255.0f); <a name="l00196"></a>00196 } <a name="l00197"></a>00197 <a name="l00198"></a>00198 <span class="comment">// Build the p2lTable as well:</span> <a name="l00199"></a>00199 <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#aae8e647e1113fd0849bdca1b72816b99" title="A lookup table for passing from float to log-odds as cell_t.">p2lTable</a>.resize( traits_t::P2LTABLE_SIZE+1 ); <a name="l00200"></a>00200 <span class="keywordtype">double</span> K = 1.0 / <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a37f190d1b41eeefcf4e72c7d7aabb94b">traits_t</a>::P2LTABLE_SIZE; <a name="l00201"></a>00201 <span class="keywordflow">for</span> (<span class="keywordtype">int</span> j=0;j<=<a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a37f190d1b41eeefcf4e72c7d7aabb94b">traits_t</a>::P2LTABLE_SIZE;j++) <a name="l00202"></a>00202 { <a name="l00203"></a>00203 <span class="keywordtype">double</span> p = j*K; <a name="l00204"></a>00204 <span class="keywordflow">if</span> (p==0) <a name="l00205"></a>00205 p=1e-14; <a name="l00206"></a>00206 <span class="keywordflow">else</span> <span class="keywordflow">if</span> (p==1) <a name="l00207"></a>00207 p=1-1e-14; <a name="l00208"></a>00208 <a name="l00209"></a>00209 <span class="keywordtype">double</span> logodd = log(p)-log(1-p); <a name="l00210"></a>00210 <span class="keywordtype">int</span> L = <a class="code" href="namespacemrpt_1_1utils.html#ab7d9cdf7d271c2f41fc1c5c9fa7d0828" title="Returns the closer integer (int) to x.">round</a>(logodd * LOGODD_K); <a name="l00211"></a>00211 <span class="keywordflow">if</span> (L>traits_t::CELLTYPE_MAX) <a name="l00212"></a>00212 L=<a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a37f190d1b41eeefcf4e72c7d7aabb94b">traits_t</a>::CELLTYPE_MAX; <a name="l00213"></a>00213 <span class="keywordflow">else</span> <span class="keywordflow">if</span> (L<traits_t::CELLTYPE_MIN) <a name="l00214"></a>00214 L=<a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a37f190d1b41eeefcf4e72c7d7aabb94b">traits_t</a>::CELLTYPE_MIN; <a name="l00215"></a>00215 <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#aae8e647e1113fd0849bdca1b72816b99" title="A lookup table for passing from float to log-odds as cell_t.">p2lTable</a>[j] = L; <a name="l00216"></a>00216 } <a name="l00217"></a>00217 <a name="l00218"></a>00218 <a class="code" href="mrpt__macros_8h.html#a88a917260793b56abd83ad2a0d849eb1">MRPT_END</a> <a name="l00219"></a>00219 } <a name="l00220"></a>00220 <span class="comment"></span> <a name="l00221"></a>00221 <span class="comment"> /** Scales an integer representation of the log-odd into a real valued probability in [0,1], using p=exp(l)/(1+exp(l))</span> <a name="l00222"></a>00222 <span class="comment"> */</span> <a name="l00223"></a><a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a26003c76f089968f664b8c7e3c7dd3d4">00223</a> <span class="keyword">inline</span> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a26003c76f089968f664b8c7e3c7dd3d4" title="Scales an integer representation of the log-odd into a real valued probability in [0...">l2p</a>(<span class="keyword">const</span> <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a7e029b03177c28b86c27ad95e9591d9a" title="The type of.">cell_t</a> l) <a name="l00224"></a>00224 { <a name="l00225"></a>00225 <span class="keywordflow">if</span> (l<traits_t::CELLTYPE_MIN) <a name="l00226"></a>00226 <span class="keywordflow">return</span> <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a3265c02c0b3ebf54d853750ffec4af59" title="A lookup table to compute occupancy probabilities in [0,1] from integer log-odds values in the cells...">logoddsTable</a>[ 0 ]; <span class="comment">// This is needed since min can be -127 and int8_t can be -128.</span> <a name="l00227"></a>00227 <span class="keywordflow">else</span> <span class="keywordflow">return</span> <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a3265c02c0b3ebf54d853750ffec4af59" title="A lookup table to compute occupancy probabilities in [0,1] from integer log-odds values in the cells...">logoddsTable</a>[ -<a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a37f190d1b41eeefcf4e72c7d7aabb94b">traits_t</a>::CELLTYPE_MIN+l ]; <a name="l00228"></a>00228 } <a name="l00229"></a>00229 <span class="comment"></span> <a name="l00230"></a>00230 <span class="comment"> /** Scales an integer representation of the log-odd into a linear scale [0,255], using p=exp(l)/(1+exp(l))</span> <a name="l00231"></a>00231 <span class="comment"> */</span> <a name="l00232"></a><a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a5e16de15a3e35a430f3a5609e711d8ae">00232</a> <span class="keyword">inline</span> uint8_t <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a5e16de15a3e35a430f3a5609e711d8ae" title="Scales an integer representation of the log-odd into a linear scale [0,255], using p=exp(l)/(1+exp(l)...">l2p_255</a>(<span class="keyword">const</span> <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a7e029b03177c28b86c27ad95e9591d9a" title="The type of.">cell_t</a> l) <a name="l00233"></a>00233 { <a name="l00234"></a>00234 <span class="keywordflow">if</span> (l<traits_t::CELLTYPE_MIN) <a name="l00235"></a>00235 <span class="keywordflow">return</span> <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a41a70c78a08d77b9a338922261b0763a" title="A lookup table to compute occupancy probabilities in the range [0,255] from integer log-odds values i...">logoddsTable_255</a>[ 0 ]; <span class="comment">// This is needed since min can be -127 and int8_t can be -128.</span> <a name="l00236"></a>00236 <span class="keywordflow">else</span> <span class="keywordflow">return</span> <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a41a70c78a08d77b9a338922261b0763a" title="A lookup table to compute occupancy probabilities in the range [0,255] from integer log-odds values i...">logoddsTable_255</a>[ -<a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a37f190d1b41eeefcf4e72c7d7aabb94b">traits_t</a>::CELLTYPE_MIN+l ]; <a name="l00237"></a>00237 } <a name="l00238"></a>00238 <span class="comment"></span> <a name="l00239"></a>00239 <span class="comment"> /** Scales a real valued probability in [0,1] to an integer representation of: log(p)-log(1-p) in the valid range of cell_t.</span> <a name="l00240"></a>00240 <span class="comment"> */</span> <a name="l00241"></a><a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#af325712d6dc838a8721e35545f550103">00241</a> <span class="keyword">inline</span> <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a7e029b03177c28b86c27ad95e9591d9a" title="The type of.">cell_t</a> <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#af325712d6dc838a8721e35545f550103" title="Scales a real valued probability in [0,1] to an integer representation of: log(p)-log(1-p) in the val...">p2l</a>(<span class="keyword">const</span> <span class="keywordtype">float</span> p) <a name="l00242"></a>00242 { <a name="l00243"></a>00243 <span class="keywordflow">return</span> <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#aae8e647e1113fd0849bdca1b72816b99" title="A lookup table for passing from float to log-odds as cell_t.">p2lTable</a>[ <span class="keyword">static_cast<</span><span class="keywordtype">unsigned</span> <span class="keywordtype">int</span><span class="keyword">></span>(p * <a class="code" href="structmrpt_1_1slam_1_1_c_log_odds_grid_map_l_u_t.html#a37f190d1b41eeefcf4e72c7d7aabb94b">traits_t</a>::P2LTABLE_SIZE) ]; <a name="l00244"></a>00244 } <a name="l00245"></a>00245 <a name="l00246"></a>00246 }; <span class="comment">// end of CLogOddsGridMap2D</span> <a name="l00247"></a>00247 <a name="l00248"></a>00248 } <span class="comment">// End of namespace</span> <a name="l00249"></a>00249 } <span class="comment">// End of namespace</span> <a name="l00250"></a>00250 <a name="l00251"></a>00251 <span class="preprocessor">#endif</span> </pre></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>