<!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>CDynamicGrid.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">CDynamicGrid.h</div> </div> </div> <div class="contents"> <a href="_c_dynamic_grid_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 <span class="preprocessor">#ifndef CDynamicGrid_H</span> <a name="l00029"></a>00029 <span class="preprocessor"></span><span class="preprocessor">#define CDynamicGrid_H</span> <a name="l00030"></a>00030 <span class="preprocessor"></span> <a name="l00031"></a>00031 <span class="preprocessor">#include <<a class="code" href="utils__defs_8h.html">mrpt/utils/utils_defs.h</a>></span> <a name="l00032"></a>00032 <a name="l00033"></a>00033 <span class="keyword">namespace </span>mrpt <a name="l00034"></a>00034 { <a name="l00035"></a>00035 <span class="keyword">namespace </span>utils <a name="l00036"></a>00036 { <a name="l00037"></a>00037 <span class="keyword">using namespace </span>mrpt::system; <a name="l00038"></a>00038 <span class="comment"></span> <a name="l00039"></a>00039 <span class="comment"> /** A 2D grid of dynamic size which stores any kind of data at each cell.</span> <a name="l00040"></a>00040 <span class="comment"> * \tparam T The type of each cell in the 2D grid.</span> <a name="l00041"></a>00041 <span class="comment"> * \ingroup mrpt_base_grp</span> <a name="l00042"></a>00042 <span class="comment"> */</span> <a name="l00043"></a>00043 <span class="keyword">template</span> <<span class="keyword">class</span> T> <a name="l00044"></a>00044 <span class="keyword">class </span>CDynamicGrid <a name="l00045"></a>00045 { <a name="l00046"></a>00046 <span class="keyword">protected</span>:<span class="comment"></span> <a name="l00047"></a>00047 <span class="comment"> /** The cells.</span> <a name="l00048"></a>00048 <span class="comment"> */</span> <a name="l00049"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#a44e35967e6dfa4a1d4ea877310c10ebb">00049</a> std<a class="code" href="classstd_1_1vector.html">::vector<T></a> <a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#a44e35967e6dfa4a1d4ea877310c10ebb" title="The cells.">m_map</a>; <a name="l00050"></a>00050 <span class="comment"></span> <a name="l00051"></a>00051 <span class="comment"> /** Used only from logically const method that really need to modify the object */</span> <a name="l00052"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#aa99e6b75ba0d986dd68df5342d9a16e3">00052</a> <span class="keyword">inline</span> std<a class="code" href="classstd_1_1vector.html">::vector<T></a> & <a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#aa99e6b75ba0d986dd68df5342d9a16e3" title="Used only from logically const method that really need to modify the object.">m_map_castaway_const</a>()<span class="keyword"> const </span>{ <span class="keywordflow">return</span> <span class="keyword">const_cast<</span> <a class="code" href="classstd_1_1vector.html" title="STL class.">std::vector</a><T<span class="keyword">></span>& >( m_map ); } <a name="l00053"></a>00053 <a name="l00054"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#ac6e709aef8fdbb23f8c24ce61ae93a9e">00054</a> <span class="keywordtype">float</span> m_x_min,m_x_max,<a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#ac6e709aef8fdbb23f8c24ce61ae93a9e">m_y_min</a>,m_y_max; <a name="l00055"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#a0d8fd68a29ddbdd0b4b635ef4a082357">00055</a> <span class="keywordtype">float</span> <a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#a0d8fd68a29ddbdd0b4b635ef4a082357">m_resolution</a>; <a name="l00056"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#aa60d1d0c9e789f4201cda9974dfe36df">00056</a> <span class="keywordtype">size_t</span> m_size_x, <a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#aa60d1d0c9e789f4201cda9974dfe36df">m_size_y</a>; <a name="l00057"></a>00057 <a name="l00058"></a>00058 <span class="keyword">public</span>:<span class="comment"></span> <a name="l00059"></a>00059 <span class="comment"> /** Constructor</span> <a name="l00060"></a>00060 <span class="comment"> */</span> <a name="l00061"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#a4e83ea4f58802ec24fc8db7079ec3261">00061</a> <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>( <span class="keywordtype">float</span> x_min = -10.0f, <a name="l00062"></a>00062 <span class="keywordtype">float</span> x_max = 10.0f, <a name="l00063"></a>00063 <span class="keywordtype">float</span> y_min = -10.0f, <a name="l00064"></a>00064 <span class="keywordtype">float</span> y_max = 10.0f, <a name="l00065"></a>00065 <span class="keywordtype">float</span> resolution = 0.10f) : <a name="l00066"></a>00066 m_map(), <a name="l00067"></a>00067 m_x_min(),m_x_max(),m_y_min(),m_y_max(), <a name="l00068"></a>00068 m_resolution(), <a name="l00069"></a>00069 m_size_x(), m_size_y() <a name="l00070"></a>00070 { <a name="l00071"></a>00071 <a class="code" href="eigen__plugins_8h.html#a8133077108cd44f617e7784243eb5db9" title="Changes the size of matrix, maintaining its previous content as possible and padding with zeros where...">setSize</a>(x_min,x_max,y_min,y_max,resolution); <a name="l00072"></a>00072 } <a name="l00073"></a>00073 <span class="comment"></span> <a name="l00074"></a>00074 <span class="comment"> /** Destructor</span> <a name="l00075"></a>00075 <span class="comment"> */</span> <a name="l00076"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#a2da2fc0f47074f8daa716a72a1418b44">00076</a> <span class="keyword">virtual</span> ~<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>() <a name="l00077"></a>00077 { <a name="l00078"></a>00078 } <a name="l00079"></a>00079 <span class="comment"></span> <a name="l00080"></a>00080 <span class="comment"> /** Changes the size of the grid, ERASING all previous contents.</span> <a name="l00081"></a>00081 <span class="comment"> * \sa resize</span> <a name="l00082"></a>00082 <span class="comment"> */</span> <a name="l00083"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#a926be9ff11d4f3a8f5553262b8fcacd9">00083</a> <span class="keywordtype">void</span> <a class="code" href="eigen__plugins_8h.html#a8133077108cd44f617e7784243eb5db9" title="Changes the size of matrix, maintaining its previous content as possible and padding with zeros where...">setSize</a>( <span class="keywordtype">float</span> x_min, <a name="l00084"></a>00084 <span class="keywordtype">float</span> x_max, <a name="l00085"></a>00085 <span class="keywordtype">float</span> y_min, <a name="l00086"></a>00086 <span class="keywordtype">float</span> y_max, <a name="l00087"></a>00087 <span class="keywordtype">float</span> resolution ) <a name="l00088"></a>00088 { <a name="l00089"></a>00089 <span class="comment">// Adjust sizes to adapt them to full sized cells acording to the resolution:</span> <a name="l00090"></a>00090 m_x_min = resolution*<a class="code" href="namespacemrpt_1_1utils.html#ab7d9cdf7d271c2f41fc1c5c9fa7d0828" title="Returns the closer integer (int) to x.">round</a>(x_min/resolution); <a name="l00091"></a>00091 m_y_min = resolution*<a class="code" href="namespacemrpt_1_1utils.html#ab7d9cdf7d271c2f41fc1c5c9fa7d0828" title="Returns the closer integer (int) to x.">round</a>(y_min/resolution); <a name="l00092"></a>00092 m_x_max = resolution*<a class="code" href="namespacemrpt_1_1utils.html#ab7d9cdf7d271c2f41fc1c5c9fa7d0828" title="Returns the closer integer (int) to x.">round</a>(x_max/resolution); <a name="l00093"></a>00093 m_y_max = resolution*<a class="code" href="namespacemrpt_1_1utils.html#ab7d9cdf7d271c2f41fc1c5c9fa7d0828" title="Returns the closer integer (int) to x.">round</a>(y_max/resolution); <a name="l00094"></a>00094 <a name="l00095"></a>00095 <span class="comment">// Res:</span> <a name="l00096"></a>00096 m_resolution = resolution; <a name="l00097"></a>00097 <a name="l00098"></a>00098 <span class="comment">// Now the number of cells should be integers:</span> <a name="l00099"></a>00099 m_size_x = <a class="code" href="namespacemrpt_1_1utils.html#ab7d9cdf7d271c2f41fc1c5c9fa7d0828" title="Returns the closer integer (int) to x.">round</a>((m_x_max-m_x_min)/m_resolution); <a name="l00100"></a>00100 m_size_y = <a class="code" href="namespacemrpt_1_1utils.html#ab7d9cdf7d271c2f41fc1c5c9fa7d0828" title="Returns the closer integer (int) to x.">round</a>((m_y_max-m_y_min)/m_resolution); <a name="l00101"></a>00101 <a name="l00102"></a>00102 <span class="comment">// Cells memory:</span> <a name="l00103"></a>00103 m_map.resize(m_size_x*m_size_y); <a name="l00104"></a>00104 } <a name="l00105"></a>00105 <span class="comment"></span> <a name="l00106"></a>00106 <span class="comment"> /** Erase the contents of all the cells.</span> <a name="l00107"></a>00107 <span class="comment"> */</span> <a name="l00108"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#a19b80979cc942fa8d56fa963cf2c88f8">00108</a> <span class="keywordtype">void</span> clear() <a name="l00109"></a>00109 { <a name="l00110"></a>00110 m_map.clear(); <a name="l00111"></a>00111 m_map.resize(m_size_x*m_size_y); <a name="l00112"></a>00112 } <a name="l00113"></a>00113 <span class="comment"></span> <a name="l00114"></a>00114 <span class="comment"> /** Fills all the cells with the same value</span> <a name="l00115"></a>00115 <span class="comment"> */</span> <a name="l00116"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#a1abcf1677e597799ad7572b604f32645">00116</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#a1abcf1677e597799ad7572b604f32645" title="Fills all the cells with the same value.">fill</a>( <span class="keyword">const</span> T& value ) { <a class="code" href="eigen__plugins_8h.html#a57fce471b07c3c84924883b5e17e2388">std::fill</a>(m_map.begin(),m_map.end(),value); } <a name="l00117"></a>00117 <span class="comment"></span> <a name="l00118"></a>00118 <span class="comment"> /** Changes the size of the grid, maintaining previous contents.</span> <a name="l00119"></a>00119 <span class="comment"> * \sa setSize</span> <a name="l00120"></a>00120 <span class="comment"> */</span> <a name="l00121"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#af43d36e226e0c62a03353504bc443556">00121</a> <span class="keyword">virtual</span> <span class="keywordtype">void</span> resize( <a name="l00122"></a>00122 <span class="keywordtype">float</span> new_x_min, <a name="l00123"></a>00123 <span class="keywordtype">float</span> new_x_max, <a name="l00124"></a>00124 <span class="keywordtype">float</span> new_y_min, <a name="l00125"></a>00125 <span class="keywordtype">float</span> new_y_max, <a name="l00126"></a>00126 <span class="keyword">const</span> T& defaultValueNewCells, <a name="l00127"></a>00127 <span class="keywordtype">float</span> additionalMarginMeters = 2.0f ) <a name="l00128"></a>00128 { <a name="l00129"></a>00129 <a class="code" href="mrpt__macros_8h.html#a45b840af519f33816311acdbb28d7c10">MRPT_START</a> <a name="l00130"></a>00130 <a name="l00131"></a>00131 <a class="code" href="mrpt__macros_8h.html#ab76a796755b4c538a2e5b4d15ef9f7e2">MRPT_CHECK_NORMAL_NUMBER</a>(new_x_min) <a name="l00132"></a>00132 <a class="code" href="mrpt__macros_8h.html#ab76a796755b4c538a2e5b4d15ef9f7e2">MRPT_CHECK_NORMAL_NUMBER</a>(new_x_max) <a name="l00133"></a>00133 <a class="code" href="mrpt__macros_8h.html#ab76a796755b4c538a2e5b4d15ef9f7e2">MRPT_CHECK_NORMAL_NUMBER</a>(new_y_min) <a name="l00134"></a>00134 <a class="code" href="mrpt__macros_8h.html#ab76a796755b4c538a2e5b4d15ef9f7e2">MRPT_CHECK_NORMAL_NUMBER</a>(new_y_max) <a name="l00135"></a>00135 <a name="l00136"></a>00136 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> x,<a class="code" href="namespace_eigen_1_1internal.html#a3d7a581aeb951248dc6fe114e9e05f07">y</a>; <a name="l00137"></a>00137 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> extra_x_izq,extra_y_arr,new_size_x=0,new_size_y=0; <a name="l00138"></a>00138 <span class="keyword">typename</span> std<a class="code" href="classstd_1_1vector.html">::vector<T></a> new_map; <a name="l00139"></a>00139 <span class="keyword">typename</span> std<a class="code" href="classstd_1_1vector_1_1iterator.html" title="STL iterator class.">::vector<T>::iterator</a> itSrc,itDst; <a name="l00140"></a>00140 <a name="l00141"></a>00141 <span class="comment">// Is resize really necesary?</span> <a name="l00142"></a>00142 <span class="keywordflow">if</span> (new_x_min>=m_x_min && <a name="l00143"></a>00143 new_y_min>=m_y_min && <a name="l00144"></a>00144 new_x_max<=m_x_max && <a name="l00145"></a>00145 new_y_max<=m_y_max) <span class="keywordflow">return</span>; <a name="l00146"></a>00146 <a name="l00147"></a>00147 <span class="keywordflow">if</span> (new_x_min>m_x_min) new_x_min=m_x_min; <a name="l00148"></a>00148 <span class="keywordflow">if</span> (new_x_max<m_x_max) new_x_max=m_x_max; <a name="l00149"></a>00149 <span class="keywordflow">if</span> (new_y_min>m_y_min) new_y_min=m_y_min; <a name="l00150"></a>00150 <span class="keywordflow">if</span> (new_y_max<m_y_max) new_y_max=m_y_max; <a name="l00151"></a>00151 <a name="l00152"></a>00152 <span class="comment">// Additional margin:</span> <a name="l00153"></a>00153 <span class="keywordflow">if</span> (additionalMarginMeters>0) <a name="l00154"></a>00154 { <a name="l00155"></a>00155 <span class="keywordflow">if</span> (new_x_min<m_x_min) new_x_min= floor(new_x_min-additionalMarginMeters); <a name="l00156"></a>00156 <span class="keywordflow">if</span> (new_x_max>m_x_max) new_x_max= ceil(new_x_max+additionalMarginMeters); <a name="l00157"></a>00157 <span class="keywordflow">if</span> (new_y_min<m_y_min) new_y_min= floor(new_y_min-additionalMarginMeters); <a name="l00158"></a>00158 <span class="keywordflow">if</span> (new_y_max>m_y_max) new_y_max= ceil(new_y_max+additionalMarginMeters); <a name="l00159"></a>00159 } <a name="l00160"></a>00160 <a name="l00161"></a>00161 <span class="comment">// Adjust sizes to adapt them to full sized cells acording to the resolution:</span> <a name="l00162"></a>00162 <span class="keywordflow">if</span> (fabs(new_x_min/m_resolution - <a class="code" href="namespacemrpt_1_1utils.html#ab7d9cdf7d271c2f41fc1c5c9fa7d0828" title="Returns the closer integer (int) to x.">round</a>(new_x_min/m_resolution))>0.05f ) <a name="l00163"></a>00163 new_x_min = m_resolution*<a class="code" href="namespacemrpt_1_1utils.html#ab7d9cdf7d271c2f41fc1c5c9fa7d0828" title="Returns the closer integer (int) to x.">round</a>(new_x_min/m_resolution); <a name="l00164"></a>00164 <span class="keywordflow">if</span> (fabs(new_y_min/m_resolution - <a class="code" href="namespacemrpt_1_1utils.html#ab7d9cdf7d271c2f41fc1c5c9fa7d0828" title="Returns the closer integer (int) to x.">round</a>(new_y_min/m_resolution))>0.05f ) <a name="l00165"></a>00165 new_y_min = m_resolution*<a class="code" href="namespacemrpt_1_1utils.html#ab7d9cdf7d271c2f41fc1c5c9fa7d0828" title="Returns the closer integer (int) to x.">round</a>(new_y_min/m_resolution); <a name="l00166"></a>00166 <span class="keywordflow">if</span> (fabs(new_x_max/m_resolution - <a class="code" href="namespacemrpt_1_1utils.html#ab7d9cdf7d271c2f41fc1c5c9fa7d0828" title="Returns the closer integer (int) to x.">round</a>(new_x_max/m_resolution))>0.05f ) <a name="l00167"></a>00167 new_x_max = m_resolution*<a class="code" href="namespacemrpt_1_1utils.html#ab7d9cdf7d271c2f41fc1c5c9fa7d0828" title="Returns the closer integer (int) to x.">round</a>(new_x_max/m_resolution); <a name="l00168"></a>00168 <span class="keywordflow">if</span> (fabs(new_y_max/m_resolution - <a class="code" href="namespacemrpt_1_1utils.html#ab7d9cdf7d271c2f41fc1c5c9fa7d0828" title="Returns the closer integer (int) to x.">round</a>(new_y_max/m_resolution))>0.05f ) <a name="l00169"></a>00169 new_y_max = m_resolution*<a class="code" href="namespacemrpt_1_1utils.html#ab7d9cdf7d271c2f41fc1c5c9fa7d0828" title="Returns the closer integer (int) to x.">round</a>(new_y_max/m_resolution); <a name="l00170"></a>00170 <a name="l00171"></a>00171 <span class="comment">// Change the map size: Extensions at each side:</span> <a name="l00172"></a>00172 extra_x_izq = <a class="code" href="namespacemrpt_1_1utils.html#ab7d9cdf7d271c2f41fc1c5c9fa7d0828" title="Returns the closer integer (int) to x.">round</a>((m_x_min-new_x_min) / m_resolution); <a name="l00173"></a>00173 extra_y_arr = <a class="code" href="namespacemrpt_1_1utils.html#ab7d9cdf7d271c2f41fc1c5c9fa7d0828" title="Returns the closer integer (int) to x.">round</a>((m_y_min-new_y_min) / m_resolution); <a name="l00174"></a>00174 <a name="l00175"></a>00175 new_size_x = <a class="code" href="namespacemrpt_1_1utils.html#ab7d9cdf7d271c2f41fc1c5c9fa7d0828" title="Returns the closer integer (int) to x.">round</a>((new_x_max-new_x_min) / m_resolution); <a name="l00176"></a>00176 new_size_y = <a class="code" href="namespacemrpt_1_1utils.html#ab7d9cdf7d271c2f41fc1c5c9fa7d0828" title="Returns the closer integer (int) to x.">round</a>((new_y_max-new_y_min) / m_resolution); <a name="l00177"></a>00177 <a name="l00178"></a>00178 <span class="comment">// Reserve new memory:</span> <a name="l00179"></a>00179 new_map.resize(new_size_x*new_size_y,defaultValueNewCells); <a name="l00180"></a>00180 <a name="l00181"></a>00181 <span class="comment">// Copy previous rows:</span> <a name="l00182"></a>00182 <span class="keywordflow">for</span> (y=0;y<m_size_y;y++) <a name="l00183"></a>00183 { <a name="l00184"></a>00184 <span class="keywordflow">for</span> (x=0,itSrc=(m_map.begin()+y*m_size_x),itDst=(new_map.begin()+extra_x_izq + (y+extra_y_arr)*new_size_x); <a name="l00185"></a>00185 x<m_size_x; <a name="l00186"></a>00186 x++,itSrc++,itDst++) <a name="l00187"></a>00187 { <a name="l00188"></a>00188 *itDst = *itSrc; <a name="l00189"></a>00189 } <a name="l00190"></a>00190 } <a name="l00191"></a>00191 <a name="l00192"></a>00192 <span class="comment">// Update the new map limits:</span> <a name="l00193"></a>00193 m_x_min = new_x_min; <a name="l00194"></a>00194 m_x_max = new_x_max; <a name="l00195"></a>00195 m_y_min = new_y_min; <a name="l00196"></a>00196 m_y_max = new_y_max; <a name="l00197"></a>00197 <a name="l00198"></a>00198 m_size_x = new_size_x; <a name="l00199"></a>00199 m_size_y = new_size_y; <a name="l00200"></a>00200 <a name="l00201"></a>00201 <span class="comment">// Keep the new map only:</span> <a name="l00202"></a>00202 m_map.swap(new_map); <a name="l00203"></a>00203 <a name="l00204"></a>00204 <a class="code" href="mrpt__macros_8h.html#a88a917260793b56abd83ad2a0d849eb1">MRPT_END</a> <a name="l00205"></a>00205 <a name="l00206"></a>00206 } <a name="l00207"></a>00207 <span class="comment"></span> <a name="l00208"></a>00208 <span class="comment"> /** Returns a pointer to the contents of a cell given by its coordinates, or NULL if it is out of the map extensions.</span> <a name="l00209"></a>00209 <span class="comment"> */</span> <a name="l00210"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#a5277bca042c6ade6fd67d5c0a8a172f2">00210</a> <span class="keyword">inline</span> T* cellByPos( <span class="keywordtype">float</span> x, <span class="keywordtype">float</span> <a class="code" href="namespace_eigen_1_1internal.html#a3d7a581aeb951248dc6fe114e9e05f07">y</a> ) <a name="l00211"></a>00211 { <a name="l00212"></a>00212 <span class="keywordtype">int</span> cx = x2idx(x); <a name="l00213"></a>00213 <span class="keywordtype">int</span> cy = y2idx(y); <a name="l00214"></a>00214 <a name="l00215"></a>00215 <span class="keywordflow">if</span>( cx<0 || cx>=static_cast<int>(m_size_x) ) <span class="keywordflow">return</span> NULL; <a name="l00216"></a>00216 <span class="keywordflow">if</span>( cy<0 || cy>=static_cast<int>(m_size_y) ) <span class="keywordflow">return</span> NULL; <a name="l00217"></a>00217 <a name="l00218"></a>00218 <span class="keywordflow">return</span> &m_map[ cx + cy*m_size_x ]; <a name="l00219"></a>00219 } <a name="l00220"></a>00220 <span class="comment"></span> <a name="l00221"></a>00221 <span class="comment"> /** Returns a pointer to the contents of a cell given by its coordinates, or NULL if it is out of the map extensions.</span> <a name="l00222"></a>00222 <span class="comment"> */</span> <a name="l00223"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#aebbd206e29754dbdbd3aa1ee37be6dab">00223</a> <span class="keyword">inline</span> <span class="keyword">const</span> T* cellByPos( <span class="keywordtype">float</span> x, <span class="keywordtype">float</span> <a class="code" href="namespace_eigen_1_1internal.html#a3d7a581aeb951248dc6fe114e9e05f07">y</a> )<span class="keyword"> const</span> <a name="l00224"></a>00224 <span class="keyword"> </span>{ <a name="l00225"></a>00225 <span class="keywordtype">int</span> cx = x2idx(x); <a name="l00226"></a>00226 <span class="keywordtype">int</span> cy = y2idx(y); <a name="l00227"></a>00227 <a name="l00228"></a>00228 <span class="keywordflow">if</span>( cx<0 || cx>=static_cast<int>(m_size_x) ) <span class="keywordflow">return</span> NULL; <a name="l00229"></a>00229 <span class="keywordflow">if</span>( cy<0 || cy>=static_cast<int>(m_size_y) ) <span class="keywordflow">return</span> NULL; <a name="l00230"></a>00230 <a name="l00231"></a>00231 <span class="keywordflow">return</span> &m_map[ cx + cy*m_size_x ]; <a name="l00232"></a>00232 } <a name="l00233"></a>00233 <span class="comment"></span> <a name="l00234"></a>00234 <span class="comment"> /** Returns a pointer to the contents of a cell given by its cell indexes, or NULL if it is out of the map extensions.</span> <a name="l00235"></a>00235 <span class="comment"> */</span> <a name="l00236"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#a4781cecfa674b11cd29470a0555a0622">00236</a> <span class="keyword">inline</span> T* cellByIndex( <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> cx, <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> cy ) <a name="l00237"></a>00237 { <a name="l00238"></a>00238 <span class="keywordflow">if</span>( cx>=m_size_x || cy>=m_size_y) <a name="l00239"></a>00239 <span class="keywordflow">return</span> NULL; <a name="l00240"></a>00240 <span class="keywordflow">else</span> <span class="keywordflow">return</span> &m_map[ cx + cy*m_size_x ]; <a name="l00241"></a>00241 } <a name="l00242"></a>00242 <span class="comment"></span> <a name="l00243"></a>00243 <span class="comment"> /** Returns a pointer to the contents of a cell given by its cell indexes, or NULL if it is out of the map extensions.</span> <a name="l00244"></a>00244 <span class="comment"> */</span> <a name="l00245"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#a58d68888956305d5f86f56760922270b">00245</a> <span class="keyword">inline</span> <span class="keyword">const</span> T* cellByIndex( <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> cx, <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> cy )<span class="keyword"> const</span> <a name="l00246"></a>00246 <span class="keyword"> </span>{ <a name="l00247"></a>00247 <span class="keywordflow">if</span>( cx>=m_size_x || cy>=m_size_y) <a name="l00248"></a>00248 <span class="keywordflow">return</span> NULL; <a name="l00249"></a>00249 <span class="keywordflow">else</span> <span class="keywordflow">return</span> &m_map[ cx + cy*m_size_x ]; <a name="l00250"></a>00250 } <a name="l00251"></a>00251 <span class="comment"></span> <a name="l00252"></a>00252 <span class="comment"> /** Returns the horizontal size of grid map in cells count.</span> <a name="l00253"></a>00253 <span class="comment"> */</span> <a name="l00254"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#aeb24078d14768d08d00c1eb79c547ff3">00254</a> <span class="keyword">inline</span> <span class="keywordtype">size_t</span> <a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#aeb24078d14768d08d00c1eb79c547ff3" title="Returns the horizontal size of grid map in cells count.">getSizeX</a>()<span class="keyword"> const </span>{ <span class="keywordflow">return</span> m_size_x; } <a name="l00255"></a>00255 <span class="comment"></span> <a name="l00256"></a>00256 <span class="comment"> /** Returns the vertical size of grid map in cells count.</span> <a name="l00257"></a>00257 <span class="comment"> */</span> <a name="l00258"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#a4d300627ac8a06e1e277292c1b0a711b">00258</a> <span class="keyword">inline</span> <span class="keywordtype">size_t</span> <a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#a4d300627ac8a06e1e277292c1b0a711b" title="Returns the vertical size of grid map in cells count.">getSizeY</a>()<span class="keyword"> const </span>{ <span class="keywordflow">return</span> m_size_y; } <a name="l00259"></a>00259 <span class="comment"></span> <a name="l00260"></a>00260 <span class="comment"> /** Returns the "x" coordinate of left side of grid map.</span> <a name="l00261"></a>00261 <span class="comment"> */</span> <a name="l00262"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#a4056c7f1f93e0ad84b1dc11429080312">00262</a> <span class="keyword">inline</span> <span class="keywordtype">float</span> <a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#a4056c7f1f93e0ad84b1dc11429080312" title="Returns the "x" coordinate of left side of grid map.">getXMin</a>()<span class="keyword">const </span>{ <span class="keywordflow">return</span> m_x_min; } <a name="l00263"></a>00263 <span class="comment"></span> <a name="l00264"></a>00264 <span class="comment"> /** Returns the "x" coordinate of right side of grid map.</span> <a name="l00265"></a>00265 <span class="comment"> */</span> <a name="l00266"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#a5b3ddaf4838deb69402688a149fff54c">00266</a> <span class="keyword">inline</span> <span class="keywordtype">float</span> <a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#a5b3ddaf4838deb69402688a149fff54c" title="Returns the "x" coordinate of right side of grid map.">getXMax</a>()<span class="keyword">const </span>{ <span class="keywordflow">return</span> m_x_max; } <a name="l00267"></a>00267 <span class="comment"></span> <a name="l00268"></a>00268 <span class="comment"> /** Returns the "y" coordinate of top side of grid map.</span> <a name="l00269"></a>00269 <span class="comment"> */</span> <a name="l00270"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#ae0c391b4f19aea09157f837d7fa15a3b">00270</a> <span class="keyword">inline</span> <span class="keywordtype">float</span> <a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#ae0c391b4f19aea09157f837d7fa15a3b" title="Returns the "y" coordinate of top side of grid map.">getYMin</a>()<span class="keyword">const </span>{ <span class="keywordflow">return</span> m_y_min; } <a name="l00271"></a>00271 <span class="comment"></span> <a name="l00272"></a>00272 <span class="comment"> /** Returns the "y" coordinate of bottom side of grid map.</span> <a name="l00273"></a>00273 <span class="comment"> */</span> <a name="l00274"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#aa287d6b8076e7377bb37a4e4194cf9b5">00274</a> <span class="keyword">inline</span> <span class="keywordtype">float</span> <a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#aa287d6b8076e7377bb37a4e4194cf9b5" title="Returns the "y" coordinate of bottom side of grid map.">getYMax</a>()<span class="keyword">const </span>{ <span class="keywordflow">return</span> m_y_max; } <a name="l00275"></a>00275 <span class="comment"></span> <a name="l00276"></a>00276 <span class="comment"> /** Returns the resolution of the grid map.</span> <a name="l00277"></a>00277 <span class="comment"> */</span> <a name="l00278"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#adc2166ca7c775540b668a2f3e81d0ba1">00278</a> <span class="keyword">inline</span> <span class="keywordtype">float</span> <a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#adc2166ca7c775540b668a2f3e81d0ba1" title="Returns the resolution of the grid map.">getResolution</a>()<span class="keyword">const </span>{ <span class="keywordflow">return</span> m_resolution; } <a name="l00279"></a>00279 <span class="comment"></span> <a name="l00280"></a>00280 <span class="comment"> /** The user must implement this in order to provide "saveToTextFile" a way to convert each cell into a numeric value */</span> <a name="l00281"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#ab1cff5e8d8397872ca5628ebeec4bb64">00281</a> <span class="keyword">virtual</span> <span class="keywordtype">float</span> cell2float(<span class="keyword">const</span> T& c)<span class="keyword"> const</span> <a name="l00282"></a>00282 <span class="keyword"> </span>{ <a name="l00283"></a>00283 <span class="keywordflow">return</span> 0; <a name="l00284"></a>00284 } <a name="l00285"></a>00285 <a name="l00286"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#ad4a3fca506c6391411806f563de64047">00286</a> <span class="keywordtype">void</span> <a class="code" href="eigen__plugins_8h.html#abea6659e38ab7a50b625ea1a4af3ec72" title="Save matrix to a text file, compatible with MATLAB text format (see also the methods of matrix classe...">saveToTextFile</a>(<span class="keyword">const</span> <a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a> &fileName)<span class="keyword"> const</span> <a name="l00287"></a>00287 <span class="keyword"> </span>{ <a name="l00288"></a>00288 FILE *f=<a class="code" href="group__mrpt__system__os.html#ga9b309cf44c48a430f3c70524e7492108" title="An OS-independent version of fopen.">os::fopen</a>(fileName.c_str(),<span class="stringliteral">"wt"</span>); <a name="l00289"></a>00289 <span class="keywordflow">if</span>(!f) <span class="keywordflow">return</span>; <a name="l00290"></a>00290 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> cy=0;cy<m_size_y;cy++) <a name="l00291"></a>00291 { <a name="l00292"></a>00292 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> cx=0;cx<m_size_x;cx++) <a name="l00293"></a>00293 <a class="code" href="group__mrpt__system__os.html#ga4cc3a0ea9b292a90300224b00e1c8fac" title="An OS-independent version of fprintf.">os::fprintf</a>(f,<span class="stringliteral">"%f "</span>,cell2float(m_map[ cx + cy*m_size_x ])); <a name="l00294"></a>00294 <a class="code" href="group__mrpt__system__os.html#ga4cc3a0ea9b292a90300224b00e1c8fac" title="An OS-independent version of fprintf.">os::fprintf</a>(f,<span class="stringliteral">"\n"</span>); <a name="l00295"></a>00295 } <a name="l00296"></a>00296 <a class="code" href="group__mrpt__system__os.html#gaf465efb0a560da1737c595780530bddf" title="An OS-independent version of fscanf.">os::fclose</a>(f); <a name="l00297"></a>00297 } <a name="l00298"></a>00298 <span class="comment"></span> <a name="l00299"></a>00299 <span class="comment"> /** Transform a coordinate values into cell indexes.</span> <a name="l00300"></a>00300 <span class="comment"> */</span> <a name="l00301"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#af7c9b186fa24f231178f0b1ccd778ab1">00301</a> <span class="keyword">inline</span> <span class="keywordtype">int</span> <a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#af7c9b186fa24f231178f0b1ccd778ab1" title="Transform a coordinate values into cell indexes.">x2idx</a>(<span class="keywordtype">float</span> x)<span class="keyword"> const </span>{ <span class="keywordflow">return</span> <span class="keyword">static_cast<</span><span class="keywordtype">int</span><span class="keyword">></span>( (x-m_x_min)/m_resolution ); } <a name="l00302"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#af5210a6b58e116584fb7ec391048573b">00302</a> <span class="keyword">inline</span> <span class="keywordtype">int</span> <a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#af5210a6b58e116584fb7ec391048573b">y2idx</a>(<span class="keywordtype">float</span> <a class="code" href="namespace_eigen_1_1internal.html#a3d7a581aeb951248dc6fe114e9e05f07">y</a>)<span class="keyword"> const </span>{ <span class="keywordflow">return</span> <span class="keyword">static_cast<</span><span class="keywordtype">int</span><span class="keyword">></span>( (y-m_y_min)/m_resolution ); } <a name="l00303"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#a63dedb14db1e7363f45ab7c6aed9fdb8">00303</a> <span class="keyword">inline</span> <span class="keywordtype">int</span> <a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#a63dedb14db1e7363f45ab7c6aed9fdb8">xy2idx</a>(<span class="keywordtype">float</span> x,<span class="keywordtype">float</span> <a class="code" href="namespace_eigen_1_1internal.html#a3d7a581aeb951248dc6fe114e9e05f07">y</a>)<span class="keyword"> const </span>{ <span class="keywordflow">return</span> x2idx(x) + y2idx(y)*m_size_x; } <a name="l00304"></a>00304 <span class="comment"></span> <a name="l00305"></a>00305 <span class="comment"> /** Transform a global (linear) cell index value into its corresponding (x,y) cell indexes. */</span> <a name="l00306"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#a20356dae1065b5ed663b08bed36d6f11">00306</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> idx2cxcy(<span class="keyword">const</span> <span class="keywordtype">int</span> &idx, <span class="keywordtype">int</span> &cx, <span class="keywordtype">int</span> &cy )<span class="keyword"> const</span> <a name="l00307"></a>00307 <span class="keyword"> </span>{ <a name="l00308"></a>00308 cx = idx % m_size_x; <a name="l00309"></a>00309 cy = idx / m_size_x; <a name="l00310"></a>00310 } <a name="l00311"></a>00311 <span class="comment"></span> <a name="l00312"></a>00312 <span class="comment"> /** Transform a cell index into a coordinate value.</span> <a name="l00313"></a>00313 <span class="comment"> */</span> <a name="l00314"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#a91a60d42d43bdc6d0174b492521fc5dc">00314</a> <span class="keyword">inline</span> <span class="keywordtype">float</span> <a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#a91a60d42d43bdc6d0174b492521fc5dc" title="Transform a cell index into a coordinate value.">idx2x</a>(<span class="keywordtype">int</span> cx)<span class="keyword"> const </span>{ <span class="keywordflow">return</span> m_x_min+(cx+0.5f)*m_resolution; } <a name="l00315"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#aad004e29d48cd60015f6711f497483fa">00315</a> <span class="keyword">inline</span> <span class="keywordtype">float</span> <a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#aad004e29d48cd60015f6711f497483fa">idx2y</a>(<span class="keywordtype">int</span> cy)<span class="keyword"> const </span>{ <span class="keywordflow">return</span> m_y_min+(cy+0.5f)*m_resolution; } <a name="l00316"></a>00316 <span class="comment"></span> <a name="l00317"></a>00317 <span class="comment"> /** Transform a coordinate value into a cell index, using a diferent "x_min" value</span> <a name="l00318"></a>00318 <span class="comment"> */</span> <a name="l00319"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#ae5f9732fa03110a3a1c801672d073251">00319</a> <span class="keyword">inline</span> <span class="keywordtype">int</span> <a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#ae5f9732fa03110a3a1c801672d073251" title="Transform a coordinate value into a cell index, using a diferent "x_min" value.">x2idx</a>(<span class="keywordtype">float</span> x,<span class="keywordtype">float</span> x_min)<span class="keyword"> const </span>{ <span class="keywordflow">return</span> <span class="keyword">static_cast<</span><span class="keywordtype">int</span><span class="keyword">></span>((x-m_x_min)/m_resolution ); } <a name="l00320"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#a0460a7c8543c6e9f8de28cc5cadfa640">00320</a> <span class="keyword">inline</span> <span class="keywordtype">int</span> <a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#a0460a7c8543c6e9f8de28cc5cadfa640">y2idx</a>(<span class="keywordtype">float</span> <a class="code" href="namespace_eigen_1_1internal.html#a3d7a581aeb951248dc6fe114e9e05f07">y</a>, <span class="keywordtype">float</span> y_min)<span class="keyword"> const </span>{ <span class="keywordflow">return</span> <span class="keyword">static_cast<</span><span class="keywordtype">int</span><span class="keyword">></span>((y-m_y_min)/m_resolution ); } <a name="l00321"></a>00321 <span class="comment"></span> <a name="l00322"></a>00322 <span class="comment"> /** Get the entire grid as a matrix. </span> <a name="l00323"></a>00323 <span class="comment"> * \tparam MAT The type of the matrix, typically a CMatrixDouble.</span> <a name="l00324"></a>00324 <span class="comment"> * \param[out] m The output matrix; will be set automatically to the correct size.</span> <a name="l00325"></a>00325 <span class="comment"> * Entry (cy,cx) in the matrix contains the grid cell with indices (cx,cy).</span> <a name="l00326"></a>00326 <span class="comment"> * \note This method will compile only for cell types that can be converted to the type of the matrix elements (e.g. double).</span> <a name="l00327"></a>00327 <span class="comment"> */</span> <a name="l00328"></a>00328 <span class="keyword">template</span> <<span class="keyword">class</span> MAT> <a name="l00329"></a><a class="code" href="classmrpt_1_1utils_1_1_c_dynamic_grid.html#aad1ca5fdd667b49e78b64c7a6f19a76b">00329</a> <span class="keywordtype">void</span> getAsMatrix(MAT &m)<span class="keyword"> const</span> <a name="l00330"></a>00330 <span class="keyword"> </span>{ <a name="l00331"></a>00331 m.setSize(m_size_y, m_size_x); <a name="l00332"></a>00332 <span class="keywordflow">if</span> (m_map.empty()) <span class="keywordflow">return</span>; <a name="l00333"></a>00333 <span class="keyword">const</span> T* c = &m_map[0]; <a name="l00334"></a>00334 <span class="keywordflow">for</span> (<span class="keywordtype">size_t</span> cy=0;cy<m_size_y;cy++) <a name="l00335"></a>00335 <span class="keywordflow">for</span> (<span class="keywordtype">size_t</span> cx=0;cx<m_size_x;cx++) <a name="l00336"></a>00336 m.set_unsafe(cy,cx, *c++); <a name="l00337"></a>00337 } <a name="l00338"></a>00338 <a name="l00339"></a>00339 }; <a name="l00340"></a>00340 <a name="l00341"></a>00341 } <span class="comment">// End of namespace</span> <a name="l00342"></a>00342 } <span class="comment">// end of namespace</span> <a name="l00343"></a>00343 <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>