<!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>CLocalMetricHypothesis.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">CLocalMetricHypothesis.h</div> </div> </div> <div class="contents"> <a href="_c_local_metric_hypothesis_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 CLocalMetricHypothesis_H</span> <a name="l00029"></a>00029 <span class="preprocessor"></span><span class="preprocessor">#define CLocalMetricHypothesis_H</span> <a name="l00030"></a>00030 <span class="preprocessor"></span> <a name="l00031"></a>00031 <span class="preprocessor">#include <<a class="code" href="synch_8h.html">mrpt/synch.h</a>></span> <a name="l00032"></a>00032 <span class="preprocessor">#include <<a class="code" href="_c_particle_filter_capable_8h.html">mrpt/bayes/CParticleFilterCapable.h</a>></span> <a name="l00033"></a>00033 <a name="l00034"></a>00034 <span class="preprocessor">#include <<a class="code" href="_h_m_t___s_l_a_m__common_8h.html">mrpt/hmtslam/HMT_SLAM_common.h</a>></span> <a name="l00035"></a>00035 <span class="preprocessor">#include <<a class="code" href="_c_h_m_h_map_node_8h.html">mrpt/hmtslam/CHMHMapNode.h</a>></span> <a name="l00036"></a>00036 <a name="l00037"></a>00037 <span class="preprocessor">#include <<a class="code" href="_c_multi_metric_map_8h.html">mrpt/slam/CMultiMetricMap.h</a>></span> <a name="l00038"></a>00038 <span class="preprocessor">#include <<a class="code" href="_c_action_robot_movement2_d_8h.html">mrpt/slam/CActionRobotMovement2D.h</a>></span> <a name="l00039"></a>00039 <span class="preprocessor">#include <<a class="code" href="_c_incremental_map_partitioner_8h.html">mrpt/slam/CIncrementalMapPartitioner.h</a>></span> <a name="l00040"></a>00040 <a name="l00041"></a>00041 <span class="preprocessor">#include <list></span> <a name="l00042"></a>00042 <a name="l00043"></a>00043 <span class="keyword">namespace </span>mrpt <a name="l00044"></a>00044 { <a name="l00045"></a>00045 <span class="keyword">namespace </span>opengl <a name="l00046"></a>00046 { <a name="l00047"></a>00047 <span class="keyword">struct </span>CSetOfObjectsPtr; <a name="l00048"></a>00048 } <a name="l00049"></a>00049 <span class="keyword">namespace </span>poses <a name="l00050"></a>00050 { <a name="l00051"></a>00051 <span class="keyword">class </span>CPose3DPDFParticles; <a name="l00052"></a>00052 } <a name="l00053"></a>00053 <a name="l00054"></a>00054 <span class="keyword">namespace </span>hmtslam <a name="l00055"></a>00055 { <a name="l00056"></a>00056 <span class="keyword">using namespace </span>mrpt::slam; <a name="l00057"></a>00057 <a name="l00058"></a><a class="code" href="namespacemrpt_1_1hmtslam.html#a3cbc1dce012698b238004879011b8cee">00058</a> <span class="keyword">class </span><a class="code" href="hmtslam__impexp_8h.html#a4f5ef02557cd461c7f3eb0eb04684aca">HMTSLAM_IMPEXP</a> <a class="code" href="classmrpt_1_1hmtslam_1_1_c_h_m_t_s_l_a_m.html" title="An implementation of Hybrid Metric Topological SLAM (HMT-SLAM).">CHMTSLAM</a>; <a name="l00059"></a><a class="code" href="namespacemrpt_1_1hmtslam.html#af179dabf4c97d4b2e3a4c1b711e6a943">00059</a> <span class="keyword">class </span><a class="code" href="hmtslam__impexp_8h.html#a4f5ef02557cd461c7f3eb0eb04684aca">HMTSLAM_IMPEXP</a> <a class="code" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m___r_b_p_f__2_d_l_a_s_e_r.html" title="Implements a 2D local SLAM method based on a RBPF over an occupancy grid map.">CLSLAM_RBPF_2DLASER</a>; <a name="l00060"></a>00060 <a name="l00061"></a><a class="code" href="structmrpt_1_1hmtslam_1_1_c_l_s_l_a_m_particle_data_ptr.html#a7f6028e7bf0f3815d26ea0e5b9948a63">00061</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_1hmtslam_1_1_c_l_s_l_a_m_particle_data.html" title="Auxiliary class used in mrpt::slam::CLocalMetricHypothesis for HMT-SLAM; this class keeps the data re...">CLSLAMParticleData</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="hmtslam__impexp_8h.html#a4f5ef02557cd461c7f3eb0eb04684aca">HMTSLAM_IMPEXP</a> ) <a name="l00062"></a><a class="code" href="structmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis_ptr.html#aeea745c64f162e15dd02bdc40573a1c3">00062</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_1hmtslam_1_1_c_local_metric_hypothesis.html" title="This class is used in HMT-SLAM to represent each of the Local Metric Hypotheses (LMHs).">CLocalMetricHypothesis</a>, 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 class="code" href="hmtslam__impexp_8h.html#a4f5ef02557cd461c7f3eb0eb04684aca">HMTSLAM_IMPEXP</a> ) <a name="l00063"></a>00063 <span class="comment"></span> <a name="l00064"></a>00064 <span class="comment"> /** Auxiliary class used in mrpt::slam::CLocalMetricHypothesis for HMT-SLAM; this class keeps the data relative to each local metric particle ("a robot metric path hypothesis" and its associated metric map).</span> <a name="l00065"></a>00065 <span class="comment"> * \ingroup mrpt_hmtslam_grp</span> <a name="l00066"></a>00066 <span class="comment"> */</span> <a name="l00067"></a>00067 class <a class="code" href="hmtslam__impexp_8h.html#a4f5ef02557cd461c7f3eb0eb04684aca">HMTSLAM_IMPEXP</a> <a class="code" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m_particle_data.html" title="Auxiliary class used in mrpt::slam::CLocalMetricHypothesis for HMT-SLAM; this class keeps the data re...">CLSLAMParticleData</a> : public mrpt::utils::CSerializable <a name="l00068"></a>00068 { <a name="l00069"></a>00069 <span class="comment">// This must be added to any CSerializable derived class:</span> <a name="l00070"></a><a class="code" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m_particle_data.html#aa33a7817b9d5a0b24ed26ba54e8a43be">00070</a> <a class="code" href="_c_serializable_8h.html#a72ab55bf7ae009c89b75715cfa21e84d" title="This declaration must be inserted in all CSerializable classes definition, within the class declarati...">DEFINE_SERIALIZABLE</a>( <a class="code" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m_particle_data.html" title="Auxiliary class used in mrpt::slam::CLocalMetricHypothesis for HMT-SLAM; this class keeps the data re...">CLSLAMParticleData</a> ) <a name="l00071"></a>00071 <a name="l00072"></a>00072 public: <a name="l00073"></a><a class="code" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m_particle_data.html#a44d287052b8b33b477efff7519f912f5">00073</a> <a class="code" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m_particle_data.html" title="Auxiliary class used in mrpt::slam::CLocalMetricHypothesis for HMT-SLAM; this class keeps the data re...">CLSLAMParticleData</a>( const <a class="code" href="classmrpt_1_1slam_1_1_t_set_of_metric_map_initializers.html" title="A set of TMetricMapInitializer structures, passed to the constructor CMultiMetricMap::CMultiMetricMap...">TSetOfMetricMapInitializers</a> *mapsInitializers = NULL ) : <a name="l00074"></a>00074 metricMaps( mapsInitializers ), <a name="l00075"></a>00075 robotPoses() <a name="l00076"></a>00076 { <a name="l00077"></a>00077 } <a name="l00078"></a>00078 <a name="l00079"></a><a class="code" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m_particle_data.html#af18f39e817abee82bdf737c949c4a96e">00079</a> <span class="keyword">virtual</span> ~<a class="code" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m_particle_data.html" title="Auxiliary class used in mrpt::slam::CLocalMetricHypothesis for HMT-SLAM; this class keeps the data re...">CLSLAMParticleData</a>() <a name="l00080"></a>00080 { <a name="l00081"></a>00081 robotPoses.clear(); <a name="l00082"></a>00082 } <a name="l00083"></a>00083 <a name="l00084"></a><a class="code" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m_particle_data.html#a7a55f32003290ee8eb8e1cac05d63e00">00084</a> <a class="code" href="classmrpt_1_1slam_1_1_c_multi_metric_map.html" title="This class stores any customizable set of metric maps.">CMultiMetricMap</a> <a class="code" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m_particle_data.html#a7a55f32003290ee8eb8e1cac05d63e00">metricMaps</a>; <a name="l00085"></a><a class="code" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m_particle_data.html#a514535a330ff55eb352ccb039b2c5373">00085</a> std<a class="code" href="classstd_1_1map.html">::map<TPoseID,CPose3D></a> <a class="code" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m_particle_data.html#a514535a330ff55eb352ccb039b2c5373">robotPoses</a>; <a name="l00086"></a>00086 }; <a name="l00087"></a>00087 <a name="l00088"></a>00088 <span class="comment"></span> <a name="l00089"></a>00089 <span class="comment"> /** This class is used in HMT-SLAM to represent each of the Local Metric Hypotheses (LMHs).</span> <a name="l00090"></a>00090 <span class="comment"> * It has a set of particles representing the robot path in nearby poses.</span> <a name="l00091"></a>00091 <span class="comment"> * \sa CHMTSLAM, CLSLAM_RBPF_2DLASER</span> <a name="l00092"></a>00092 <span class="comment"> */</span> <a name="l00093"></a>00093 <span class="keyword">class </span><a class="code" href="hmtslam__impexp_8h.html#a4f5ef02557cd461c7f3eb0eb04684aca">HMTSLAM_IMPEXP</a> <a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html" title="This class is used in HMT-SLAM to represent each of the Local Metric Hypotheses (LMHs).">CLocalMetricHypothesis</a> : <a name="l00094"></a>00094 <span class="keyword">public</span> bayes::<a class="code" href="classmrpt_1_1bayes_1_1_c_particle_filter_capable.html" title="This virtual class defines the interface that any particles based PDF class must implement in order t...">CParticleFilterCapable</a>, <span class="keyword">public</span> bayes::<a class="code" href="classmrpt_1_1bayes_1_1_c_particle_filter_data.html" title="This template class declares the array of particles and its internal data, managing some memory-relat...">CParticleFilterData</a><CLSLAMParticleData>, <a name="l00095"></a>00095 <span class="keyword">public</span> 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="l00096"></a>00096 { <a name="l00097"></a><a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html#ac34a721ee598515baa4048b339f41013">00097</a> <span class="keyword">friend</span> <span class="keyword">class </span><a class="code" href="hmtslam__impexp_8h.html#a4f5ef02557cd461c7f3eb0eb04684aca">HMTSLAM_IMPEXP</a> <a class="code" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m___r_b_p_f__2_d_l_a_s_e_r.html" title="Implements a 2D local SLAM method based on a RBPF over an occupancy grid map.">CLSLAM_RBPF_2DLASER</a>; <a name="l00098"></a>00098 <a name="l00099"></a>00099 <span class="comment">// This must be added to any CSerializable derived class:</span> <a name="l00100"></a><a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html#a190437d4041db42984c49394686e827d">00100</a> <a class="code" href="_c_serializable_8h.html#a72ab55bf7ae009c89b75715cfa21e84d" title="This declaration must be inserted in all CSerializable classes definition, within the class declarati...">DEFINE_SERIALIZABLE</a>( <a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html" title="This class is used in HMT-SLAM to represent each of the Local Metric Hypotheses (LMHs).">CLocalMetricHypothesis</a> ) <a name="l00101"></a>00101 <a name="l00102"></a>00102 public:<span class="comment"></span> <a name="l00103"></a>00103 <span class="comment"> /** Constructor (Default param only used from STL classes)</span> <a name="l00104"></a>00104 <span class="comment"> */</span> <a name="l00105"></a>00105 <a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html" title="This class is used in HMT-SLAM to represent each of the Local Metric Hypotheses (LMHs).">CLocalMetricHypothesis</a>( <a class="code" href="classmrpt_1_1hmtslam_1_1_c_h_m_t_s_l_a_m.html" title="An implementation of Hybrid Metric Topological SLAM (HMT-SLAM).">CHMTSLAM</a> * parent = NULL ); <a name="l00106"></a>00106 <span class="comment"></span> <a name="l00107"></a>00107 <span class="comment"> /** Destructor</span> <a name="l00108"></a>00108 <span class="comment"> */</span> <a name="l00109"></a>00109 ~<a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html" title="This class is used in HMT-SLAM to represent each of the Local Metric Hypotheses (LMHs).">CLocalMetricHypothesis</a>(); <a name="l00110"></a>00110 <a name="l00111"></a><a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html#a3fca93101fbbd36f8542deb960231f53">00111</a> synch::CCriticalSection m_lock; <span class="comment">//!< Critical section for threads signaling they are working with the LMH.</span> <a name="l00112"></a><a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html#a559c9d5b9fcc9325ecd95f722fbe682f">00112</a> <span class="comment"></span> <a class="code" href="namespacemrpt_1_1hmtslam.html#a6a8c7a5cb874400f4df9d1fd6b6ff9ee" title="An integer number uniquely identifying each of the concurrent hypotheses for the robot topological pa...">THypothesisID</a> m_ID; <span class="comment">//!< The unique ID of the hypothesis (Used for accessing mrpt::slam::CHierarchicalMHMap).</span> <a name="l00113"></a><a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html#acb6413f6bc48d29770cc179eab5ee0a3">00113</a> <span class="comment"></span> <a class="code" href="structmrpt_1_1utils_1_1safe__ptr.html" title="A wrapper class for pointers that can be safely copied with "=" operator without problems.">safe_ptr</a><<a class="code" href="classmrpt_1_1hmtslam_1_1_c_h_m_t_s_l_a_m.html" title="An implementation of Hybrid Metric Topological SLAM (HMT-SLAM).">CHMTSLAM</a>> m_parent; <span class="comment">//!< For quick access to our parent object.</span> <a name="l00114"></a><a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html#ae2172d3ffdfeeefe6183f6dca598f960">00114</a> <span class="comment"></span> <a class="code" href="namespacemrpt_1_1hmtslam.html#afc45e3c745da87655acd25af131343bf" title="An integer number uniquely identifying each robot pose stored in HMT-SLAM.">TPoseID</a> m_currentRobotPose; <span class="comment">//!< The current robot pose (its global unique ID) for this hypothesis.</span> <a name="l00115"></a>00115 <span class="comment"></span> <span class="comment">//TNodeIDList m_neighbors; //!< The list of all areas sourronding the current one (this includes the current area itself).</span> <a name="l00116"></a><a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html#a7bda1e6774884134f9b34d220eccd5df">00116</a> <a class="code" href="classstd_1_1set.html">TNodeIDSet</a> m_neighbors; <span class="comment">//!< The list of all areas sourronding the current one (this includes the current area itself).</span> <a name="l00117"></a><a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html#ad7adc8d8a5e7a04334a50558b051aa15">00117</a> <span class="comment"></span> std::<a class="code" href="classstd_1_1map.html" title="STL class.">map</a><<a class="code" href="namespacemrpt_1_1hmtslam.html#afc45e3c745da87655acd25af131343bf" title="An integer number uniquely identifying each robot pose stored in HMT-SLAM.">TPoseID</a>,<a class="code" href="classmrpt_1_1hmtslam_1_1_c_h_m_h_map_node.html" title="A class for representing a node in a hierarchical, multi-hypothesis map.">CHMHMapNode</a>::<a class="code" href="namespacemrpt_1_1utils.html#a718b4f99645b7e9f6501c9b7bb2a2fe7" title="The type for node IDs in graphs of different types.">TNodeID</a>> m_nodeIDmemberships; <span class="comment">//!< The hybrid map node membership for each robot pose.</span> <a name="l00118"></a><a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html#a9a921aef54b49bab62dc18e20913f44e">00118</a> <span class="comment"></span> std::<a class="code" href="classstd_1_1map.html" title="STL class.">map</a><TPoseID,<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>> m_SFs; <span class="comment">//!< The SF gathered at each robot pose.</span> <a name="l00119"></a><a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html#af701aeb4da0c4c13ae8e288e92389ccf">00119</a> <span class="comment"></span> <a class="code" href="classstd_1_1vector.html">TPoseIDList</a> m_posesPendingAddPartitioner; <span class="comment">//!< The list of poseIDs waiting to be added to the graph partitioner, what happens in the LSLAM thread main loop.</span> <a name="l00120"></a><a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html#a1baff49d6df7e31ad47308f9d4dcf411">00120</a> <span class="comment"></span> <a class="code" href="classmrpt_1_1utils_1_1list__searchable.html">TNodeIDList</a> m_areasPendingTBI; <span class="comment">//!< The list of area IDs waiting to be processed by the TBI (topological bayesian inference) engines to search for potential loop-closures. Set in CHMTSLAM::LSLAM_process_message_from_AA, read in</span> <a name="l00121"></a>00121 <span class="comment"></span> <a name="l00122"></a><a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html#a3b7c38915660b84a3b3de6a80b5b4d97">00122</a> <span class="keywordtype">double</span> m_log_w; <span class="comment">//!< Log-weight of this hypothesis.</span> <a name="l00123"></a><a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html#adcde7731917b103e6e4b460c1627b215">00123</a> <span class="comment"></span> std::<a class="code" href="classstd_1_1vector.html" title="STL class.">vector</a><std::<a class="code" href="classstd_1_1map.html" title="STL class.">map</a><TPoseID,<span class="keywordtype">double</span>> > m_log_w_metric_history; <span class="comment">//!< The historic log-weights of the metric observations inserted in this LMH, for each particle.</span> <a name="l00124"></a>00124 <span class="comment"></span> <span class="comment">//std::map<TPoseID,double> m_log_w_topol_history; //!< The historic log-weights of the topological observations inserted in this LMH.</span> <a name="l00125"></a>00125 <a name="l00126"></a><a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html#a1683692cc38d5b813b5dcf35aabecf3d">00126</a> <a class="code" href="classmrpt_1_1slam_1_1_c_action_robot_movement2_d.html" title="Represents a probabilistic 2D movement of the robot mobile base.">CActionRobotMovement2D</a> m_accumRobotMovement; <span class="comment">//!< Used in CLSLAM_RBPF_2DLASER</span> <a name="l00127"></a><a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html#a8ed7c3c48ce94c1310a19a59adde5b38">00127</a> <span class="comment"></span> <span class="keywordtype">bool</span> m_accumRobotMovementIsValid; <span class="comment">//!< Used in CLSLAM_RBPF_2DLASER</span> <a name="l00128"></a>00128 <span class="comment"></span><span class="comment"></span> <a name="l00129"></a>00129 <span class="comment"> /** Used by AA thread */</span> <a name="l00130"></a>00130 struct <a class="code" href="structmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis_1_1_t_robot_poses_partitioning.html" title="Used by AA thread.">TRobotPosesPartitioning</a> <a name="l00131"></a>00131 { <a name="l00132"></a><a class="code" href="structmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis_1_1_t_robot_poses_partitioning.html#a887774328c43a236c3b5ce81efa894cc">00132</a> synch::CCriticalSection <a class="code" href="structmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis_1_1_t_robot_poses_partitioning.html#a887774328c43a236c3b5ce81efa894cc" title="CS to access the entire struct.">lock</a>; <span class="comment">//!< CS to access the entire struct.</span> <a name="l00133"></a><a class="code" href="structmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis_1_1_t_robot_poses_partitioning.html#a5997d50c91a47ef0f3f5297ee6126004">00133</a> <span class="comment"></span> <a class="code" href="classmrpt_1_1slam_1_1_c_incremental_map_partitioner.html" title="This class can be used to make partitions on a map/graph build from observations taken at some poses/...">CIncrementalMapPartitioner</a> <a class="code" href="structmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis_1_1_t_robot_poses_partitioning.html#a5997d50c91a47ef0f3f5297ee6126004">partitioner</a>; <a name="l00134"></a><a class="code" href="structmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis_1_1_t_robot_poses_partitioning.html#ad96fcf5f468e3c21491f8b89b0f822a3">00134</a> std<a class="code" href="classstd_1_1map.html">::map<uint32_t,TPoseID></a> <a class="code" href="structmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis_1_1_t_robot_poses_partitioning.html#ad96fcf5f468e3c21491f8b89b0f822a3" title="For the poses in "partitioner".">idx2pose</a>; <span class="comment">//!< For the poses in "partitioner".</span> <a name="l00135"></a>00135 <span class="comment"></span> <a name="l00136"></a>00136 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> pose2idx(<span class="keyword">const</span> TPoseID &<span class="keywordtype">id</span>) <span class="keyword">const</span>; <span class="comment">//!< Uses idx2pose to perform inverse searches.</span> <a name="l00137"></a>00137 <span class="comment"></span> <a name="l00138"></a>00138 } m_robotPosesGraph; <a name="l00139"></a>00139 <span class="comment"></span> <a name="l00140"></a>00140 <span class="comment"> /** Returns a 3D representation of the the current robot pose, all the poses in the auxiliary graph, and each of the areas they belong to.</span> <a name="l00141"></a>00141 <span class="comment"> * The metric maps are *not* included here for convenience, call m_metricMaps.getAs3DScene().</span> <a name="l00142"></a>00142 <span class="comment"> * The previous contents of "objs" will be discarded</span> <a name="l00143"></a>00143 <span class="comment"> */</span> <a name="l00144"></a>00144 <span class="keywordtype">void</span> getAs3DScene( <a class="code" href="structmrpt_1_1opengl_1_1_c_set_of_objects_ptr.html">mrpt::opengl::CSetOfObjectsPtr</a> &objs ) <span class="keyword">const</span>; <a name="l00145"></a>00145 <span class="comment"></span> <a name="l00146"></a>00146 <span class="comment"> /** Returns the mean of each robot pose in this LMH, as computed from the set of particles.</span> <a name="l00147"></a>00147 <span class="comment"> * \sa getPathParticles, getRelativePose</span> <a name="l00148"></a>00148 <span class="comment"> */</span> <a name="l00149"></a>00149 <span class="keywordtype">void</span> getMeans( <a class="code" href="classstd_1_1map.html">std::map< TPoseID, CPose3D ></a> &outList ) <span class="keyword">const</span>; <a name="l00150"></a>00150 <span class="comment"></span> <a name="l00151"></a>00151 <span class="comment"> /** Returns the mean and covariance of each robot pose in this LMH, as computed from the set of particles.</span> <a name="l00152"></a>00152 <span class="comment"> * \sa getMeans, getPoseParticles</span> <a name="l00153"></a>00153 <span class="comment"> */</span> <a name="l00154"></a>00154 <span class="keywordtype">void</span> getPathParticles( <a class="code" href="classstd_1_1map.html" title="STL class.">std::map< TPoseID, CPose3DPDFParticles ></a> &outList ) <span class="keyword">const</span>; <a name="l00155"></a>00155 <span class="comment"></span> <a name="l00156"></a>00156 <span class="comment"> /** Returns the mean and covariance of each robot pose in this LMH, as computed from the set of particles.</span> <a name="l00157"></a>00157 <span class="comment"> * \sa getMeans, getPathParticles</span> <a name="l00158"></a>00158 <span class="comment"> */</span> <a name="l00159"></a>00159 <span class="keywordtype">void</span> getPoseParticles( <span class="keyword">const</span> <a class="code" href="namespacemrpt_1_1hmtslam.html#afc45e3c745da87655acd25af131343bf" title="An integer number uniquely identifying each robot pose stored in HMT-SLAM.">TPoseID</a> &poseID, <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_particles.html" title="Declares a class that represents a Probability Density function (PDF) of a 3D pose.">CPose3DPDFParticles</a> &outPDF ) <span class="keyword">const</span>; <a name="l00160"></a>00160 <span class="comment"></span> <a name="l00161"></a>00161 <span class="comment"> /** Returns the pose PDF of some pose relative to some other pose ID (both must be part of the the LMH).</span> <a name="l00162"></a>00162 <span class="comment"> * \sa getMeans, getPoseParticles</span> <a name="l00163"></a>00163 <span class="comment"> */</span> <a name="l00164"></a>00164 <span class="keywordtype">void</span> getRelativePose( <a name="l00165"></a>00165 <span class="keyword">const</span> <a class="code" href="namespacemrpt_1_1hmtslam.html#afc45e3c745da87655acd25af131343bf" title="An integer number uniquely identifying each robot pose stored in HMT-SLAM.">TPoseID</a> &reference, <a name="l00166"></a>00166 <span class="keyword">const</span> <a class="code" href="namespacemrpt_1_1hmtslam.html#afc45e3c745da87655acd25af131343bf" title="An integer number uniquely identifying each robot pose stored in HMT-SLAM.">TPoseID</a> &pose, <a name="l00167"></a>00167 <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_particles.html" title="Declares a class that represents a Probability Density function (PDF) of a 3D pose.">CPose3DPDFParticles</a> &outPDF ) <span class="keyword">const</span>; <a name="l00168"></a>00168 <span class="comment"></span> <a name="l00169"></a>00169 <span class="comment"> /** Describes the LMH in text.</span> <a name="l00170"></a>00170 <span class="comment"> */</span> <a name="l00171"></a>00171 <span class="keywordtype">void</span> dumpAsText(<a class="code" href="classmrpt_1_1utils_1_1_c_string_list.html" title="A class for storing a list of text lines.">utils::CStringList</a> &st) <span class="keyword">const</span>; <a name="l00172"></a>00172 <span class="comment"></span> <a name="l00173"></a>00173 <span class="comment"> /** Change all coordinates to set a given robot pose as the new coordinate origin, and rebuild metric maps and change coords in the partitioning subsystem as well.</span> <a name="l00174"></a>00174 <span class="comment"> */</span> <a name="l00175"></a>00175 <span class="keywordtype">void</span> changeCoordinateOrigin( <span class="keyword">const</span> <a class="code" href="namespacemrpt_1_1hmtslam.html#afc45e3c745da87655acd25af131343bf" title="An integer number uniquely identifying each robot pose stored in HMT-SLAM.">TPoseID</a> &newOrigin ); <a name="l00176"></a>00176 <span class="comment"></span> <a name="l00177"></a>00177 <span class="comment"> /** Rebuild the metric maps of all particles from the observations and their estimated poses. */</span> <a name="l00178"></a>00178 <span class="keywordtype">void</span> rebuildMetricMaps(); <a name="l00179"></a>00179 <span class="comment"></span> <a name="l00180"></a>00180 <span class="comment"> /** Rebuild the auxiliary metric maps in "m_robotPosesGraph" from the observations "m_SFs" and their estimated poses. */</span> <a name="l00181"></a>00181 <span class="comment">//void rebuildSSOMatrix();</span> <a name="l00182"></a>00182 <span class="comment"></span> <a name="l00183"></a>00183 <span class="comment"> /** Sets the number of particles to the initial number according to the PF options, and initialize them with no robot poses & empty metric maps.</span> <a name="l00184"></a>00184 <span class="comment"> */</span> <a name="l00185"></a>00185 <span class="keywordtype">void</span> clearRobotPoses(); <a name="l00186"></a>00186 <span class="comment"></span> <a name="l00187"></a>00187 <span class="comment"> /** Returns the i'th particle hypothesis for the current robot pose. */</span> <a name="l00188"></a>00188 <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> * getCurrentPose(<span class="keyword">const</span> <span class="keywordtype">size_t</span> &particleIdx) <span class="keyword">const</span>; <a name="l00189"></a>00189 <span class="comment"></span> <a name="l00190"></a>00190 <span class="comment"> /** Returns the i'th particle hypothesis for the current robot pose. */</span> <a name="l00191"></a>00191 <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> * getCurrentPose(<span class="keyword">const</span> <span class="keywordtype">size_t</span> &particleIdx); <a name="l00192"></a>00192 <span class="comment"></span> <a name="l00193"></a>00193 <span class="comment"> /** Removes a given area from the LMH:</span> <a name="l00194"></a>00194 <span class="comment"> * - The corresponding node in the HMT map is updated with the robot poses & SFs in the LMH.</span> <a name="l00195"></a>00195 <span class="comment"> * - Robot poses belonging to that area are removed from:</span> <a name="l00196"></a>00196 <span class="comment"> * - the particles.</span> <a name="l00197"></a>00197 <span class="comment"> * - the graph partitioner.</span> <a name="l00198"></a>00198 <span class="comment"> * - the list of SFs.</span> <a name="l00199"></a>00199 <span class="comment"> * - the list m_nodeIDmemberships.</span> <a name="l00200"></a>00200 <span class="comment"> * - m_neighbors is updated.</span> <a name="l00201"></a>00201 <span class="comment"> * - The weights of all particles are changed to remove the effects of the removed metric observations.</span> <a name="l00202"></a>00202 <span class="comment"> * - After calling this the metric maps should be updated.</span> <a name="l00203"></a>00203 <span class="comment"> * - This method internally calls updateAreaFromLMH</span> <a name="l00204"></a>00204 <span class="comment"> */</span> <a name="l00205"></a>00205 <span class="keywordtype">void</span> removeAreaFromLMH( <span class="keyword">const</span> <a class="code" href="classmrpt_1_1hmtslam_1_1_c_h_m_h_map_node.html#a4320fd5748b07f6fdb6dd1bdc5b3920e" title="The type of the IDs of nodes.">CHMHMapNode::TNodeID</a> areaID ); <a name="l00206"></a>00206 <span class="comment"></span> <a name="l00207"></a>00207 <span class="comment"> /** The corresponding node in the HMT map is updated with the robot poses & SFs in the LMH: the poses are referenced to the area's reference poseID, such as that reference is at the origin.</span> <a name="l00208"></a>00208 <span class="comment"> * If eraseSFsFromLMH=true, the sensoryframes are moved rather than copied to the area, and removed from the LMH.</span> <a name="l00209"></a>00209 <span class="comment"> * \note The critical section m_map_cs is locked internally, unlock it before calling this.</span> <a name="l00210"></a>00210 <span class="comment"> */</span> <a name="l00211"></a>00211 <span class="keywordtype">void</span> updateAreaFromLMH( <a name="l00212"></a>00212 <span class="keyword">const</span> <a class="code" href="classmrpt_1_1hmtslam_1_1_c_h_m_h_map_node.html#a4320fd5748b07f6fdb6dd1bdc5b3920e" title="The type of the IDs of nodes.">CHMHMapNode::TNodeID</a> areaID, <a name="l00213"></a>00213 <span class="keywordtype">bool</span> eraseSFsFromLMH = <span class="keyword">false</span> ); <a name="l00214"></a>00214 <a name="l00215"></a>00215 <a name="l00216"></a>00216 <span class="keyword">protected</span>: <a name="l00217"></a>00217 <span class="comment"></span> <a name="l00218"></a>00218 <span class="comment"> /** @name Virtual methods for Particle Filter implementation (just a wrapper interface, actually implemented in CHMTSLAM::m_LSLAM_method)</span> <a name="l00219"></a>00219 <span class="comment"> @{</span> <a name="l00220"></a>00220 <span class="comment"> */</span> <a name="l00221"></a>00221 <span class="comment"></span> <a name="l00222"></a>00222 <span class="comment"> /** The PF algorithm implementation.</span> <a name="l00223"></a>00223 <span class="comment"> */</span> <a name="l00224"></a>00224 <span class="keywordtype">void</span> prediction_and_update_pfAuxiliaryPFOptimal( <a name="l00225"></a>00225 <span class="keyword">const</span> <a class="code" href="classmrpt_1_1slam_1_1_c_action_collection.html" title="Declares a class for storing a collection of robot actions.">mrpt::slam::CActionCollection</a> * action, <a name="l00226"></a>00226 <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...">mrpt::slam::CSensoryFrame</a> * observation, <a name="l00227"></a>00227 <span class="keyword">const</span> <a class="code" href="structmrpt_1_1bayes_1_1_c_particle_filter_1_1_t_particle_filter_options.html" title="The configuration of a particle filter.">bayes::CParticleFilter::TParticleFilterOptions</a> &PF_options ); <a name="l00228"></a>00228 <span class="comment"></span> <a name="l00229"></a>00229 <span class="comment"> /** The PF algorithm implementation. */</span> <a name="l00230"></a>00230 <span class="keywordtype">void</span> prediction_and_update_pfOptimalProposal( <a name="l00231"></a>00231 <span class="keyword">const</span> <a class="code" href="classmrpt_1_1slam_1_1_c_action_collection.html" title="Declares a class for storing a collection of robot actions.">mrpt::slam::CActionCollection</a> * action, <a name="l00232"></a>00232 <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...">mrpt::slam::CSensoryFrame</a> * observation, <a name="l00233"></a>00233 <span class="keyword">const</span> <a class="code" href="structmrpt_1_1bayes_1_1_c_particle_filter_1_1_t_particle_filter_options.html" title="The configuration of a particle filter.">bayes::CParticleFilter::TParticleFilterOptions</a> &PF_options );<span class="comment"></span> <a name="l00234"></a>00234 <span class="comment"> /** @}</span> <a name="l00235"></a>00235 <span class="comment"> */</span> <a name="l00236"></a>00236 <a name="l00237"></a>00237 <span class="comment"></span> <a name="l00238"></a>00238 <span class="comment"> /** Auxiliary variable used in the "pfAuxiliaryPFOptimal" algorithm.</span> <a name="l00239"></a>00239 <span class="comment"> */</span> <a name="l00240"></a><a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html#abc11654124437b1de2c11f11b6d4de42">00240</a> <span class="keyword">mutable</span> <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> <a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html#abc11654124437b1de2c11f11b6d4de42" title="Auxiliary variable used in the "pfAuxiliaryPFOptimal" algorithm.">m_pfAuxiliaryPFOptimal_estimatedProb</a>; <a name="l00241"></a>00241 <span class="comment"></span> <a name="l00242"></a>00242 <span class="comment"> /** Auxiliary variable used in the "pfAuxiliaryPFOptimal" algorithm.</span> <a name="l00243"></a>00243 <span class="comment"> */</span> <a name="l00244"></a><a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html#a8fabfc4450cff62dfe7a46394238dac2">00244</a> <span class="keyword">mutable</span> std<a class="code" href="classstd_1_1vector.html">::vector<double></a> <a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html#a8fabfc4450cff62dfe7a46394238dac2" title="Auxiliary variable used in the "pfAuxiliaryPFOptimal" algorithm.">m_maxLikelihood</a>; <a name="l00245"></a>00245 <span class="comment"></span> <a name="l00246"></a>00246 <span class="comment"> /** Auxiliary variable used in the "pfAuxiliaryPFOptimal" algorithm.</span> <a name="l00247"></a>00247 <span class="comment"> */</span> <a name="l00248"></a><a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html#adb3d4f2b5e1ab97d40b9bad40e9a657f">00248</a> <span class="keyword">mutable</span> std<a class="code" href="classstd_1_1vector.html" title="STL class.">::vector<CPose2D,Eigen::aligned_allocator<CPose2D></a> > <a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html#adb3d4f2b5e1ab97d40b9bad40e9a657f" title="Auxiliary variable used in the "pfAuxiliaryPFOptimal" algorithm.">m_movementDraws</a>; <a name="l00249"></a>00249 <span class="comment"></span> <a name="l00250"></a>00250 <span class="comment"> /** Auxiliary variable used in the "pfAuxiliaryPFOptimal" algorithm.</span> <a name="l00251"></a>00251 <span class="comment"> */</span> <a name="l00252"></a><a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html#adf3b8099493296b90d5d8e7ffec620da">00252</a> <span class="keyword">mutable</span> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html#adf3b8099493296b90d5d8e7ffec620da" title="Auxiliary variable used in the "pfAuxiliaryPFOptimal" algorithm.">m_movementDrawsIdx</a>; <a name="l00253"></a>00253 <span class="comment"></span> <a name="l00254"></a>00254 <span class="comment"> /** Auxiliary variable used in the "pfAuxiliaryPFOptimal" algorithm.</span> <a name="l00255"></a>00255 <span class="comment"> */</span> <a name="l00256"></a><a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html#aed755bb8891d2a1dcd96e0b2a17e7db0">00256</a> <span class="keyword">mutable</span> <a class="code" href="classstd_1_1vector.html" title="STL class.">StdVector_CPose2D</a> <a class="code" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html#aed755bb8891d2a1dcd96e0b2a17e7db0" title="Auxiliary variable used in the "pfAuxiliaryPFOptimal" algorithm.">m_movementDrawMaximumLikelihood</a>; <a name="l00257"></a>00257 <a name="l00258"></a>00258 <span class="comment"></span> <a name="l00259"></a>00259 <span class="comment"> /** The following implements:</span> <a name="l00260"></a>00260 <span class="comment"> * - CParticleFilterCapable::getW</span> <a name="l00261"></a>00261 <span class="comment"> * - CParticleFilterCapable::setW</span> <a name="l00262"></a>00262 <span class="comment"> * - CParticleFilterCapable::particlesCount</span> <a name="l00263"></a>00263 <span class="comment"> * - CParticleFilterCapable::normalizeWeights</span> <a name="l00264"></a>00264 <span class="comment"> * - CParticleFilterCapable::ESS</span> <a name="l00265"></a>00265 <span class="comment"> * - CParticleFilterCapable::performSubstitution</span> <a name="l00266"></a>00266 <span class="comment"> */</span> <a name="l00267"></a>00267 <a class="code" href="_c_particle_filter_data_8h.html#a1dab657a0f7d1fe1f4821dbbc2b4ea60" title="This must be placed within the declaration of classes inheriting from both CParticleFilterData and CP...">IMPLEMENT_PARTICLE_FILTER_CAPABLE</a>(<a class="code" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m_particle_data.html" title="Auxiliary class used in mrpt::slam::CLocalMetricHypothesis for HMT-SLAM; this class keeps the data re...">CLSLAMParticleData</a>) <a name="l00268"></a>00268 <a name="l00269"></a>00269 }; <span class="comment">// End of class def.</span> <a name="l00270"></a>00270 <a name="l00271"></a>00271 } <span class="comment">// End of namespace</span> <a name="l00272"></a>00272 } <span class="comment">// End of namespace</span> <a name="l00273"></a>00273 <a name="l00274"></a>00274 <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>