<!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>CRandomFieldGridMap2D.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">CRandomFieldGridMap2D.h</div> </div> </div> <div class="contents"> <a href="_c_random_field_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 CRandomFieldGridMap2D_H</span> <a name="l00030"></a>00030 <span class="preprocessor"></span><span class="preprocessor">#define CRandomFieldGridMap2D_H</span> <a name="l00031"></a>00031 <span class="preprocessor"></span> <a name="l00032"></a>00032 <span class="preprocessor">#include <<a class="code" href="_c_dynamic_grid_8h.html">mrpt/utils/CDynamicGrid.h</a>></span> <a name="l00033"></a>00033 <span class="preprocessor">#include <<a class="code" href="_c_image_8h.html">mrpt/utils/CImage.h</a>></span> <a name="l00034"></a>00034 <span class="preprocessor">#include <<a class="code" href="_c_serializable_8h.html">mrpt/utils/CSerializable.h</a>></span> <a name="l00035"></a>00035 <span class="preprocessor">#include <<a class="code" href="_c_matrix_d_8h.html">mrpt/math/CMatrixD.h</a>></span> <a name="l00036"></a>00036 <span class="preprocessor">#include <<a class="code" href="_c_loadable_options_8h.html">mrpt/utils/CLoadableOptions.h</a>></span> <a name="l00037"></a>00037 <span class="preprocessor">#include <<a class="code" href="_c_metric_map_8h.html">mrpt/slam/CMetricMap.h</a>></span> <a name="l00038"></a>00038 <a name="l00039"></a>00039 <span class="preprocessor">#include <<a class="code" href="maps_2include_2mrpt_2maps_2link__pragmas_8h.html">mrpt/maps/link_pragmas.h</a>></span> <a name="l00040"></a>00040 <a name="l00041"></a>00041 <span class="keyword">namespace </span>mrpt <a name="l00042"></a>00042 { <a name="l00043"></a>00043 <span class="keyword">namespace </span>slam <a name="l00044"></a>00044 { <a name="l00045"></a>00045 <span class="keyword">using namespace </span>mrpt::utils; <a name="l00046"></a>00046 <span class="keyword">using namespace </span>mrpt::poses; <a name="l00047"></a>00047 <span class="keyword">using namespace </span>mrpt::math; <a name="l00048"></a>00048 <a name="l00049"></a><a class="code" href="structmrpt_1_1slam_1_1_c_random_field_grid_map2_d_ptr.html#a0f2932a4539e57857c23a5667f35b1a0">00049</a> <a class="code" href="_c_serializable_8h.html#a9ef523d787f6cb837a0585b790882588" title="This declaration must be inserted in all CSerializable classes definition, before the class declarati...">DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE_LINKAGE</a>( <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html" title="CRandomFieldGridMap2D represents a 2D grid map where each cell is associated one real-valued property...">CRandomFieldGridMap2D</a> , <a class="code" href="classmrpt_1_1slam_1_1_c_metric_map.html" title="Declares a virtual base class for all metric maps storage classes.">CMetricMap</a>, <a class="code" href="maps_2include_2mrpt_2maps_2link__pragmas_8h.html#ad401479c152d92658375c646837e33ed">MAPS_IMPEXP</a> ) <a name="l00050"></a>00050 <a name="l00051"></a>00051 <span class="comment">// Pragma defined to ensure no structure packing: since we'll serialize TRandomFieldCell to streams, we want it not to depend on compiler options, etc.</span> <a name="l00052"></a>00052 <span class="preprocessor">#pragma pack(push,1)</span> <a name="l00053"></a>00053 <span class="preprocessor"></span><span class="comment"></span> <a name="l00054"></a>00054 <span class="comment"> /** The contents of each cell in a CRandomFieldGridMap2D map.</span> <a name="l00055"></a>00055 <span class="comment"> * \ingroup mrpt_maps_grp</span> <a name="l00056"></a>00056 <span class="comment"> **/</span> <a name="l00057"></a>00057 <span class="keyword">struct </span><a class="code" href="maps_2include_2mrpt_2maps_2link__pragmas_8h.html#ad401479c152d92658375c646837e33ed">MAPS_IMPEXP</a> <a class="code" href="structmrpt_1_1slam_1_1_t_random_field_cell.html" title="The contents of each cell in a CRandomFieldGridMap2D map.">TRandomFieldCell</a> <a name="l00058"></a>00058 {<span class="comment"></span> <a name="l00059"></a>00059 <span class="comment"> /** Constructor */</span> <a name="l00060"></a><a class="code" href="structmrpt_1_1slam_1_1_t_random_field_cell.html#ae51f78ff90665adf2be628c9a7eee94e">00060</a> <a class="code" href="structmrpt_1_1slam_1_1_t_random_field_cell.html" title="The contents of each cell in a CRandomFieldGridMap2D map.">TRandomFieldCell</a>(<span class="keywordtype">double</span> kfmean_dm_mean = 1e-20, <span class="keywordtype">double</span> kfstd_dmmeanw = 0) : <a name="l00061"></a>00061 kf_mean (kfmean_dm_mean), <a name="l00062"></a>00062 kf_std (kfstd_dmmeanw), <a name="l00063"></a>00063 dmv_var_mean (0) <a name="l00064"></a>00064 { } <a name="l00065"></a>00065 <a name="l00066"></a>00066 <span class="comment">// *Note*: Use unions to share memory between data fields, since only a set</span> <a name="l00067"></a>00067 <span class="comment">// of the variables will be used for each mapping strategy.</span> <a name="l00068"></a>00068 <span class="comment">// You can access to a "TRandomFieldCell *cell" like: cell->kf_mean, cell->kf_std, etc..</span> <a name="l00069"></a>00069 <span class="comment">// but accessing cell->kf_mean would also modify (i.e. ARE the same memory slot) cell->dm_mean, for example.</span> <a name="l00070"></a>00070 <a name="l00071"></a>00071 <span class="comment">// Note 2: If the number of type of fields are changed in the future,</span> <a name="l00072"></a>00072 <span class="comment">// *PLEASE* also update the writeToStream() and readFromStream() methods!!</span> <a name="l00073"></a>00073 <a name="l00074"></a>00074 <span class="keyword">union</span> <a name="l00075"></a>00075 { <a name="l00076"></a><a class="code" href="structmrpt_1_1slam_1_1_t_random_field_cell.html#ac4a861d42bf807d9427826b61367c7e0">00076</a> <span class="keywordtype">double</span> <a class="code" href="structmrpt_1_1slam_1_1_t_random_field_cell.html#ac4a861d42bf807d9427826b61367c7e0" title="[KF-methods only] The mean value of this cell">kf_mean</a>; <span class="comment">//!< [KF-methods only] The mean value of this cell</span> <a name="l00077"></a><a class="code" href="structmrpt_1_1slam_1_1_t_random_field_cell.html#a3ebb8faed77a76c1a14ff2753e967bd3">00077</a> <span class="comment"></span> <span class="keywordtype">double</span> <a class="code" href="structmrpt_1_1slam_1_1_t_random_field_cell.html#a3ebb8faed77a76c1a14ff2753e967bd3" title="[Kernel-methods only] The cumulative weighted readings of this cell">dm_mean</a>; <span class="comment">//!< [Kernel-methods only] The cumulative weighted readings of this cell</span> <a name="l00078"></a>00078 <span class="comment"></span> <a name="l00079"></a>00079 }; <a name="l00080"></a>00080 <span class="keyword">union</span> <a name="l00081"></a>00081 { <a name="l00082"></a><a class="code" href="structmrpt_1_1slam_1_1_t_random_field_cell.html#a541290d488a73f062d325872dff27165">00082</a> <span class="keywordtype">double</span> <a class="code" href="structmrpt_1_1slam_1_1_t_random_field_cell.html#a541290d488a73f062d325872dff27165" title="[KF-methods only] The standard deviation value of this cell">kf_std</a>; <span class="comment">//!< [KF-methods only] The standard deviation value of this cell</span> <a name="l00083"></a><a class="code" href="structmrpt_1_1slam_1_1_t_random_field_cell.html#a17b8298c337ebe804c26e07bddfcb31a">00083</a> <span class="comment"></span> <span class="keywordtype">double</span> <a class="code" href="structmrpt_1_1slam_1_1_t_random_field_cell.html#a17b8298c337ebe804c26e07bddfcb31a" title="[Kernel-methods only] The cumulative weights (concentration = alpha * dm_mean / dm_mean_w + (1-alpha)...">dm_mean_w</a>; <span class="comment">//!< [Kernel-methods only] The cumulative weights (concentration = alpha * dm_mean / dm_mean_w + (1-alpha)*r0 )</span> <a name="l00084"></a>00084 <span class="comment"></span> }; <a name="l00085"></a>00085 <a name="l00086"></a><a class="code" href="structmrpt_1_1slam_1_1_t_random_field_cell.html#aaafcff5dc50fd1e73b7ddfac09a229ca">00086</a> <span class="keywordtype">double</span> <a class="code" href="structmrpt_1_1slam_1_1_t_random_field_cell.html#aaafcff5dc50fd1e73b7ddfac09a229ca" title="[Kernel DM-V only] The cumulative weighted variance of this cell">dmv_var_mean</a>; <span class="comment">//!< [Kernel DM-V only] The cumulative weighted variance of this cell</span> <a name="l00087"></a>00087 <span class="comment"></span> }; <a name="l00088"></a>00088 <span class="preprocessor">#pragma pack(pop)</span> <a name="l00089"></a>00089 <span class="preprocessor"></span><span class="comment"></span> <a name="l00090"></a>00090 <span class="comment"> /** CRandomFieldGridMap2D represents a 2D grid map where each cell is associated one real-valued property which is estimated by this map, either</span> <a name="l00091"></a>00091 <span class="comment"> * as a simple value or as a probility distribution (for each cell).</span> <a name="l00092"></a>00092 <span class="comment"> *</span> <a name="l00093"></a>00093 <span class="comment"> * There are a number of methods available to build the gas grid-map, depending on the value of</span> <a name="l00094"></a>00094 <span class="comment"> * "TMapRepresentation maptype" passed in the constructor.</span> <a name="l00095"></a>00095 <span class="comment"> *</span> <a name="l00096"></a>00096 <span class="comment"> * The following papers describe the mapping alternatives implemented here:</span> <a name="l00097"></a>00097 <span class="comment"> * - mrKernelDM: A kernel-based method:</span> <a name="l00098"></a>00098 <span class="comment"> * "Building gas concentration gridmaps with a mobile robot", Lilienthal, A. and Duckett, T., Robotics and Autonomous Systems, v.48, 2004.</span> <a name="l00099"></a>00099 <span class="comment"> *</span> <a name="l00100"></a>00100 <span class="comment"> * - mrKernelDMV: A kernel-based method:</span> <a name="l00101"></a>00101 <span class="comment"> * "A Statistical Approach to Gas Distribution Modelling with Mobile Robots--The Kernel DM+ V Algorithm"</span> <a name="l00102"></a>00102 <span class="comment"> * , Lilienthal, A.J. and Reggente, M. and Trincavelli, M. and Blanco, J.L. and Gonzalez, J., IROS 2009.</span> <a name="l00103"></a>00103 <span class="comment"> *</span> <a name="l00104"></a>00104 <span class="comment"> * Note that this class is virtual, since derived classes still have to implement:</span> <a name="l00105"></a>00105 <span class="comment"> * - mrpt::slam::CMetricMap::computeObservationLikelihood()</span> <a name="l00106"></a>00106 <span class="comment"> * - mrpt::slam::CMetricMap::internal_insertObservation()</span> <a name="l00107"></a>00107 <span class="comment"> * - Serialization methods: writeToStream() and readFromStream()</span> <a name="l00108"></a>00108 <span class="comment"> *</span> <a name="l00109"></a>00109 <span class="comment"> * \sa mrpt::slam::CGasConcentrationGridMap2D, mrpt::slam::CWirelessPowerGridMap2D, mrpt::slam::CMetricMap, mrpt::utils::CDynamicGrid, The application icp-slam, mrpt::slam::CMultiMetricMap</span> <a name="l00110"></a>00110 <span class="comment"> * \ingroup mrpt_maps_grp</span> <a name="l00111"></a>00111 <span class="comment"> */</span> <a name="l00112"></a>00112 <span class="keyword">class </span><a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html" title="CRandomFieldGridMap2D represents a 2D grid map where each cell is associated one real-valued property...">CRandomFieldGridMap2D</a> : <span class="keyword">public</span> <a class="code" href="classmrpt_1_1slam_1_1_c_metric_map.html" title="Declares a virtual base class for all metric maps storage classes.">CMetricMap</a>, <span class="keyword">public</span> utils::<a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html" title="A 2D grid of dynamic size which stores any kind of data at each cell.">CDynamicGrid</a><TRandomFieldCell> <a name="l00113"></a>00113 { <a name="l00114"></a><a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a06bea6c1795bab58bfa5ec4529af9e84">00114</a> <span class="keyword">typedef</span> utils<a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html">::CDynamicGrid<TRandomFieldCell></a> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a06bea6c1795bab58bfa5ec4529af9e84">BASE</a>; <a name="l00115"></a>00115 <a name="l00116"></a>00116 <span class="comment">// This must be added to any CSerializable derived class:</span> <a name="l00117"></a><a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a6fec28a53e20dfc1c4d046c26f9f7b48">00117</a> <a class="code" href="_c_serializable_8h.html#a5876f72cf51bfb66a82bf81cc493febc" title="This declaration must be inserted in virtual CSerializable classes definition:">DEFINE_VIRTUAL_SERIALIZABLE</a>( <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html" title="CRandomFieldGridMap2D represents a 2D grid map where each cell is associated one real-valued property...">CRandomFieldGridMap2D</a> ) <a name="l00118"></a>00118 public: <a name="l00119"></a>00119 <span class="comment"></span> <a name="l00120"></a>00120 <span class="comment"> /** Calls the base CMetricMap::clear</span> <a name="l00121"></a>00121 <span class="comment"> * Declared here to avoid ambiguity between the two clear() in both base classes.</span> <a name="l00122"></a>00122 <span class="comment"> */</span> <a name="l00123"></a><a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a814f4778b6ae7a2f9896311258d11d16">00123</a> inline <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a814f4778b6ae7a2f9896311258d11d16" title="Calls the base CMetricMap::clear Declared here to avoid ambiguity between the two clear() in both bas...">clear</a>() { <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a814f4778b6ae7a2f9896311258d11d16" title="Calls the base CMetricMap::clear Declared here to avoid ambiguity between the two clear() in both bas...">CMetricMap::clear</a>(); } <a name="l00124"></a>00124 <a name="l00125"></a>00125 <span class="comment">// This method is just used for the ::saveToTextFile() method in base class.</span> <a name="l00126"></a><a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a2003d2a313da0a880a43949201713243">00126</a> <span class="keywordtype">float</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a2003d2a313da0a880a43949201713243">cell2float</a>(<span class="keyword">const</span> <a class="code" href="structmrpt_1_1slam_1_1_t_random_field_cell.html" title="The contents of each cell in a CRandomFieldGridMap2D map.">TRandomFieldCell</a>& c)<span class="keyword"> const</span> <a name="l00127"></a>00127 <span class="keyword"> </span>{ <a name="l00128"></a>00128 <span class="keywordflow">return</span> c.<a class="code" href="structmrpt_1_1slam_1_1_t_random_field_cell.html#ac4a861d42bf807d9427826b61367c7e0" title="[KF-methods only] The mean value of this cell">kf_mean</a>; <a name="l00129"></a>00129 } <a name="l00130"></a>00130 <span class="comment"></span> <a name="l00131"></a>00131 <span class="comment"> /** The type of map representation to be used.</span> <a name="l00132"></a>00132 <span class="comment"> */</span> <a name="l00133"></a><a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a1bdb0ec64ac5ebc8f0b803b66151703a">00133</a> <span class="keyword">enum</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a1bdb0ec64ac5ebc8f0b803b66151703a" title="The type of map representation to be used.">TMapRepresentation</a> <a name="l00134"></a>00134 { <a name="l00135"></a><a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a1bdb0ec64ac5ebc8f0b803b66151703aa74922fc75f39ecce9f2f53a6fd1af7cc">00135</a> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a1bdb0ec64ac5ebc8f0b803b66151703aa74922fc75f39ecce9f2f53a6fd1af7cc">mrKernelDM</a> = 0, <span class="comment">//</span> <a name="l00136"></a><a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a1bdb0ec64ac5ebc8f0b803b66151703aa9309f68da0f5bb01cdfa973305ce623c">00136</a> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a1bdb0ec64ac5ebc8f0b803b66151703aa9309f68da0f5bb01cdfa973305ce623c">mrAchim</a> = 0, <span class="comment">// Another alias for "mrKernelDM", for backward compatibility</span> <a name="l00137"></a><a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a1bdb0ec64ac5ebc8f0b803b66151703aa65b92bd320f8b9834cbe5554b7f2a4c0">00137</a> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a1bdb0ec64ac5ebc8f0b803b66151703aa65b92bd320f8b9834cbe5554b7f2a4c0">mrKalmanFilter</a>, <a name="l00138"></a><a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a1bdb0ec64ac5ebc8f0b803b66151703aaa58f7d260813aa09d312883dee48d56b">00138</a> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a1bdb0ec64ac5ebc8f0b803b66151703aaa58f7d260813aa09d312883dee48d56b">mrKalmanApproximate</a>, <a name="l00139"></a><a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a1bdb0ec64ac5ebc8f0b803b66151703aab63874317f7204696d76c86b89beed16">00139</a> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a1bdb0ec64ac5ebc8f0b803b66151703aab63874317f7204696d76c86b89beed16">mrKernelDMV</a> <a name="l00140"></a>00140 }; <a name="l00141"></a>00141 <span class="comment"></span> <a name="l00142"></a>00142 <span class="comment"> /** Constructor</span> <a name="l00143"></a>00143 <span class="comment"> */</span> <a name="l00144"></a>00144 <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#accefbf61b5feb257bfab0530184337ff" title="Constructor.">CRandomFieldGridMap2D</a>( <a name="l00145"></a>00145 <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a1bdb0ec64ac5ebc8f0b803b66151703a" title="The type of map representation to be used.">TMapRepresentation</a> mapType = <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a1bdb0ec64ac5ebc8f0b803b66151703aa9309f68da0f5bb01cdfa973305ce623c">mrAchim</a>, <a name="l00146"></a>00146 <span class="keywordtype">float</span> x_min = -2, <a name="l00147"></a>00147 <span class="keywordtype">float</span> x_max = 2, <a name="l00148"></a>00148 <span class="keywordtype">float</span> y_min = -2, <a name="l00149"></a>00149 <span class="keywordtype">float</span> y_max = 2, <a name="l00150"></a>00150 <span class="keywordtype">float</span> resolution = 0.1 <a name="l00151"></a>00151 ); <a name="l00152"></a>00152 <span class="comment"></span> <a name="l00153"></a>00153 <span class="comment"> /** Destructor */</span> <a name="l00154"></a>00154 <span class="keyword">virtual</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#ab0b808a64312a83401796abfa4e33076" title="Destructor.">~CRandomFieldGridMap2D</a>(); <a name="l00155"></a>00155 <span class="comment"></span> <a name="l00156"></a>00156 <span class="comment"> /** Returns true if the map is empty/no observation has been inserted (in this class it always return false,</span> <a name="l00157"></a>00157 <span class="comment"> * unless redefined otherwise in base classes)</span> <a name="l00158"></a>00158 <span class="comment"> */</span> <a name="l00159"></a>00159 <span class="keyword">virtual</span> <span class="keywordtype">bool</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a1a5d553a88fe8001ee9bd99b3ce4b52d" title="Returns true if the map is empty/no observation has been inserted (in this class it always return fal...">isEmpty</a>() <span class="keyword">const</span>; <a name="l00160"></a>00160 <a name="l00161"></a>00161 <span class="comment"></span> <a name="l00162"></a>00162 <span class="comment"> /** Save the current map as a graphical file (BMP,PNG,...).</span> <a name="l00163"></a>00163 <span class="comment"> * The file format will be derived from the file extension (see CImage::saveToFile )</span> <a name="l00164"></a>00164 <span class="comment"> * It depends on the map representation model:</span> <a name="l00165"></a>00165 <span class="comment"> * mrAchim: Each pixel is the ratio \f$ \sum{\frac{wR}{w}} \f$</span> <a name="l00166"></a>00166 <span class="comment"> * mrKalmanFilter: Each pixel is the mean value of the Gaussian that represents each cell.</span> <a name="l00167"></a>00167 <span class="comment"> *</span> <a name="l00168"></a>00168 <span class="comment"> * \sa \a getAsBitmapFile()</span> <a name="l00169"></a>00169 <span class="comment"> */</span> <a name="l00170"></a>00170 <span class="keyword">virtual</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#ae9683b3ad3051a68b012aa67aa544ce0" title="Save the current map as a graphical file (BMP,PNG,...).">saveAsBitmapFile</a>(<span class="keyword">const</span> <a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a> &filName) <span class="keyword">const</span>; <a name="l00171"></a>00171 <span class="comment"></span> <a name="l00172"></a>00172 <span class="comment"> /** Returns an image just as described in \a saveAsBitmapFile */</span> <a name="l00173"></a>00173 <span class="keyword">virtual</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#afc6db16768f9079bf47d5b1476b5e996" title="Returns an image just as described in saveAsBitmapFile.">getAsBitmapFile</a>(<a class="code" href="classmrpt_1_1utils_1_1_c_image.html" title="A class for storing images as grayscale or RGB bitmaps.">mrpt::utils::CImage</a> &out_img) <span class="keyword">const</span>; <a name="l00174"></a>00174 <span class="comment"></span> <a name="l00175"></a>00175 <span class="comment"> /** Parameters common to any derived class.</span> <a name="l00176"></a>00176 <span class="comment"> * Derived classes should derive a new struct from this one, plus "public utils::CLoadableOptions",</span> <a name="l00177"></a>00177 <span class="comment"> * and call the internal_* methods where appropiate to deal with the variables declared here.</span> <a name="l00178"></a>00178 <span class="comment"> * Derived classes instantions of their "TInsertionOptions" MUST set the pointer "m_insertOptions_common" upon construction.</span> <a name="l00179"></a>00179 <span class="comment"> */</span> <a name="l00180"></a>00180 <span class="keyword">struct </span><a class="code" href="maps_2include_2mrpt_2maps_2link__pragmas_8h.html#ad401479c152d92658375c646837e33ed">MAPS_IMPEXP</a> TInsertionOptionsCommon <a name="l00181"></a>00181 { <a name="l00182"></a>00182 TInsertionOptionsCommon(); <span class="comment">//!< Default values loader</span> <a name="l00183"></a>00183 <span class="comment"></span><span class="comment"></span> <a name="l00184"></a>00184 <span class="comment"> /** See utils::CLoadableOptions */</span> <a name="l00185"></a>00185 <span class="keywordtype">void</span> internal_loadFromConfigFile_common( <a name="l00186"></a>00186 <span class="keyword">const</span> <a class="code" href="classmrpt_1_1utils_1_1_c_config_file_base.html" title="This class allows loading and storing values and vectors of different types from a configuration text...">mrpt::utils::CConfigFileBase</a> &source, <a name="l00187"></a>00187 <span class="keyword">const</span> <a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a> &section); <a name="l00188"></a>00188 <a name="l00189"></a>00189 <span class="keywordtype">void</span> internal_dumpToTextStream_common(<a class="code" href="classmrpt_1_1utils_1_1_c_stream.html" title="This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...">CStream</a> &out) <span class="keyword">const</span>; <span class="comment">//!< See utils::CLoadableOptions</span> <a name="l00190"></a>00190 <span class="comment"></span><span class="comment"></span> <a name="l00191"></a>00191 <span class="comment"> /** @name Kernel methods (mrKernelDM, mrKernelDMV)</span> <a name="l00192"></a>00192 <span class="comment"> @{ */</span> <a name="l00193"></a><a class="code" href="structmrpt_1_1slam_1_1_c_random_field_grid_map2_d_1_1_t_insertion_options_common.html#a3afa47032318bd32e9df69c0a792df30">00193</a> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1slam_1_1_c_random_field_grid_map2_d_1_1_t_insertion_options_common.html#a3afa47032318bd32e9df69c0a792df30" title="The sigma of the "Parzen"-kernel Gaussian.">sigma</a>; <span class="comment">//!< The sigma of the "Parzen"-kernel Gaussian</span> <a name="l00194"></a><a class="code" href="structmrpt_1_1slam_1_1_c_random_field_grid_map2_d_1_1_t_insertion_options_common.html#a86394e651b3089dbd144885cf0a67a69">00194</a> <span class="comment"></span> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1slam_1_1_c_random_field_grid_map2_d_1_1_t_insertion_options_common.html#a86394e651b3089dbd144885cf0a67a69" title="The cutoff radius for updating cells.">cutoffRadius</a>; <span class="comment">//!< The cutoff radius for updating cells.</span> <a name="l00195"></a><a class="code" href="structmrpt_1_1slam_1_1_c_random_field_grid_map2_d_1_1_t_insertion_options_common.html#a730287aeef0fae9cc76e6ca1bfca42c9">00195</a> <span class="comment"></span> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1slam_1_1_c_random_field_grid_map2_d_1_1_t_insertion_options_common.html#a730287aeef0fae9cc76e6ca1bfca42c9">R_min</a>,R_max; <span class="comment">//!< Limits for normalization of sensor readings.</span> <a name="l00196"></a><a class="code" href="structmrpt_1_1slam_1_1_c_random_field_grid_map2_d_1_1_t_insertion_options_common.html#a121eacfeb225178211331521fded415f">00196</a> <span class="comment"></span> <span class="keywordtype">double</span> <a class="code" href="structmrpt_1_1slam_1_1_c_random_field_grid_map2_d_1_1_t_insertion_options_common.html#a121eacfeb225178211331521fded415f" title="[DM/DM+V methods] The scaling parameter for the confidence "alpha" values (see the IROS 2009 paper; s...">dm_sigma_omega</a>; <span class="comment">//!< [DM/DM+V methods] The scaling parameter for the confidence "alpha" values (see the IROS 2009 paper; see CRandomFieldGridMap2D) */</span> <a name="l00197"></a>00197 <span class="comment"></span><span class="comment"> /** @} */</span> <a name="l00198"></a>00198 <span class="comment"></span> <a name="l00199"></a>00199 <span class="comment"> /** @name Kalman-filter methods (mrKalmanFilter, mrKalmanApproximate)</span> <a name="l00200"></a>00200 <span class="comment"> @{ */</span> <a name="l00201"></a><a class="code" href="structmrpt_1_1slam_1_1_c_random_field_grid_map2_d_1_1_t_insertion_options_common.html#ab3ac1c547894de9da1ff86788c8b706b">00201</a> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1slam_1_1_c_random_field_grid_map2_d_1_1_t_insertion_options_common.html#ab3ac1c547894de9da1ff86788c8b706b" title="The "sigma" for the initial covariance value between cells (in meters).">KF_covSigma</a>; <span class="comment">//!< The "sigma" for the initial covariance value between cells (in meters).</span> <a name="l00202"></a><a class="code" href="structmrpt_1_1slam_1_1_c_random_field_grid_map2_d_1_1_t_insertion_options_common.html#af34344b6687eb12c29eb21cb33573cfd">00202</a> <span class="comment"></span> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1slam_1_1_c_random_field_grid_map2_d_1_1_t_insertion_options_common.html#af34344b6687eb12c29eb21cb33573cfd" title="The initial standard deviation of each cell's concentration (will be stored both at each cell's struc...">KF_initialCellStd</a>; <span class="comment">//!< The initial standard deviation of each cell's concentration (will be stored both at each cell's structure and in the covariance matrix as variances in the diagonal) (in normalized concentration units).</span> <a name="l00203"></a><a class="code" href="structmrpt_1_1slam_1_1_c_random_field_grid_map2_d_1_1_t_insertion_options_common.html#a7dfc988c09f0529ec670f83233c371a0">00203</a> <span class="comment"></span> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1slam_1_1_c_random_field_grid_map2_d_1_1_t_insertion_options_common.html#a7dfc988c09f0529ec670f83233c371a0" title="The sensor model noise (in normalized concentration units).">KF_observationModelNoise</a>; <span class="comment">//!< The sensor model noise (in normalized concentration units).</span> <a name="l00204"></a><a class="code" href="structmrpt_1_1slam_1_1_c_random_field_grid_map2_d_1_1_t_insertion_options_common.html#a8cf9d24ff786ef4216809575a316fff5">00204</a> <span class="comment"></span> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1slam_1_1_c_random_field_grid_map2_d_1_1_t_insertion_options_common.html#a8cf9d24ff786ef4216809575a316fff5" title="The default value for the mean of cells' concentration.">KF_defaultCellMeanValue</a>; <span class="comment">//!< The default value for the mean of cells' concentration.</span> <a name="l00205"></a><a class="code" href="structmrpt_1_1slam_1_1_c_random_field_grid_map2_d_1_1_t_insertion_options_common.html#accf983f2c4803b8ee3a79b2a27dd955e">00205</a> <span class="comment"></span> uint16_t <a class="code" href="structmrpt_1_1slam_1_1_c_random_field_grid_map2_d_1_1_t_insertion_options_common.html#accf983f2c4803b8ee3a79b2a27dd955e" title="[mrKalmanApproximate] The size of the window of neighbor cells.">KF_W_size</a>; <span class="comment">//!< [mrKalmanApproximate] The size of the window of neighbor cells.</span> <a name="l00206"></a>00206 <span class="comment"></span><span class="comment"> /** @} */</span> <a name="l00207"></a>00207 }; <a name="l00208"></a>00208 <span class="comment"></span> <a name="l00209"></a>00209 <span class="comment"> /** Changes the size of the grid, maintaining previous contents.</span> <a name="l00210"></a>00210 <span class="comment"> * \sa setSize</span> <a name="l00211"></a>00211 <span class="comment"> */</span> <a name="l00212"></a>00212 <span class="keyword">virtual</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a609f16ecd8a54610090f48b474b5098f" title="Changes the size of the grid, maintaining previous contents.">resize</a>( <span class="keywordtype">float</span> new_x_min, <a name="l00213"></a>00213 <span class="keywordtype">float</span> new_x_max, <a name="l00214"></a>00214 <span class="keywordtype">float</span> new_y_min, <a name="l00215"></a>00215 <span class="keywordtype">float</span> new_y_max, <a name="l00216"></a>00216 <span class="keyword">const</span> <a class="code" href="structmrpt_1_1slam_1_1_t_random_field_cell.html" title="The contents of each cell in a CRandomFieldGridMap2D map.">TRandomFieldCell</a>& defaultValueNewCells, <a name="l00217"></a>00217 <span class="keywordtype">float</span> additionalMarginMeters = 1.0f ); <a name="l00218"></a>00218 <span class="comment"></span> <a name="l00219"></a>00219 <span class="comment"> /** Computes the ratio in [0,1] of correspondences between "this" and the "otherMap" map, whose 6D pose relative to "this" is "otherMapPose"</span> <a name="l00220"></a>00220 <span class="comment"> * In the case of a multi-metric map, this returns the average between the maps. This method always return 0 for grid maps.</span> <a name="l00221"></a>00221 <span class="comment"> * \param otherMap [IN] The other map to compute the matching with.</span> <a name="l00222"></a>00222 <span class="comment"> * \param otherMapPose [IN] The 6D pose of the other map as seen from "this".</span> <a name="l00223"></a>00223 <span class="comment"> * \param minDistForCorr [IN] The minimum distance between 2 non-probabilistic map elements for counting them as a correspondence.</span> <a name="l00224"></a>00224 <span class="comment"> * \param minMahaDistForCorr [IN] The minimum Mahalanobis distance between 2 probabilistic map elements for counting them as a correspondence.</span> <a name="l00225"></a>00225 <span class="comment"> *</span> <a name="l00226"></a>00226 <span class="comment"> * \return The matching ratio [0,1]</span> <a name="l00227"></a>00227 <span class="comment"> * \sa computeMatchingWith2D</span> <a name="l00228"></a>00228 <span class="comment"> */</span> <a name="l00229"></a>00229 <span class="keywordtype">float</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#acf4c103e5db2f06ec814645f728f6ce2" title="Computes the ratio in [0,1] of correspondences between "this" and the "otherMap" map, whose 6D pose relative to "this" is "otherMapPose" In the case of a multi-metric map, this returns the average between the maps.">compute3DMatchingRatio</a>( <a name="l00230"></a>00230 <span class="keyword">const</span> <a class="code" href="classmrpt_1_1slam_1_1_c_metric_map.html" title="Declares a virtual base class for all metric maps storage classes.">CMetricMap</a> *otherMap, <a name="l00231"></a>00231 <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">CPose3D</a> &otherMapPose, <a name="l00232"></a>00232 <span class="keywordtype">float</span> minDistForCorr = 0.10f, <a name="l00233"></a>00233 <span class="keywordtype">float</span> minMahaDistForCorr = 2.0f <a name="l00234"></a>00234 ) <span class="keyword">const</span>; <a name="l00235"></a>00235 <a name="l00236"></a>00236 <span class="comment"></span> <a name="l00237"></a>00237 <span class="comment"> /** The implementation in this class just calls all the corresponding method of the contained metric maps.</span> <a name="l00238"></a>00238 <span class="comment"> */</span> <a name="l00239"></a>00239 <span class="keyword">virtual</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a8c58a41751a103962401f5f2768e0bc8" title="The implementation in this class just calls all the corresponding method of the contained metric maps...">saveMetricMapRepresentationToFile</a>( <a name="l00240"></a>00240 <span class="keyword">const</span> <a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a> &filNamePrefix <a name="l00241"></a>00241 ) <span class="keyword">const</span>; <a name="l00242"></a>00242 <span class="comment"></span> <a name="l00243"></a>00243 <span class="comment"> /** Save a matlab ".m" file which represents as 3D surfaces the mean and a given confidence level for the concentration of each cell.</span> <a name="l00244"></a>00244 <span class="comment"> * This method can only be called in a KF map model.</span> <a name="l00245"></a>00245 <span class="comment"> * \sa getAsMatlab3DGraphScript</span> <a name="l00246"></a>00246 <span class="comment"> */</span> <a name="l00247"></a>00247 <span class="keyword">virtual</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a2d24916fa541757e2fc02a5da12ec9ff" title="Save a matlab ".m" file which represents as 3D surfaces the mean and a given confidence level for the...">saveAsMatlab3DGraph</a>(<span class="keyword">const</span> <a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a> &filName) <span class="keyword">const</span>; <a name="l00248"></a>00248 <span class="comment"></span> <a name="l00249"></a>00249 <span class="comment"> /** Return a large text block with a MATLAB script to plot the contents of this map \sa saveAsMatlab3DGraph</span> <a name="l00250"></a>00250 <span class="comment"> * This method can only be called in a KF map model.</span> <a name="l00251"></a>00251 <span class="comment"> */</span> <a name="l00252"></a>00252 <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#aabe9a9913d0f135abd54ead888787281" title="Return a large text block with a MATLAB script to plot the contents of this map.">getAsMatlab3DGraphScript</a>(<a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a> &out_script) <span class="keyword">const</span>; <a name="l00253"></a>00253 <span class="comment"></span> <a name="l00254"></a>00254 <span class="comment"> /** Returns a 3D object representing the map.</span> <a name="l00255"></a>00255 <span class="comment"> */</span> <a name="l00256"></a>00256 <span class="keyword">virtual</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a2fa4c22d128c7d97a2df7311b52fde71" title="Returns a 3D object representing the map.">getAs3DObject</a> ( <a class="code" href="structmrpt_1_1opengl_1_1_c_set_of_objects_ptr.html">mrpt::opengl::CSetOfObjectsPtr</a> &outObj ) <span class="keyword">const</span>; <a name="l00257"></a>00257 <span class="comment"></span> <a name="l00258"></a>00258 <span class="comment"> /** Return the type of the random-field grid map, according to parameters passed on construction.</span> <a name="l00259"></a>00259 <span class="comment"> */</span> <a name="l00260"></a>00260 <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a1bdb0ec64ac5ebc8f0b803b66151703a" title="The type of map representation to be used.">TMapRepresentation</a> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#ae6db1a79c4966b3ad989011ef9cea9df" title="Return the type of the random-field grid map, according to parameters passed on construction.">getMapType</a>(); <a name="l00261"></a>00261 <span class="comment"></span> <a name="l00262"></a>00262 <span class="comment"> /** Returns the prediction of the measurement at some (x,y) coordinates, and its certainty (in the form of the expected variance).</span> <a name="l00263"></a>00263 <span class="comment"> * This methods is implemented differently for the different gas map types.</span> <a name="l00264"></a>00264 <span class="comment"> */</span> <a name="l00265"></a>00265 <span class="keyword">virtual</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#af5432ab6a12bdadea34f1940f02e8f07" title="Returns the prediction of the measurement at some (x,y) coordinates, and its certainty (in the form o...">predictMeasurement</a>( <a name="l00266"></a>00266 <span class="keyword">const</span> <span class="keywordtype">double</span> &x, <a name="l00267"></a>00267 <span class="keyword">const</span> <span class="keywordtype">double</span> &<a class="code" href="namespace_eigen_1_1internal.html#a3d7a581aeb951248dc6fe114e9e05f07">y</a>, <a name="l00268"></a>00268 <span class="keywordtype">double</span> &out_predict_response, <a name="l00269"></a>00269 <span class="keywordtype">double</span> &out_predict_response_variance ); <a name="l00270"></a>00270 <span class="comment"></span> <a name="l00271"></a>00271 <span class="comment"> /** Return the mean and covariance vector of the full Kalman filter estimate (works for all KF-based methods). */</span> <a name="l00272"></a>00272 <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a42d516517b992a3e652d5cd26a1dedf6" title="Return the mean and covariance vector of the full Kalman filter estimate (works for all KF-based meth...">getMeanAndCov</a>( <a class="code" href="structmrpt_1_1dynamicsize__vector.html" title="The base class of MRPT vectors, actually, Eigen column matrices of dynamic size with specialized cons...">vector_double</a> &out_means, <a class="code" href="classmrpt_1_1math_1_1_c_matrix_template_numeric.html" title="A matrix of dynamic size.">CMatrixDouble</a> &out_cov) <span class="keyword">const</span>; <a name="l00273"></a>00273 <a name="l00274"></a>00274 <span class="keyword">protected</span>:<span class="comment"></span> <a name="l00275"></a>00275 <span class="comment"> /** Common options to all random-field grid maps: pointer that is set to the derived-class instance of "insertOptions" upon construction of this class. */</span> <a name="l00276"></a><a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#afaaa020b87fd1dd95f86de61512faed3">00276</a> <a class="code" href="structmrpt_1_1slam_1_1_c_random_field_grid_map2_d_1_1_t_insertion_options_common.html" title="Parameters common to any derived class.">TInsertionOptionsCommon</a> * <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#afaaa020b87fd1dd95f86de61512faed3" title="Common options to all random-field grid maps: pointer that is set to the derived-class instance of "i...">m_insertOptions_common</a>; <a name="l00277"></a>00277 <span class="comment"></span> <a name="l00278"></a>00278 <span class="comment"> /** Get the part of the options common to all CRandomFieldGridMap2D classes */</span> <a name="l00279"></a>00279 <span class="keyword">virtual</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html" title="CRandomFieldGridMap2D represents a 2D grid map where each cell is associated one real-valued property...">CRandomFieldGridMap2D</a><a class="code" href="structmrpt_1_1slam_1_1_c_random_field_grid_map2_d_1_1_t_insertion_options_common.html" title="Parameters common to any derived class.">::TInsertionOptionsCommon</a>* <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a832c1f4446f52bef49d0b9c12aac23bd" title="Get the part of the options common to all CRandomFieldGridMap2D classes.">getCommonInsertOptions</a>() = 0; <a name="l00280"></a>00280 <span class="comment"></span> <a name="l00281"></a>00281 <span class="comment"> /** The map representation type of this map, as passed in the constructor */</span> <a name="l00282"></a><a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#ac708ec88c7f83b1f55292d338b4597d3">00282</a> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a1bdb0ec64ac5ebc8f0b803b66151703a" title="The type of map representation to be used.">TMapRepresentation</a> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#ac708ec88c7f83b1f55292d338b4597d3" title="The map representation type of this map, as passed in the constructor.">m_mapType</a>; <a name="l00283"></a>00283 <a name="l00284"></a><a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a835c94b79ca4037c4a49638fd69049a9">00284</a> <a class="code" href="classmrpt_1_1math_1_1_c_matrix_d.html" title="This class is a "CSerializable" wrapper for "CMatrixTemplateNumeric<double>".">CMatrixD</a> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a835c94b79ca4037c4a49638fd69049a9" title="The whole covariance matrix, used for the Kalman Filter map representation.">m_cov</a>; <span class="comment">//!< The whole covariance matrix, used for the Kalman Filter map representation.</span> <a name="l00285"></a>00285 <span class="comment"></span><span class="comment"></span> <a name="l00286"></a>00286 <span class="comment"> /** The compressed band diagonal matrix for the KF2 implementation.</span> <a name="l00287"></a>00287 <span class="comment"> * The format is a Nx(W^2+2W+1) matrix, one row per cell in the grid map with the</span> <a name="l00288"></a>00288 <span class="comment"> * cross-covariances between each cell and half of the window around it in the grid.</span> <a name="l00289"></a>00289 <span class="comment"> */</span> <a name="l00290"></a><a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a420cf955fe634e3c3809cce95c29b14f">00290</a> <a class="code" href="classmrpt_1_1math_1_1_c_matrix_d.html" title="This class is a "CSerializable" wrapper for "CMatrixTemplateNumeric<double>".">CMatrixD</a> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a420cf955fe634e3c3809cce95c29b14f" title="The compressed band diagonal matrix for the KF2 implementation.">m_stackedCov</a>; <a name="l00291"></a><a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#ab03b2e1abfd332618cdf4c27f335d688">00291</a> <span class="keyword">mutable</span> <span class="keywordtype">bool</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#ab03b2e1abfd332618cdf4c27f335d688" title="Only for the KF2 implementation.">m_hasToRecoverMeanAndCov</a>; <span class="comment">//!< Only for the KF2 implementation.</span> <a name="l00292"></a>00292 <span class="comment"></span><span class="comment"></span> <a name="l00293"></a>00293 <span class="comment"> /** @name Auxiliary vars for DM & DM+V methods</span> <a name="l00294"></a>00294 <span class="comment"> @{ */</span> <a name="l00295"></a><a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#aaffe8baacca2ecea8fbf65d1a33839cb">00295</a> <span class="keywordtype">float</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#aaffe8baacca2ecea8fbf65d1a33839cb">m_DM_lastCutOff</a>; <a name="l00296"></a><a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a01e5b4ea2c6d1c51ececad2f07829324">00296</a> std<a class="code" href="classstd_1_1vector.html">::vector<float></a> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a01e5b4ea2c6d1c51ececad2f07829324">m_DM_gaussWindow</a>; <a name="l00297"></a><a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#af8ef1584cd3d129dad99299c08c0fa77">00297</a> <span class="keywordtype">double</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a84197bd6e66dd5812150812e945d3d33">m_average_normreadings_mean</a>, <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#af8ef1584cd3d129dad99299c08c0fa77">m_average_normreadings_var</a>; <a name="l00298"></a><a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a1976b75b9ce20b44bc4eb70d97fac7fa">00298</a> <span class="keywordtype">size_t</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a1976b75b9ce20b44bc4eb70d97fac7fa">m_average_normreadings_count</a>;<span class="comment"></span> <a name="l00299"></a>00299 <span class="comment"> /** @} */</span> <a name="l00300"></a>00300 <span class="comment"></span> <a name="l00301"></a>00301 <span class="comment"> /** The implementation of "insertObservation" for Achim Lilienthal's map models DM & DM+V.</span> <a name="l00302"></a>00302 <span class="comment"> * \param normReading Is a [0,1] normalized concentration reading.</span> <a name="l00303"></a>00303 <span class="comment"> * \param sensorPose Is the sensor pose on the robot</span> <a name="l00304"></a>00304 <span class="comment"> * \param is_DMV = false -> map type is Kernel DM; true -> map type is DM+V</span> <a name="l00305"></a>00305 <span class="comment"> */</span> <a name="l00306"></a>00306 <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a76dee0556409f170b6de842670876310" title="The implementation of "insertObservation" for Achim Lilienthal's map models DM & DM+V...">insertObservation_KernelDM_DMV</a>( <a name="l00307"></a>00307 <span class="keywordtype">float</span> normReading, <a name="l00308"></a>00308 <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">CPose3D</a> &sensorPose, <a name="l00309"></a>00309 <span class="keywordtype">bool</span> is_DMV ); <a name="l00310"></a>00310 <span class="comment"></span> <a name="l00311"></a>00311 <span class="comment"> /** The implementation of "insertObservation" for the (whole) Kalman Filter map model.</span> <a name="l00312"></a>00312 <span class="comment"> * \param normReading Is a [0,1] normalized concentration reading.</span> <a name="l00313"></a>00313 <span class="comment"> * \param sensorPose Is the sensor pose</span> <a name="l00314"></a>00314 <span class="comment"> */</span> <a name="l00315"></a>00315 <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a683f55b585d646b2a621113166e3e413" title="The implementation of "insertObservation" for the (whole) Kalman Filter map model.">insertObservation_KF</a>( <a name="l00316"></a>00316 <span class="keywordtype">float</span> normReading, <a name="l00317"></a>00317 <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">CPose3D</a> &sensorPose ); <a name="l00318"></a>00318 <span class="comment"></span> <a name="l00319"></a>00319 <span class="comment"> /** The implementation of "insertObservation" for the Efficient Kalman Filter map model.</span> <a name="l00320"></a>00320 <span class="comment"> * \param normReading Is a [0,1] normalized concentration reading.</span> <a name="l00321"></a>00321 <span class="comment"> * \param sensorPose Is the sensor pose</span> <a name="l00322"></a>00322 <span class="comment"> */</span> <a name="l00323"></a>00323 <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a00d03cf9798e2930e20666204d09e652" title="The implementation of "insertObservation" for the Efficient Kalman Filter map model.">insertObservation_KF2</a>( <a name="l00324"></a>00324 <span class="keywordtype">float</span> normReading, <a name="l00325"></a>00325 <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">CPose3D</a> &sensorPose ); <a name="l00326"></a>00326 <span class="comment"></span> <a name="l00327"></a>00327 <span class="comment"> /** Computes the average cell concentration, or the overall average value if it has never been observed */</span> <a name="l00328"></a>00328 <span class="keywordtype">double</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#af2bfb86feb6aeebfb36a6ef4ca9f46ef" title="Computes the average cell concentration, or the overall average value if it has never been observed...">computeMeanCellValue_DM_DMV</a> (<span class="keyword">const</span> <a class="code" href="structmrpt_1_1slam_1_1_t_random_field_cell.html" title="The contents of each cell in a CRandomFieldGridMap2D map.">TRandomFieldCell</a> *cell ) <span class="keyword">const</span>; <a name="l00329"></a>00329 <span class="comment"></span> <a name="l00330"></a>00330 <span class="comment"> /** Computes the estimated variance of the cell concentration, or the overall average variance if it has never been observed */</span> <a name="l00331"></a>00331 <span class="keywordtype">double</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#aeff0d652dea1426a3e4a332c2c44f532" title="Computes the estimated variance of the cell concentration, or the overall average variance if it has ...">computeVarCellValue_DM_DMV</a> (<span class="keyword">const</span> <a class="code" href="structmrpt_1_1slam_1_1_t_random_field_cell.html" title="The contents of each cell in a CRandomFieldGridMap2D map.">TRandomFieldCell</a> *cell ) <span class="keyword">const</span>; <a name="l00332"></a>00332 <span class="comment"></span> <a name="l00333"></a>00333 <span class="comment"> /** In the KF2 implementation, takes the auxiliary matrices and from them update the cells' mean and std values.</span> <a name="l00334"></a>00334 <span class="comment"> * \sa m_hasToRecoverMeanAndCov</span> <a name="l00335"></a>00335 <span class="comment"> */</span> <a name="l00336"></a>00336 <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#ae0efc7ac2c68687c98128ef15a84bf2e" title="In the KF2 implementation, takes the auxiliary matrices and from them update the cells' mean and std ...">recoverMeanAndCov</a>() <span class="keyword">const</span>; <a name="l00337"></a>00337 <span class="comment"></span> <a name="l00338"></a>00338 <span class="comment"> /** Erase all the contents of the map */</span> <a name="l00339"></a>00339 <span class="keyword">virtual</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a9624bf853d1a300ea645d0d742f969c1" title="Erase all the contents of the map.">internal_clear</a>(); <a name="l00340"></a>00340 <a name="l00341"></a>00341 }; <a name="l00342"></a>00342 <a name="l00343"></a>00343 <a name="l00344"></a>00344 } <span class="comment">// End of namespace</span> <a name="l00345"></a>00345 <a name="l00346"></a>00346 <a name="l00347"></a>00347 <span class="comment">// Specializations MUST occur at the same namespace:</span> <a name="l00348"></a>00348 <span class="keyword">namespace </span>utils <a name="l00349"></a>00349 { <a name="l00350"></a>00350 <span class="keyword">template</span> <> <a name="l00351"></a>00351 <span class="keyword">struct </span><a class="code" href="structmrpt_1_1utils_1_1_t_enum_type_filler.html" title="Only specializations of this class are defined for each enum type of interest.">TEnumTypeFiller</a><slam::CRandomFieldGridMap2D::TMapRepresentation> <a name="l00352"></a>00352 { <a name="l00353"></a><a class="code" href="structmrpt_1_1utils_1_1_t_enum_type_filler_3_01slam_1_1_c_random_field_grid_map2_d_1_1_t_map_representation_01_4.html#a6c82c7e44db1e8ef142190897d330b71">00353</a> <span class="keyword">typedef</span> slam<a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a1bdb0ec64ac5ebc8f0b803b66151703a" title="The type of map representation to be used.">::CRandomFieldGridMap2D::TMapRepresentation</a> <a class="code" href="structmrpt_1_1utils_1_1_t_enum_type_filler_3_01slam_1_1_c_random_field_grid_map2_d_1_1_t_map_representation_01_4.html#a6c82c7e44db1e8ef142190897d330b71">enum_t</a>; <a name="l00354"></a><a class="code" href="structmrpt_1_1utils_1_1_t_enum_type_filler_3_01slam_1_1_c_random_field_grid_map2_d_1_1_t_map_representation_01_4.html#a6620b9df4296dd677247d4b7250e5d69">00354</a> <span class="keyword">static</span> <span class="keywordtype">void</span> <a class="code" href="eigen__plugins_8h.html#a57fce471b07c3c84924883b5e17e2388">fill</a>(<a class="code" href="classmrpt_1_1utils_1_1bimap.html" title="A bidirectional version of std::map, declared as bimap<KEY,VALUE> and which actually contains two std::...">bimap<enum_t,std::string></a> &m_map) <a name="l00355"></a>00355 { <a name="l00356"></a>00356 m_map.<a class="code" href="classmrpt_1_1utils_1_1bimap.html#af21e6b0fcd4c2046adf6e6a9a9b3c997" title="Insert a new pair KEY<->VALUE in the bi-map.">insert</a>(<a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a1bdb0ec64ac5ebc8f0b803b66151703aa74922fc75f39ecce9f2f53a6fd1af7cc">slam::CRandomFieldGridMap2D::mrKernelDM</a>, <span class="stringliteral">"mrKernelDM"</span>); <a name="l00357"></a>00357 m_map.<a class="code" href="classmrpt_1_1utils_1_1bimap.html#af21e6b0fcd4c2046adf6e6a9a9b3c997" title="Insert a new pair KEY<->VALUE in the bi-map.">insert</a>(<a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a1bdb0ec64ac5ebc8f0b803b66151703aa65b92bd320f8b9834cbe5554b7f2a4c0">slam::CRandomFieldGridMap2D::mrKalmanFilter</a>, <span class="stringliteral">"mrKalmanFilter"</span>); <a name="l00358"></a>00358 m_map.<a class="code" href="classmrpt_1_1utils_1_1bimap.html#af21e6b0fcd4c2046adf6e6a9a9b3c997" title="Insert a new pair KEY<->VALUE in the bi-map.">insert</a>(<a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a1bdb0ec64ac5ebc8f0b803b66151703aaa58f7d260813aa09d312883dee48d56b">slam::CRandomFieldGridMap2D::mrKalmanApproximate</a>, <span class="stringliteral">"mrKalmanApproximate"</span>); <a name="l00359"></a>00359 m_map.<a class="code" href="classmrpt_1_1utils_1_1bimap.html#af21e6b0fcd4c2046adf6e6a9a9b3c997" title="Insert a new pair KEY<->VALUE in the bi-map.">insert</a>(<a class="code" href="classmrpt_1_1slam_1_1_c_random_field_grid_map2_d.html#a1bdb0ec64ac5ebc8f0b803b66151703aab63874317f7204696d76c86b89beed16">slam::CRandomFieldGridMap2D::mrKernelDMV</a>, <span class="stringliteral">"mrKernelDMV"</span>); <a name="l00360"></a>00360 } <a name="l00361"></a>00361 }; <a name="l00362"></a>00362 } <span class="comment">// End of namespace</span> <a name="l00363"></a>00363 } <span class="comment">// End of namespace</span> <a name="l00364"></a>00364 <a name="l00365"></a>00365 <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>