<!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>CMetricMap.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">CMetricMap.h</div> </div> </div> <div class="contents"> <a href="_c_metric_map_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 CMetricMap_H</span> <a name="l00029"></a>00029 <span class="preprocessor"></span><span class="preprocessor">#define CMetricMap_H</span> <a name="l00030"></a>00030 <span class="preprocessor"></span> <a name="l00031"></a>00031 <span class="preprocessor">#include <<a class="code" href="_c_serializable_8h.html">mrpt/utils/CSerializable.h</a>></span> <a name="l00032"></a>00032 <span class="preprocessor">#include <<a class="code" href="_c_set_of_objects_8h.html">mrpt/opengl/CSetOfObjects.h</a>></span> <a name="l00033"></a>00033 <a name="l00034"></a>00034 <span class="preprocessor">#include <<a class="code" href="_c_observation_8h.html">mrpt/slam/CObservation.h</a>></span> <a name="l00035"></a>00035 <span class="preprocessor">#include <<a class="code" href="_t_matching_pair_8h.html">mrpt/utils/TMatchingPair.h</a>></span> <a name="l00036"></a>00036 <a name="l00037"></a>00037 <span class="preprocessor">#include <<a class="code" href="_c_point2_d_8h.html">mrpt/poses/CPoint2D.h</a>></span> <a name="l00038"></a>00038 <span class="preprocessor">#include <<a class="code" href="_c_point3_d_8h.html">mrpt/poses/CPoint3D.h</a>></span> <a name="l00039"></a>00039 <span class="preprocessor">#include <<a class="code" href="_c_pose2_d_8h.html">mrpt/poses/CPose2D.h</a>></span> <a name="l00040"></a>00040 <span class="preprocessor">#include <<a class="code" href="_c_pose3_d_8h.html">mrpt/poses/CPose3D.h</a>></span> <a name="l00041"></a>00041 <a name="l00042"></a>00042 <span class="preprocessor">#include <<a class="code" href="_c_observable_8h.html">mrpt/utils/CObservable.h</a>></span> <a name="l00043"></a>00043 <span class="preprocessor">#include <<a class="code" href="_c_metric_map_events_8h.html">mrpt/slam/CMetricMapEvents.h</a>></span> <a name="l00044"></a>00044 <a name="l00045"></a>00045 <span class="keyword">namespace </span>mrpt <a name="l00046"></a>00046 { <a name="l00047"></a>00047 <span class="keyword">namespace </span>slam <a name="l00048"></a>00048 { <a name="l00049"></a>00049 <span class="keyword">using namespace </span>mrpt::utils; <a name="l00050"></a>00050 <a name="l00051"></a>00051 <span class="keyword">class </span>CObservation; <a name="l00052"></a>00052 <span class="keyword">class </span>CPointsMap; <a name="l00053"></a>00053 <span class="keyword">class </span>CSimplePointsMap; <a name="l00054"></a>00054 <span class="keyword">class </span>CSimpleMap; <a name="l00055"></a>00055 <span class="keyword">class </span>CSensoryFrame; <a name="l00056"></a>00056 <a name="l00057"></a><a class="code" href="structmrpt_1_1slam_1_1_c_metric_map_ptr.html#af63deddb9d3837bce394b9916a4de47f">00057</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_metric_map.html" title="Declares a virtual base class for all metric maps storage classes.">CMetricMap</a>, <a class="code" href="classmrpt_1_1utils_1_1_c_serializable.html" title="The virtual base class which provides a unified interface for all persistent objects in MRPT...">mrpt::utils::CSerializable</a>, <a class="code" href="obs_2include_2mrpt_2obs_2link__pragmas_8h.html#ae8bb1b2647c58d6ae2eb30ca31fcf5a1">OBS_IMPEXP</a> ) <a name="l00058"></a>00058 <a name="l00059"></a>00059 <span class="comment">/** Declares a virtual base class for all metric maps storage classes.</span> <a name="l00060"></a>00060 <span class="comment"> In this class virtual methods are provided to allow the insertion</span> <a name="l00061"></a>00061 <span class="comment"> of any type of "CObservation" objects into the metric map, thus</span> <a name="l00062"></a>00062 <span class="comment"> updating the map (doesn't matter if it is a 2D/3D grid or a points</span> <a name="l00063"></a>00063 <span class="comment"> map).</span> <a name="l00064"></a>00064 <span class="comment"> <b>IMPORTANT</b>: Observations doesn't include any information about the</span> <a name="l00065"></a>00065 <span class="comment"> robot pose beliefs, just the raw observation and information about</span> <a name="l00066"></a>00066 <span class="comment"> the sensor pose relative to the robot mobile base coordinates origin.</span> <a name="l00067"></a>00067 <span class="comment"> *</span> <a name="l00068"></a>00068 <span class="comment"> * Note that all metric maps implement this mrpt::utils::CObservable interface,</span> <a name="l00069"></a>00069 <span class="comment"> * emitting the following events:</span> <a name="l00070"></a>00070 <span class="comment"> * - mrpt::slam::mrptEventMetricMapClear: Upon call of the ::clear() method.</span> <a name="l00071"></a>00071 <span class="comment"> * - mrpt::slam::mrptEventMetricMapInsert: Upon insertion of an observation that effectively modifies the map (e.g. inserting an image into a grid map will NOT raise an event, inserting a laser scan will).</span> <a name="l00072"></a>00072 <span class="comment"> *</span> <a name="l00073"></a>00073 <span class="comment"> * \sa CObservation, CSensoryFrame, CMultiMetricMap</span> <a name="l00074"></a>00074 <span class="comment"> * \ingroup mrpt_obs_grp</span> <a name="l00075"></a>00075 <span class="comment"> */</span> <a name="l00076"></a>00076 class <a class="code" href="obs_2include_2mrpt_2obs_2link__pragmas_8h.html#ae8bb1b2647c58d6ae2eb30ca31fcf5a1">OBS_IMPEXP</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 name="l00077"></a>00077 public mrpt::utils::<a class="code" href="classmrpt_1_1utils_1_1_c_serializable.html" title="The virtual base class which provides a unified interface for all persistent objects in MRPT...">CSerializable</a>, <a name="l00078"></a>00078 public mrpt::utils::<a class="code" href="classmrpt_1_1utils_1_1_c_observable.html" title="Inherit from this class for those objects capable of being observed by a CObserver class...">CObservable</a> <a name="l00079"></a>00079 { <a name="l00080"></a>00080 <span class="comment">// This must be added to any CSerializable derived class:</span> <a name="l00081"></a><a class="code" href="classmrpt_1_1slam_1_1_c_metric_map.html#a6fec28a53e20dfc1c4d046c26f9f7b48">00081</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_metric_map.html" title="Declares a virtual base class for all metric maps storage classes.">CMetricMap</a> ) <a name="l00082"></a>00082 <a name="l00083"></a>00083 private:<span class="comment"></span> <a name="l00084"></a>00084 <span class="comment"> /** Internal method called by clear() */</span> <a name="l00085"></a>00085 virtual <span class="keywordtype">void</span> internal_clear() = 0; <a name="l00086"></a>00086 <span class="comment"></span> <a name="l00087"></a>00087 <span class="comment"> /** Hook for each time a "internal_insertObservation" returns "true"</span> <a name="l00088"></a>00088 <span class="comment"> * This is called automatically from insertObservation() when internal_insertObservation returns true.</span> <a name="l00089"></a>00089 <span class="comment"> */</span> <a name="l00090"></a><a class="code" href="classmrpt_1_1slam_1_1_c_metric_map.html#a75f844879662ac04588a1eda33432a77">00090</a> virtual <span class="keywordtype">void</span> OnPostSuccesfulInsertObs(const <a class="code" href="classmrpt_1_1slam_1_1_c_observation.html" title="Declares a class that represents any robot's observation.">CObservation</a> *) <a name="l00091"></a>00091 { <a name="l00092"></a>00092 <span class="comment">// Default: do nothing</span> <a name="l00093"></a>00093 } <a name="l00094"></a>00094 <span class="comment"></span> <a name="l00095"></a>00095 <span class="comment"> /** Internal method called by insertObservation() */</span> <a name="l00096"></a>00096 <span class="keyword">virtual</span> <span class="keywordtype">bool</span> internal_insertObservation( <a name="l00097"></a>00097 <span class="keyword">const</span> <a class="code" href="classmrpt_1_1slam_1_1_c_observation.html" title="Declares a class that represents any robot's observation.">CObservation</a> *obs, <a name="l00098"></a>00098 <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> *robotPose = NULL ) = 0; <a name="l00099"></a>00099 <a name="l00100"></a>00100 <span class="keyword">public</span>:<span class="comment"></span> <a name="l00101"></a>00101 <span class="comment"> /** Erase all the contents of the map */</span> <a name="l00102"></a>00102 <span class="keywordtype">void</span> clear(); <a name="l00103"></a>00103 <span class="comment"></span> <a name="l00104"></a>00104 <span class="comment"> /** Returns true if the map is empty/no observation has been inserted.</span> <a name="l00105"></a>00105 <span class="comment"> */</span> <a name="l00106"></a>00106 <span class="keyword">virtual</span> <span class="keywordtype">bool</span> isEmpty() <span class="keyword">const</span> = 0; <a name="l00107"></a>00107 <span class="comment"></span> <a name="l00108"></a>00108 <span class="comment"> /** Load the map contents from a CSimpleMap object, erasing all previous content of the map.</span> <a name="l00109"></a>00109 <span class="comment"> * This is automaticed invoking "insertObservation" for each observation at the mean 3D robot pose as</span> <a name="l00110"></a>00110 <span class="comment"> * given by the "poses::CPosePDF" in the CSimpleMap object.</span> <a name="l00111"></a>00111 <span class="comment"> *</span> <a name="l00112"></a>00112 <span class="comment"> * \sa insertObservation, CSimpleMap</span> <a name="l00113"></a>00113 <span class="comment"> * \exception std::exception Some internal steps in invoked methods can raise exceptions on invalid parameters, etc...</span> <a name="l00114"></a>00114 <span class="comment"> */</span> <a name="l00115"></a>00115 <span class="keywordtype">void</span> loadFromProbabilisticPosesAndObservations( <span class="keyword">const</span> <a class="code" href="classmrpt_1_1slam_1_1_c_simple_map.html" title="This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs, thus a "metric map" can be t...">CSimpleMap</a> &Map ); <a name="l00116"></a>00116 <span class="comment"></span> <a name="l00117"></a>00117 <span class="comment"> /** Load the map contents from a CSimpleMap object, erasing all previous content of the map.</span> <a name="l00118"></a>00118 <span class="comment"> * This is automaticed invoking "insertObservation" for each observation at the mean 3D robot pose as</span> <a name="l00119"></a>00119 <span class="comment"> * given by the "poses::CPosePDF" in the CSimpleMap object.</span> <a name="l00120"></a>00120 <span class="comment"> *</span> <a name="l00121"></a>00121 <span class="comment"> * \sa insertObservation, CSimpleMap</span> <a name="l00122"></a>00122 <span class="comment"> * \exception std::exception Some internal steps in invoked methods can raise exceptions on invalid parameters, etc...</span> <a name="l00123"></a>00123 <span class="comment"> */</span> <a name="l00124"></a><a class="code" href="classmrpt_1_1slam_1_1_c_metric_map.html#aedf155237d3fe3d595994b9659a4e688">00124</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1slam_1_1_c_metric_map.html#aedf155237d3fe3d595994b9659a4e688" title="Load the map contents from a CSimpleMap object, erasing all previous content of the map...">loadFromSimpleMap</a>( <span class="keyword">const</span> <a class="code" href="classmrpt_1_1slam_1_1_c_simple_map.html" title="This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs, thus a "metric map" can be t...">CSimpleMap</a> &Map ) { loadFromProbabilisticPosesAndObservations(Map); } <a name="l00125"></a>00125 <span class="comment"></span> <a name="l00126"></a>00126 <span class="comment"> /** Insert the observation information into this map. This method must be implemented</span> <a name="l00127"></a>00127 <span class="comment"> * in derived classes.</span> <a name="l00128"></a>00128 <span class="comment"> * \param obs The observation</span> <a name="l00129"></a>00129 <span class="comment"> * \param robotPose The 3D pose of the robot mobile base in the map reference system, or NULL (default) if you want to use the origin.</span> <a name="l00130"></a>00130 <span class="comment"> *</span> <a name="l00131"></a>00131 <span class="comment"> * \sa CObservation::insertObservationInto</span> <a name="l00132"></a>00132 <span class="comment"> */</span> <a name="l00133"></a><a class="code" href="classmrpt_1_1slam_1_1_c_metric_map.html#ad1d3f22228d6dbdb3c31c132713bf782">00133</a> <span class="keyword">inline</span> <span class="keywordtype">bool</span> insertObservation( <a name="l00134"></a>00134 <span class="keyword">const</span> <a class="code" href="classmrpt_1_1slam_1_1_c_observation.html" title="Declares a class that represents any robot's observation.">CObservation</a> *obs, <a name="l00135"></a>00135 <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> *robotPose = NULL ) <a name="l00136"></a>00136 { <a name="l00137"></a>00137 <span class="keywordtype">bool</span> done = internal_insertObservation(obs,robotPose); <a name="l00138"></a>00138 <span class="keywordflow">if</span> (done) <a name="l00139"></a>00139 { <a name="l00140"></a>00140 OnPostSuccesfulInsertObs(obs); <a name="l00141"></a>00141 publishEvent( <a class="code" href="classmrpt_1_1slam_1_1mrpt_event_metric_map_insert.html" title="Event emitted by a metric up upon a succesful call to insertObservation()">mrptEventMetricMapInsert</a>(<span class="keyword">this</span>,obs,robotPose) ); <a name="l00142"></a>00142 } <a name="l00143"></a>00143 <span class="keywordflow">return</span> done; <a name="l00144"></a>00144 } <a name="l00145"></a>00145 <span class="comment"></span> <a name="l00146"></a>00146 <span class="comment"> /** A wrapper for smart pointers, just calls the non-smart pointer version. */</span> <a name="l00147"></a><a class="code" href="classmrpt_1_1slam_1_1_c_metric_map.html#a7cb614f5ec634ec6f6a20b14163e5b07">00147</a> <span class="keyword">inline</span> <span class="keywordtype">bool</span> insertObservationPtr( <a name="l00148"></a>00148 <span class="keyword">const</span> <a class="code" href="structmrpt_1_1slam_1_1_c_observation_ptr.html">CObservationPtr</a> &obs, <a name="l00149"></a>00149 <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> *robotPose = NULL ) <a name="l00150"></a>00150 { <a name="l00151"></a>00151 <a class="code" href="mrpt__macros_8h.html#a45b840af519f33816311acdbb28d7c10">MRPT_START</a> <a name="l00152"></a>00152 <span class="keywordflow">if</span> (!obs.present()) { <a class="code" href="mrpt__macros_8h.html#aaa3f404ea85a6575a7139f8d101370ba">THROW_EXCEPTION</a>(<span class="stringliteral">"Trying to pass a null pointer."</span>); } <a name="l00153"></a>00153 <span class="keywordflow">return</span> insertObservation(obs.<a class="code" href="structmrpt_1_1slam_1_1_c_observation_ptr.html#a1322d521444219cbc75294abdac08440">pointer</a>(),robotPose); <a name="l00154"></a>00154 <a class="code" href="mrpt__macros_8h.html#a88a917260793b56abd83ad2a0d849eb1">MRPT_END</a> <a name="l00155"></a>00155 } <a name="l00156"></a>00156 <span class="comment"></span> <a name="l00157"></a>00157 <span class="comment"> /** Computes the log-likelihood of a given observation given an arbitrary robot 3D pose.</span> <a name="l00158"></a>00158 <span class="comment"> *</span> <a name="l00159"></a>00159 <span class="comment"> * \param takenFrom The robot's pose the observation is supposed to be taken from.</span> <a name="l00160"></a>00160 <span class="comment"> * \param obs The observation.</span> <a name="l00161"></a>00161 <span class="comment"> * \return This method returns a log-likelihood.</span> <a name="l00162"></a>00162 <span class="comment"> *</span> <a name="l00163"></a>00163 <span class="comment"> * \sa Used in particle filter algorithms, see: CMultiMetricMapPDF::update</span> <a name="l00164"></a>00164 <span class="comment"> */</span> <a name="l00165"></a>00165 <span class="keyword">virtual</span> <span class="keywordtype">double</span> computeObservationLikelihood( <span class="keyword">const</span> <a class="code" href="classmrpt_1_1slam_1_1_c_observation.html" title="Declares a class that represents any robot's observation.">CObservation</a> *obs, <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> &takenFrom ) = 0; <a name="l00166"></a>00166 <span class="comment"></span> <a name="l00167"></a>00167 <span class="comment"> /** Computes the log-likelihood of a given observation given an arbitrary robot 2D pose.</span> <a name="l00168"></a>00168 <span class="comment"> *</span> <a name="l00169"></a>00169 <span class="comment"> * \param takenFrom The robot's pose the observation is supposed to be taken from.</span> <a name="l00170"></a>00170 <span class="comment"> * \param obs The observation.</span> <a name="l00171"></a>00171 <span class="comment"> * \return This method returns a log-likelihood.</span> <a name="l00172"></a>00172 <span class="comment"> *</span> <a name="l00173"></a>00173 <span class="comment"> * \sa Used in particle filter algorithms, see: CMultiMetricMapPDF::update</span> <a name="l00174"></a>00174 <span class="comment"> */</span> <a name="l00175"></a><a class="code" href="classmrpt_1_1slam_1_1_c_metric_map.html#a6adfc3df476a7edafaca40444d8dad04">00175</a> <span class="keywordtype">double</span> computeObservationLikelihood( <span class="keyword">const</span> <a class="code" href="classmrpt_1_1slam_1_1_c_observation.html" title="Declares a class that represents any robot's observation.">CObservation</a> *obs, <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose2_d.html" title="A class used to store a 2D pose.">CPose2D</a> &takenFrom ) <a name="l00176"></a>00176 { <a name="l00177"></a>00177 <span class="keywordflow">return</span> computeObservationLikelihood(obs,<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>(takenFrom)); <a name="l00178"></a>00178 } <a name="l00179"></a>00179 <span class="comment"></span> <a name="l00180"></a>00180 <span class="comment"> /** Returns true if this map is able to compute a sensible likelihood function for this observation (i.e. an occupancy grid map cannot with an image).</span> <a name="l00181"></a>00181 <span class="comment"> * \param obs The observation.</span> <a name="l00182"></a>00182 <span class="comment"> * \sa computeObservationLikelihood</span> <a name="l00183"></a>00183 <span class="comment"> */</span> <a name="l00184"></a><a class="code" href="classmrpt_1_1slam_1_1_c_metric_map.html#a8936d61e45446a74633d00a7ce6b4603">00184</a> <span class="keyword">virtual</span> <span class="keywordtype">bool</span> canComputeObservationLikelihood( <span class="keyword">const</span> <a class="code" href="classmrpt_1_1slam_1_1_c_observation.html" title="Declares a class that represents any robot's observation.">CObservation</a> *obs ) <a name="l00185"></a>00185 { <a name="l00186"></a>00186 <span class="keywordflow">return</span> <span class="keyword">true</span>; <span class="comment">// Unless implemented otherwise, we can always compute the likelihood.</span> <a name="l00187"></a>00187 } <a name="l00188"></a>00188 <span class="comment"></span> <a name="l00189"></a>00189 <span class="comment"> /** Returns the sum of the log-likelihoods of each individual observation within a mrpt::slam::CSensoryFrame.</span> <a name="l00190"></a>00190 <span class="comment"> *</span> <a name="l00191"></a>00191 <span class="comment"> * \param takenFrom The robot's pose the observation is supposed to be taken from.</span> <a name="l00192"></a>00192 <span class="comment"> * \param sf The set of observations in a CSensoryFrame.</span> <a name="l00193"></a>00193 <span class="comment"> * \return This method returns a log-likelihood.</span> <a name="l00194"></a>00194 <span class="comment"> * \sa canComputeObservationsLikelihood</span> <a name="l00195"></a>00195 <span class="comment"> */</span> <a name="l00196"></a>00196 <span class="keywordtype">double</span> computeObservationsLikelihood( <span class="keyword">const</span> <a class="code" href="classmrpt_1_1slam_1_1_c_sensory_frame.html" title="Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...">CSensoryFrame</a> &sf, <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose2_d.html" title="A class used to store a 2D pose.">CPose2D</a> &takenFrom ); <a name="l00197"></a>00197 <span class="comment"></span> <a name="l00198"></a>00198 <span class="comment"> /** Returns true if this map is able to compute a sensible likelihood function for this observation (i.e. an occupancy grid map cannot with an image).</span> <a name="l00199"></a>00199 <span class="comment"> * \param sf The observations.</span> <a name="l00200"></a>00200 <span class="comment"> * \sa canComputeObservationLikelihood</span> <a name="l00201"></a>00201 <span class="comment"> */</span> <a name="l00202"></a>00202 <span class="keywordtype">bool</span> canComputeObservationsLikelihood( <span class="keyword">const</span> <a class="code" href="classmrpt_1_1slam_1_1_c_sensory_frame.html" title="Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...">CSensoryFrame</a> &sf ); <a name="l00203"></a>00203 <span class="comment"></span> <a name="l00204"></a>00204 <span class="comment"> /** Constructor</span> <a name="l00205"></a>00205 <span class="comment"> */</span> <a name="l00206"></a>00206 <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 name="l00207"></a>00207 <span class="comment"></span> <a name="l00208"></a>00208 <span class="comment"> /** Destructor</span> <a name="l00209"></a>00209 <span class="comment"> */</span> <a name="l00210"></a>00210 <span class="keyword">virtual</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>(); <a name="l00211"></a>00211 <a name="l00212"></a>00212 <span class="preprocessor">#ifdef MRPT_BACKCOMPATIB_08X // For backward compatibility</span> <a name="l00213"></a>00213 <span class="preprocessor"></span> <span class="keyword">typedef</span> mrpt<a class="code" href="structmrpt_1_1utils_1_1_t_matching_pair.html" title="A structure for holding correspondences between two sets of points or points-like entities in 2D or 3...">::utils::TMatchingPair</a> <a class="code" href="structmrpt_1_1utils_1_1_t_matching_pair.html" title="A structure for holding correspondences between two sets of points or points-like entities in 2D or 3...">TMatchingPair</a>; <a name="l00214"></a>00214 <span class="keyword">typedef</span> mrpt<a class="code" href="structmrpt_1_1utils_1_1_t_matching_pair.html" title="A structure for holding correspondences between two sets of points or points-like entities in 2D or 3...">::utils::TMatchingPairPtr</a> <a class="code" href="namespacemrpt_1_1utils.html#af7beba77b6c2056d9c5d5fd795e7b45d">TMatchingPairPtr</a>; <a name="l00215"></a>00215 <span class="keyword">typedef</span> mrpt<a class="code" href="classmrpt_1_1utils_1_1_t_matching_pair_list.html" title="A list of TMatchingPair.">::utils::TMatchingPairList</a> <a class="code" href="classmrpt_1_1utils_1_1_t_matching_pair_list.html" title="A list of TMatchingPair.">TMatchingPairList</a>; <a name="l00216"></a>00216 <span class="preprocessor">#endif</span> <a name="l00217"></a>00217 <span class="preprocessor"></span><span class="comment"></span> <a name="l00218"></a>00218 <span class="comment"> /** Computes the matchings between this and another 2D points map.</span> <a name="l00219"></a>00219 <span class="comment"> This includes finding:</span> <a name="l00220"></a>00220 <span class="comment"> - The set of points pairs in each map</span> <a name="l00221"></a>00221 <span class="comment"> - The mean squared distance between corresponding pairs.</span> <a name="l00222"></a>00222 <span class="comment"> This method is the most time critical one into the ICP algorithm.</span> <a name="l00223"></a>00223 <span class="comment"></span> <a name="l00224"></a>00224 <span class="comment"> * \param otherMap [IN] The other map to compute the matching with.</span> <a name="l00225"></a>00225 <span class="comment"> * \param otherMapPose [IN] The pose of the other map as seen from "this".</span> <a name="l00226"></a>00226 <span class="comment"> * \param maxDistForCorrespondence [IN] Maximum 2D linear distance between two points to be matched.</span> <a name="l00227"></a>00227 <span class="comment"> * \param maxAngularDistForCorrespondence [IN] In radians: The aim is to allow larger distances to more distant correspondences.</span> <a name="l00228"></a>00228 <span class="comment"> * \param angularDistPivotPoint [IN] The point used to calculate distances from in both maps.</span> <a name="l00229"></a>00229 <span class="comment"> * \param correspondences [OUT] The detected matchings pairs.</span> <a name="l00230"></a>00230 <span class="comment"> * \param correspondencesRatio [OUT] The ratio [0,1] of points in otherMap with at least one correspondence.</span> <a name="l00231"></a>00231 <span class="comment"> * \param sumSqrDist [OUT] The sum of all matched points squared distances.If undesired, set to NULL, as default.</span> <a name="l00232"></a>00232 <span class="comment"> * \param onlyKeepTheClosest [IN] If set to true, only the closest correspondence will be returned. If false (default) all are returned.</span> <a name="l00233"></a>00233 <span class="comment"> *</span> <a name="l00234"></a>00234 <span class="comment"> * \sa compute3DMatchingRatio</span> <a name="l00235"></a>00235 <span class="comment"> */</span> <a name="l00236"></a><a class="code" href="classmrpt_1_1slam_1_1_c_metric_map.html#aa684de52360d687fb0ee30790f430574">00236</a> <span class="keyword">virtual</span> <span class="keywordtype">void</span> computeMatchingWith2D( <a name="l00237"></a>00237 <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="l00238"></a>00238 <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose2_d.html" title="A class used to store a 2D pose.">CPose2D</a> &otherMapPose, <a name="l00239"></a>00239 <span class="keywordtype">float</span> maxDistForCorrespondence, <a name="l00240"></a>00240 <span class="keywordtype">float</span> maxAngularDistForCorrespondence, <a name="l00241"></a>00241 <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose2_d.html" title="A class used to store a 2D pose.">CPose2D</a> &angularDistPivotPoint, <a name="l00242"></a>00242 TMatchingPairList &correspondences, <a name="l00243"></a>00243 <span class="keywordtype">float</span> &correspondencesRatio, <a name="l00244"></a>00244 <span class="keywordtype">float</span> *sumSqrDist = NULL, <a name="l00245"></a>00245 <span class="keywordtype">bool</span> onlyKeepTheClosest = <span class="keyword">true</span>, <a name="l00246"></a>00246 <span class="keywordtype">bool</span> onlyUniqueRobust = <span class="keyword">false</span>, <a name="l00247"></a>00247 <span class="keyword">const</span> <span class="keywordtype">size_t</span> decimation_other_map_points = 1, <a name="l00248"></a>00248 <span class="keyword">const</span> <span class="keywordtype">size_t</span> offset_other_map_points = 0 )<span class="keyword"> const</span> <a name="l00249"></a>00249 <span class="keyword"> </span>{ <a name="l00250"></a>00250 <a class="code" href="mrpt__macros_8h.html#a45b840af519f33816311acdbb28d7c10">MRPT_START</a> <a name="l00251"></a>00251 <a class="code" href="mrpt__macros_8h.html#aaa3f404ea85a6575a7139f8d101370ba">THROW_EXCEPTION</a>(<span class="stringliteral">"Virtual method not implemented in derived class."</span>) <a name="l00252"></a>00252 <a class="code" href="mrpt__macros_8h.html#a88a917260793b56abd83ad2a0d849eb1">MRPT_END</a> <a name="l00253"></a>00253 } <a name="l00254"></a>00254 <span class="comment"></span> <a name="l00255"></a>00255 <span class="comment"> /** Computes the matchings between this and another 3D points map - method used in 3D-ICP.</span> <a name="l00256"></a>00256 <span class="comment"> This method finds the set of point pairs in each map.</span> <a name="l00257"></a>00257 <span class="comment"></span> <a name="l00258"></a>00258 <span class="comment"> The method is the most time critical one into the ICP algorithm.</span> <a name="l00259"></a>00259 <span class="comment"></span> <a name="l00260"></a>00260 <span class="comment"> * \param otherMap [IN] The other map to compute the matching with.</span> <a name="l00261"></a>00261 <span class="comment"> * \param otherMapPose [IN] The pose of the other map as seen from "this".</span> <a name="l00262"></a>00262 <span class="comment"> * \param maxDistForCorrespondence [IN] Maximum 2D linear distance between two points to be matched.</span> <a name="l00263"></a>00263 <span class="comment"> * \param maxAngularDistForCorrespondence [IN] In radians: The aim is to allow larger distances to more distant correspondences.</span> <a name="l00264"></a>00264 <span class="comment"> * \param angularDistPivotPoint [IN] The point used to calculate distances from in both maps.</span> <a name="l00265"></a>00265 <span class="comment"> * \param correspondences [OUT] The detected matchings pairs.</span> <a name="l00266"></a>00266 <span class="comment"> * \param correspondencesRatio [OUT] The ratio [0,1] of points in otherMap with at least one correspondence.</span> <a name="l00267"></a>00267 <span class="comment"> * \param sumSqrDist [OUT] The sum of all matched points squared distances.If undesired, set to NULL, as default.</span> <a name="l00268"></a>00268 <span class="comment"> * \param onlyKeepTheClosest [IN] If set to true, only the closest correspondence will be returned. If false (default) all are returned.</span> <a name="l00269"></a>00269 <span class="comment"> *</span> <a name="l00270"></a>00270 <span class="comment"> * \sa compute3DMatchingRatio</span> <a name="l00271"></a>00271 <span class="comment"> */</span> <a name="l00272"></a><a class="code" href="classmrpt_1_1slam_1_1_c_metric_map.html#a7aafbdbb3f2cb17e14e1af9997c3fa48">00272</a> <span class="keyword">virtual</span> <span class="keywordtype">void</span> computeMatchingWith3D( <a name="l00273"></a>00273 <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="l00274"></a>00274 <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="l00275"></a>00275 <span class="keywordtype">float</span> maxDistForCorrespondence, <a name="l00276"></a>00276 <span class="keywordtype">float</span> maxAngularDistForCorrespondence, <a name="l00277"></a>00277 <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_point3_d.html" title="A class used to store a 3D point.">CPoint3D</a> &angularDistPivotPoint, <a name="l00278"></a>00278 TMatchingPairList &correspondences, <a name="l00279"></a>00279 <span class="keywordtype">float</span> &correspondencesRatio, <a name="l00280"></a>00280 <span class="keywordtype">float</span> *sumSqrDist = NULL, <a name="l00281"></a>00281 <span class="keywordtype">bool</span> onlyKeepTheClosest = <span class="keyword">true</span>, <a name="l00282"></a>00282 <span class="keywordtype">bool</span> onlyUniqueRobust = <span class="keyword">false</span>, <a name="l00283"></a>00283 <span class="keyword">const</span> <span class="keywordtype">size_t</span> decimation_other_map_points = 1, <a name="l00284"></a>00284 <span class="keyword">const</span> <span class="keywordtype">size_t</span> offset_other_map_points = 0 )<span class="keyword"> const</span> <a name="l00285"></a>00285 <span class="keyword"> </span>{ <a name="l00286"></a>00286 <a class="code" href="mrpt__macros_8h.html#a45b840af519f33816311acdbb28d7c10">MRPT_START</a> <a name="l00287"></a>00287 <a class="code" href="mrpt__macros_8h.html#aaa3f404ea85a6575a7139f8d101370ba">THROW_EXCEPTION</a>(<span class="stringliteral">"Virtual method not implemented in derived class."</span>) <a name="l00288"></a>00288 <a class="code" href="mrpt__macros_8h.html#a88a917260793b56abd83ad2a0d849eb1">MRPT_END</a> <a name="l00289"></a>00289 } <a name="l00290"></a>00290 <a name="l00291"></a>00291 <span class="comment"></span> <a name="l00292"></a>00292 <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="l00293"></a>00293 <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="l00294"></a>00294 <span class="comment"> * \param otherMap [IN] The other map to compute the matching with.</span> <a name="l00295"></a>00295 <span class="comment"> * \param otherMapPose [IN] The 6D pose of the other map as seen from "this".</span> <a name="l00296"></a>00296 <span class="comment"> * \param minDistForCorr [IN] The minimum distance between 2 non-probabilistic map elements for counting them as a correspondence.</span> <a name="l00297"></a>00297 <span class="comment"> * \param minMahaDistForCorr [IN] The minimum Mahalanobis distance between 2 probabilistic map elements for counting them as a correspondence.</span> <a name="l00298"></a>00298 <span class="comment"> *</span> <a name="l00299"></a>00299 <span class="comment"> * \return The matching ratio [0,1]</span> <a name="l00300"></a>00300 <span class="comment"> * \sa computeMatchingWith2D</span> <a name="l00301"></a>00301 <span class="comment"> */</span> <a name="l00302"></a>00302 <span class="keyword">virtual</span> <span class="keywordtype">float</span> compute3DMatchingRatio( <a name="l00303"></a>00303 <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="l00304"></a>00304 <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="l00305"></a>00305 <span class="keywordtype">float</span> minDistForCorr = 0.10f, <a name="l00306"></a>00306 <span class="keywordtype">float</span> minMahaDistForCorr = 2.0f <a name="l00307"></a>00307 ) <span class="keyword">const</span> = 0; <a name="l00308"></a>00308 <span class="comment"></span> <a name="l00309"></a>00309 <span class="comment"> /** This virtual method saves the map to a file "filNamePrefix"+< some_file_extension >, as an image or in any other applicable way (Notice that other methods to save the map may be implemented in classes implementing this virtual interface).</span> <a name="l00310"></a>00310 <span class="comment"> */</span> <a name="l00311"></a>00311 <span class="keyword">virtual</span> <span class="keywordtype">void</span> saveMetricMapRepresentationToFile( <a name="l00312"></a>00312 <span class="keyword">const</span> <a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a> &filNamePrefix <a name="l00313"></a>00313 ) <span class="keyword">const</span> = 0; <a name="l00314"></a>00314 <span class="comment"></span> <a name="l00315"></a>00315 <span class="comment"> /** Returns a 3D object representing the map.</span> <a name="l00316"></a>00316 <span class="comment"> */</span> <a name="l00317"></a>00317 <span class="keyword">virtual</span> <span class="keywordtype">void</span> getAs3DObject( <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> = 0; <a name="l00318"></a>00318 <span class="comment"></span> <a name="l00319"></a>00319 <span class="comment"> /** When set to true (default=false), calling "getAs3DObject" will have no effects.</span> <a name="l00320"></a>00320 <span class="comment"> */</span> <a name="l00321"></a><a class="code" href="classmrpt_1_1slam_1_1_c_metric_map.html#a2b50a8c61d853cc452b82d58756e9603">00321</a> <span class="keywordtype">bool</span> <a class="code" href="classmrpt_1_1slam_1_1_c_metric_map.html#a2b50a8c61d853cc452b82d58756e9603" title="When set to true (default=false), calling "getAs3DObject" will have no effects.">m_disableSaveAs3DObject</a>; <a name="l00322"></a>00322 <span class="comment"></span> <a name="l00323"></a>00323 <span class="comment"> /** This method is called at the end of each "prediction-update-map insertion" cycle within "mrpt::slam::CMetricMapBuilderRBPF::processActionObservation".</span> <a name="l00324"></a>00324 <span class="comment"> * This method should normally do nothing, but in some cases can be used to free auxiliary cached variables.</span> <a name="l00325"></a>00325 <span class="comment"> */</span> <a name="l00326"></a><a class="code" href="classmrpt_1_1slam_1_1_c_metric_map.html#aabd4d4be402cdd01bc8db467f214516a">00326</a> <span class="keyword">virtual</span> <span class="keywordtype">void</span> auxParticleFilterCleanUp() <a name="l00327"></a>00327 { <a name="l00328"></a>00328 <span class="comment">// Default implementation: do nothing.</span> <a name="l00329"></a>00329 } <a name="l00330"></a>00330 <span class="comment"></span> <a name="l00331"></a>00331 <span class="comment"> /** Returns the square distance from the 2D point (x0,y0) to the closest correspondence in the map.</span> <a name="l00332"></a>00332 <span class="comment"> */</span> <a name="l00333"></a><a class="code" href="classmrpt_1_1slam_1_1_c_metric_map.html#ae6235efcb6d5da8e9db1ad6ccfb8225c">00333</a> <span class="keyword">virtual</span> <span class="keywordtype">float</span> squareDistanceToClosestCorrespondence( <a name="l00334"></a>00334 <span class="keyword">const</span> <span class="keywordtype">float</span> &x0, <a name="l00335"></a>00335 <span class="keyword">const</span> <span class="keywordtype">float</span> &y0 )<span class="keyword"> const</span> <a name="l00336"></a>00336 <span class="keyword"> </span>{ <a name="l00337"></a>00337 <a class="code" href="mrpt__macros_8h.html#a45b840af519f33816311acdbb28d7c10">MRPT_START</a> <a name="l00338"></a>00338 <a class="code" href="mrpt__macros_8h.html#aaa3f404ea85a6575a7139f8d101370ba">THROW_EXCEPTION</a>(<span class="stringliteral">"Virtual method not implemented in derived class."</span>) <a name="l00339"></a>00339 <a class="code" href="mrpt__macros_8h.html#a88a917260793b56abd83ad2a0d849eb1">MRPT_END</a> <a name="l00340"></a>00340 } <a name="l00341"></a>00341 <a name="l00342"></a>00342 <span class="comment"></span> <a name="l00343"></a>00343 <span class="comment"> /** If the map is a simple points map or it's a multi-metric map that contains EXACTLY one simple points map, return it.</span> <a name="l00344"></a>00344 <span class="comment"> * Otherwise, return NULL</span> <a name="l00345"></a>00345 <span class="comment"> */</span> <a name="l00346"></a><a class="code" href="classmrpt_1_1slam_1_1_c_metric_map.html#ae7b0688c0e2c0d75554e22b739649463">00346</a> <span class="keyword">virtual</span> <span class="keyword">const</span> <a class="code" href="classmrpt_1_1slam_1_1_c_simple_points_map.html" title="A cloud of points in 2D or 3D, which can be built from a sequence of laser scans.">CSimplePointsMap</a> * <a class="code" href="classmrpt_1_1slam_1_1_c_metric_map.html#ae7b0688c0e2c0d75554e22b739649463" title="If the map is a simple points map or it's a multi-metric map that contains EXACTLY one simple points ...">getAsSimplePointsMap</a>()<span class="keyword"> const </span>{ <span class="keywordflow">return</span> NULL; } <a name="l00347"></a><a class="code" href="classmrpt_1_1slam_1_1_c_metric_map.html#ace4e7cc2a2f070d556c5074117a3aa2f">00347</a> <span class="keyword">virtual</span> <a class="code" href="classmrpt_1_1slam_1_1_c_simple_points_map.html" title="A cloud of points in 2D or 3D, which can be built from a sequence of laser scans.">CSimplePointsMap</a> * <a class="code" href="classmrpt_1_1slam_1_1_c_metric_map.html#ace4e7cc2a2f070d556c5074117a3aa2f">getAsSimplePointsMap</a>() { <span class="keywordflow">return</span> NULL; } <a name="l00348"></a>00348 <a name="l00349"></a>00349 <a name="l00350"></a>00350 }; <span class="comment">// End of class def.</span> <a name="l00351"></a>00351 <span class="comment"></span> <a name="l00352"></a>00352 <span class="comment"> /** A list of metric maps (used in the mrpt::poses::CPosePDFParticles class):</span> <a name="l00353"></a>00353 <span class="comment"> */</span> <a name="l00354"></a><a class="code" href="namespacemrpt_1_1slam.html#a4a08ae2dfc5960f445532895b5012dbf">00354</a> <span class="keyword">typedef</span> std<a class="code" href="classstd_1_1deque.html">::deque<CMetricMap*></a> <a class="code" href="namespacemrpt_1_1slam.html#a4a08ae2dfc5960f445532895b5012dbf" title="A list of metric maps (used in the mrpt::poses::CPosePDFParticles class):">TMetricMapList</a>; <a name="l00355"></a>00355 <a name="l00356"></a>00356 } <span class="comment">// End of namespace</span> <a name="l00357"></a>00357 } <span class="comment">// End of namespace</span> <a name="l00358"></a>00358 <a name="l00359"></a>00359 <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>