Sophie

Sophie

distrib > Fedora > 14 > x86_64 > by-pkgid > e6f1a3debfddb2a6cccaab627266a0ea > files > 1007

mrpt-doc-0.9.0-0.5.fc14.x86_64.rpm

<!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>The MRPT project: CMetricMapsAlignmentAlgorithm.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> &gt; <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.6.2-20100208 -->
<script type="text/javascript"><!--
var searchBox = new SearchBox("searchBox", "search",false,'Search');
--></script>
<div class="navigation" id="top">
  <div class="tabs">
    <ul>
      <li><a href="index.html"><span>Main&nbsp;Page</span></a></li>
      <li><a href="pages.html"><span>Related&nbsp;Pages</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">
        <img id="MSearchSelect" src="search/search.png"
             onmouseover="return searchBox.OnSearchSelectShow()"
             onmouseout="return searchBox.OnSearchSelectHide()"
             alt=""/>
        <input type="text" id="MSearchField" value="Search" accesskey="S"
             onfocus="searchBox.OnSearchFieldFocus(true)" 
             onblur="searchBox.OnSearchFieldFocus(false)" 
             onkeyup="searchBox.OnSearchFieldChange(event)"/>
        <a id="MSearchClose" href="javascript:searchBox.CloseResultsWindow()"><img id="MSearchCloseImg" border="0" src="search/close.png" alt=""/></a>
        </div>
      </li>
    </ul>
  </div>
  <div class="tabs">
    <ul>
      <li><a href="files.html"><span>File&nbsp;List</span></a></li>
      <li><a href="globals.html"><span>File&nbsp;Members</span></a></li>
    </ul>
  </div>
<h1>CMetricMapsAlignmentAlgorithm.h</h1><a href="_c_metric_maps_alignment_algorithm_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://mrpt.sourceforge.net/                            |</span>
<a name="l00005"></a>00005 <span class="comment">   |                                                                           |</span>
<a name="l00006"></a>00006 <span class="comment">   |   Copyright (C) 2005-2010  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  &lt;jlblanco@ctima.uma.es&gt;                     |</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 &lt;http://www.gnu.org/licenses/&gt;.         |</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 CMetricMapsAlignmentAlgorithm_H</span>
<a name="l00029"></a>00029 <span class="preprocessor"></span><span class="preprocessor">#define CMetricMapsAlignmentAlgorithm_H</span>
<a name="l00030"></a>00030 <span class="preprocessor"></span>
<a name="l00031"></a>00031 <span class="preprocessor">#include &lt;<a class="code" href="_c_points_map_8h.html">mrpt/slam/CPointsMap.h</a>&gt;</span>
<a name="l00032"></a>00032 <span class="preprocessor">#include &lt;<a class="code" href="_c_pose2_d_8h.html">mrpt/poses/CPose2D.h</a>&gt;</span>
<a name="l00033"></a>00033 <span class="preprocessor">#include &lt;<a class="code" href="_c_pose_p_d_f_8h.html">mrpt/poses/CPosePDF.h</a>&gt;</span>
<a name="l00034"></a>00034 <span class="preprocessor">#include &lt;<a class="code" href="_c_pose3_d_p_d_f_8h.html">mrpt/poses/CPose3DPDF.h</a>&gt;</span>
<a name="l00035"></a>00035 <span class="preprocessor">#include &lt;<a class="code" href="_c_pose_p_d_f_gaussian_8h.html">mrpt/poses/CPosePDFGaussian.h</a>&gt;</span>
<a name="l00036"></a>00036 <span class="preprocessor">#include &lt;<a class="code" href="_c_pose3_d_p_d_f_gaussian_8h.html">mrpt/poses/CPose3DPDFGaussian.h</a>&gt;</span>
<a name="l00037"></a>00037 
<a name="l00038"></a>00038 <span class="preprocessor">#include &lt;<a class="code" href="_c_debug_output_capable_8h.html">mrpt/utils/CDebugOutputCapable.h</a>&gt;</span>
<a name="l00039"></a>00039 
<a name="l00040"></a>00040 <span class="preprocessor">#include &lt;<a class="code" href="slam_2include_2mrpt_2slam_2link__pragmas_8h.html">mrpt/slam/link_pragmas.h</a>&gt;</span>
<a name="l00041"></a>00041 
<a name="l00042"></a>00042 <span class="keyword">namespace </span>mrpt
<a name="l00043"></a>00043 {
<a name="l00044"></a>00044 <span class="keyword">namespace </span>slam
<a name="l00045"></a>00045 {<span class="comment"></span>
<a name="l00046"></a>00046 <span class="comment">        /** A base class for any algorithm able of maps alignment. There are two methods</span>
<a name="l00047"></a>00047 <span class="comment">         *   depending on an PDF or a single 2D Pose value is available as initial guess for the methods.</span>
<a name="l00048"></a>00048 <span class="comment">     *</span>
<a name="l00049"></a>00049 <span class="comment">         * \sa CPointsMap, utils::CDebugOutputCapable</span>
<a name="l00050"></a>00050 <span class="comment">         */</span>
<a name="l00051"></a><a class="code" href="classmrpt_1_1slam_1_1_c_metric_maps_alignment_algorithm.html">00051</a>         <span class="keyword">class </span><a class="code" href="slam_2include_2mrpt_2slam_2link__pragmas_8h.html#a26118d9c67fb641718c989b57c9acf64">SLAM_IMPEXP</a>  <a class="code" href="classmrpt_1_1slam_1_1_c_metric_maps_alignment_algorithm.html" title="A base class for any algorithm able of maps alignment.">CMetricMapsAlignmentAlgorithm</a> : <span class="keyword">public</span> mrpt::utils::<a class="code" href="classmrpt_1_1utils_1_1_c_debug_output_capable.html" title="This base class provides a common printf-like method to send debug information to...">CDebugOutputCapable</a>
<a name="l00052"></a>00052         {
<a name="l00053"></a>00053         <span class="keyword">public</span>:<span class="comment"></span>
<a name="l00054"></a>00054 <span class="comment">        /** Destructor</span>
<a name="l00055"></a>00055 <span class="comment">          */</span>
<a name="l00056"></a><a class="code" href="classmrpt_1_1slam_1_1_c_metric_maps_alignment_algorithm.html#af8229035ad0a58e120e61e690a5639c9">00056</a>         <span class="keyword">virtual</span> ~<a class="code" href="classmrpt_1_1slam_1_1_c_metric_maps_alignment_algorithm.html" title="A base class for any algorithm able of maps alignment.">CMetricMapsAlignmentAlgorithm</a>()
<a name="l00057"></a>00057         {
<a name="l00058"></a>00058         }
<a name="l00059"></a>00059 <span class="comment"></span>
<a name="l00060"></a>00060 <span class="comment">                /** The method for aligning a pair of metric maps, aligning only 2D + orientation.</span>
<a name="l00061"></a>00061 <span class="comment">                 *   The meaning of some parameters and the kind of the maps to be aligned are implementation dependant,</span>
<a name="l00062"></a>00062 <span class="comment">                 *    so look into the derived classes for instructions.</span>
<a name="l00063"></a>00063 <span class="comment">                 *  The target is to find a PDF for the pose displacement between</span>
<a name="l00064"></a>00064 <span class="comment">                 *   maps, &lt;b&gt;thus the pose of m2 relative to m1&lt;/b&gt;. This pose</span>
<a name="l00065"></a>00065 <span class="comment">                 *   is returned as a PDF rather than a single value.</span>
<a name="l00066"></a>00066 <span class="comment">                 *</span>
<a name="l00067"></a>00067 <span class="comment">                 * \param m1                    [IN] The first map</span>
<a name="l00068"></a>00068 <span class="comment">                 * \param m2                    [IN] The second map. The pose of this map respect to m1 is to be estimated.</span>
<a name="l00069"></a>00069 <span class="comment">                 * \param grossEst              [IN] An initial gross estimation for the displacement. If a given algorithm doesn&#39;t need it, set to &lt;code&gt;CPose2D(0,0,0)&lt;/code&gt; for example.</span>
<a name="l00070"></a>00070 <span class="comment">                 * \param runningTime   [OUT] A pointer to a container for obtaining the algorithm running time in seconds, or NULL if you don&#39;t need it.</span>
<a name="l00071"></a>00071 <span class="comment">                 * \param info                  [OUT] See derived classes for details, or NULL if it isn&#39;t needed.</span>
<a name="l00072"></a>00072 <span class="comment">                 *</span>
<a name="l00073"></a>00073 <span class="comment">                 * \return A smart pointer to the output estimated pose PDF.</span>
<a name="l00074"></a>00074 <span class="comment">                 * \sa CICP</span>
<a name="l00075"></a>00075 <span class="comment">                 */</span>
<a name="l00076"></a>00076                 CPosePDFPtr Align(
<a name="l00077"></a>00077                                 <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>                *m1,
<a name="l00078"></a>00078                                 <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>                *m2,
<a name="l00079"></a>00079                                 <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>                   &amp;grossEst,
<a name="l00080"></a>00080                                 <span class="keywordtype">float</span>                                   *runningTime = NULL,
<a name="l00081"></a>00081                                 <span class="keywordtype">void</span>                                    *info = NULL );
<a name="l00082"></a>00082 <span class="comment"></span>
<a name="l00083"></a>00083 <span class="comment">        /** The virtual method for aligning a pair of metric maps, aligning only 2D + orientation.</span>
<a name="l00084"></a>00084 <span class="comment">                 *   The meaning of some parameters are implementation dependant,</span>
<a name="l00085"></a>00085 <span class="comment">                 *    so look at the derived classes for more details.</span>
<a name="l00086"></a>00086 <span class="comment">                 *  The goal is to find a PDF for the pose displacement between</span>
<a name="l00087"></a>00087 <span class="comment">                 *   maps, that is, &lt;b&gt;the pose of m2 relative to m1&lt;/b&gt;. This pose</span>
<a name="l00088"></a>00088 <span class="comment">                 *   is returned as a PDF rather than a single value.</span>
<a name="l00089"></a>00089 <span class="comment">                 *</span>
<a name="l00090"></a>00090 <span class="comment">                 *  \note This method can be configurated with a &quot;options&quot; structure in the implementation classes.</span>
<a name="l00091"></a>00091 <span class="comment">                 *</span>
<a name="l00092"></a>00092 <span class="comment">                 * \param m1                    [IN] The first map (MUST BE A COccupancyGridMap2D  derived class)</span>
<a name="l00093"></a>00093 <span class="comment">                 * \param m2                    [IN] The second map. (MUST BE A CPointsMap derived class) The pose of this map respect to m1 is to be estimated.</span>
<a name="l00094"></a>00094 <span class="comment">                 * \param initialEstimationPDF  [IN] An initial gross estimation for the displacement.</span>
<a name="l00095"></a>00095 <span class="comment">                 * \param runningTime   [OUT] A pointer to a container for obtaining the algorithm running time in seconds, or NULL if you don&#39;t need it.</span>
<a name="l00096"></a>00096 <span class="comment">                 * \param info                  [OUT] See derived classes for details, or NULL if it isn&#39;t needed.</span>
<a name="l00097"></a>00097 <span class="comment">                 *</span>
<a name="l00098"></a>00098 <span class="comment">                 * \return A smart pointer to the output estimated pose PDF.</span>
<a name="l00099"></a>00099 <span class="comment">                 * \sa CICP</span>
<a name="l00100"></a>00100 <span class="comment">                 */</span>
<a name="l00101"></a>00101                 <span class="keyword">virtual</span> CPosePDFPtr AlignPDF(
<a name="l00102"></a>00102                                 <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>                *m1,
<a name="l00103"></a>00103                                 <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>                *m2,
<a name="l00104"></a>00104                                 <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose_p_d_f_gaussian.html" title="Declares a class that represents a Probability Density function (PDF) of a 2D pose...">CPosePDFGaussian</a>  &amp;initialEstimationPDF,
<a name="l00105"></a>00105                                 <span class="keywordtype">float</span>                                   *runningTime = NULL,
<a name="l00106"></a>00106                                 <span class="keywordtype">void</span>                                    *info = NULL ) = 0;
<a name="l00107"></a>00107 
<a name="l00108"></a>00108 <span class="comment"></span>
<a name="l00109"></a>00109 <span class="comment">                /** The method for aligning a pair of metric maps, aligning the full 6D pose.</span>
<a name="l00110"></a>00110 <span class="comment">                 *   The meaning of some parameters and the kind of the maps to be aligned are implementation dependant,</span>
<a name="l00111"></a>00111 <span class="comment">                 *    so look into the derived classes for instructions.</span>
<a name="l00112"></a>00112 <span class="comment">                 *  The target is to find a PDF for the pose displacement between</span>
<a name="l00113"></a>00113 <span class="comment">                 *   maps, &lt;b&gt;thus the pose of m2 relative to m1&lt;/b&gt;. This pose</span>
<a name="l00114"></a>00114 <span class="comment">                 *   is returned as a PDF rather than a single value.</span>
<a name="l00115"></a>00115 <span class="comment">                 *</span>
<a name="l00116"></a>00116 <span class="comment">                 * \param m1                    [IN] The first map</span>
<a name="l00117"></a>00117 <span class="comment">                 * \param m2                    [IN] The second map. The pose of this map respect to m1 is to be estimated.</span>
<a name="l00118"></a>00118 <span class="comment">                 * \param grossEst              [IN] An initial gross estimation for the displacement. If a given algorithm doesn&#39;t need it, set to &lt;code&gt;CPose3D(0,0,0)&lt;/code&gt; for example.</span>
<a name="l00119"></a>00119 <span class="comment">                 * \param runningTime   [OUT] A pointer to a container for obtaining the algorithm running time in seconds, or NULL if you don&#39;t need it.</span>
<a name="l00120"></a>00120 <span class="comment">                 * \param info                  [OUT] See derived classes for details, or NULL if it isn&#39;t needed.</span>
<a name="l00121"></a>00121 <span class="comment">                 *</span>
<a name="l00122"></a>00122 <span class="comment">                 * \return A smart pointer to the output estimated pose PDF.</span>
<a name="l00123"></a>00123 <span class="comment">                 * \sa CICP</span>
<a name="l00124"></a>00124 <span class="comment">                 */</span>
<a name="l00125"></a>00125                 CPose3DPDFPtr Align3D(
<a name="l00126"></a>00126                                 <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>                *m1,
<a name="l00127"></a>00127                                 <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>                *m2,
<a name="l00128"></a>00128                                 <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.">CPose3D</a>                   &amp;grossEst,
<a name="l00129"></a>00129                                 <span class="keywordtype">float</span>                                   *runningTime = NULL,
<a name="l00130"></a>00130                                 <span class="keywordtype">void</span>                                    *info = NULL );
<a name="l00131"></a>00131 <span class="comment"></span>
<a name="l00132"></a>00132 <span class="comment">        /** The virtual method for aligning a pair of metric maps, aligning the full 6D pose.</span>
<a name="l00133"></a>00133 <span class="comment">                 *   The meaning of some parameters are implementation dependant,</span>
<a name="l00134"></a>00134 <span class="comment">                 *    so look at the derived classes for more details.</span>
<a name="l00135"></a>00135 <span class="comment">                 *  The goal is to find a PDF for the pose displacement between</span>
<a name="l00136"></a>00136 <span class="comment">                 *   maps, that is, &lt;b&gt;the pose of m2 relative to m1&lt;/b&gt;. This pose</span>
<a name="l00137"></a>00137 <span class="comment">                 *   is returned as a PDF rather than a single value.</span>
<a name="l00138"></a>00138 <span class="comment">                 *</span>
<a name="l00139"></a>00139 <span class="comment">                 *  \note This method can be configurated with a &quot;options&quot; structure in the implementation classes.</span>
<a name="l00140"></a>00140 <span class="comment">                 *</span>
<a name="l00141"></a>00141 <span class="comment">                 * \param m1                    [IN] The first map (MUST BE A COccupancyGridMap2D  derived class)</span>
<a name="l00142"></a>00142 <span class="comment">                 * \param m2                    [IN] The second map. (MUST BE A CPointsMap derived class) The pose of this map respect to m1 is to be estimated.</span>
<a name="l00143"></a>00143 <span class="comment">                 * \param initialEstimationPDF  [IN] An initial gross estimation for the displacement.</span>
<a name="l00144"></a>00144 <span class="comment">                 * \param runningTime   [OUT] A pointer to a container for obtaining the algorithm running time in seconds, or NULL if you don&#39;t need it.</span>
<a name="l00145"></a>00145 <span class="comment">                 * \param info                  [OUT] See derived classes for details, or NULL if it isn&#39;t needed.</span>
<a name="l00146"></a>00146 <span class="comment">                 *</span>
<a name="l00147"></a>00147 <span class="comment">                 * \return A smart pointer to the output estimated pose PDF.</span>
<a name="l00148"></a>00148 <span class="comment">                 * \sa CICP</span>
<a name="l00149"></a>00149 <span class="comment">                 */</span>
<a name="l00150"></a>00150                 <span class="keyword">virtual</span> CPose3DPDFPtr Align3DPDF(
<a name="l00151"></a>00151                                 <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>                *m1,
<a name="l00152"></a>00152                                 <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>                *m2,
<a name="l00153"></a>00153                                 <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian.html" title="Declares a class that represents a Probability Density function (PDF) of a 3D pose...">CPose3DPDFGaussian</a>        &amp;initialEstimationPDF,
<a name="l00154"></a>00154                                 <span class="keywordtype">float</span>                                   *runningTime = NULL,
<a name="l00155"></a>00155                                 <span class="keywordtype">void</span>                                    *info = NULL ) = 0;
<a name="l00156"></a>00156 
<a name="l00157"></a>00157 
<a name="l00158"></a>00158         };
<a name="l00159"></a>00159 
<a name="l00160"></a>00160         } <span class="comment">// End of namespace</span>
<a name="l00161"></a>00161 } <span class="comment">// End of namespace</span>
<a name="l00162"></a>00162 
<a name="l00163"></a>00163 <span class="preprocessor">#endif</span>
</pre></div></div>
<!--- window showing the filter options -->
<div id="MSearchSelectWindow"
     onmouseover="return searchBox.OnSearchSelectShow()"
     onmouseout="return searchBox.OnSearchSelectHide()"
     onkeydown="return searchBox.OnSearchSelectKey(event)">
<a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(0)"><span class="SelectionMark">&nbsp;</span>All</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(1)"><span class="SelectionMark">&nbsp;</span>Classes</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(2)"><span class="SelectionMark">&nbsp;</span>Namespaces</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(3)"><span class="SelectionMark">&nbsp;</span>Files</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(4)"><span class="SelectionMark">&nbsp;</span>Functions</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(5)"><span class="SelectionMark">&nbsp;</span>Variables</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(6)"><span class="SelectionMark">&nbsp;</span>Typedefs</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(7)"><span class="SelectionMark">&nbsp;</span>Enumerations</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(8)"><span class="SelectionMark">&nbsp;</span>Enumerator</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(9)"><span class="SelectionMark">&nbsp;</span>Friends</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(10)"><span class="SelectionMark">&nbsp;</span>Defines</a></div>

<!-- iframe showing the search results (closed by default) -->
<div id="MSearchResultsWindow">
<iframe src="" frameborder="0" 
        name="MSearchResults" id="MSearchResults">
</iframe>
</div>

<br><hr><br> <table border="0" width="100%"> <tr> <td> Page generated by <a href="http://www.doxygen.org" target="_blank">Doxygen 1.6.2-20100208</a> for MRPT 0.9.0 SVN: at Wed Jul 14 12:48:09 UTC 2010</td><td></td> <td width="100"> </td> <td width="150">  </td></tr> </table> </body></html>