Sophie

Sophie

distrib > Fedora > 16 > i386 > by-pkgid > 4bc66056a634db26a1f4d0845dc41ca6 > files > 1056

mrpt-doc-0.9.5-0.1.20110925svn2670.fc16.i686.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>CMetricMapBuilderRBPF.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.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&#160;Page</span></a></li>
      <li><a href="pages.html"><span>Related&#160;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&#160;List</span></a></li>
      <li><a href="globals.html"><span>File&#160;Members</span></a></li>
    </ul>
  </div>
<div class="header">
  <div class="headertitle">
<div class="title">CMetricMapBuilderRBPF.h</div>  </div>
</div>
<div class="contents">
<a href="_c_metric_map_builder_r_b_p_f_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  &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 CMetricMapBuilderRBPF_H</span>
<a name="l00029"></a>00029 <span class="preprocessor"></span><span class="preprocessor">#define CMetricMapBuilderRBPF_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_metric_map_builder_8h.html">mrpt/slam/CMetricMapBuilder.h</a>&gt;</span>
<a name="l00032"></a>00032 <span class="preprocessor">#include &lt;<a class="code" href="_c_multi_metric_map_p_d_f_8h.html">mrpt/slam/CMultiMetricMapPDF.h</a>&gt;</span>
<a name="l00033"></a>00033 <span class="preprocessor">#include &lt;<a class="code" href="_c_multi_metric_map_8h.html">mrpt/slam/CMultiMetricMap.h</a>&gt;</span>
<a name="l00034"></a>00034 
<a name="l00035"></a>00035 <span class="preprocessor">#include &lt;<a class="code" href="_c_particle_filter_8h.html">mrpt/bayes/CParticleFilter.h</a>&gt;</span>
<a name="l00036"></a>00036 <span class="preprocessor">#include &lt;<a class="code" href="_c_particle_filter_capable_8h.html">mrpt/bayes/CParticleFilterCapable.h</a>&gt;</span>
<a name="l00037"></a>00037 <span class="preprocessor">#include &lt;<a class="code" href="_c_loadable_options_8h.html">mrpt/utils/CLoadableOptions.h</a>&gt;</span>
<a name="l00038"></a>00038 <span class="preprocessor">#include &lt;<a class="code" href="safe__pointers_8h.html">mrpt/utils/safe_pointers.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">        /** This class implements a Rao-Blackwelized Particle Filter (RBPF) approach to map building (SLAM).</span>
<a name="l00047"></a>00047 <span class="comment">         *   Internally, the list of particles, each containing a hypothesis for the robot path plus its associated</span>
<a name="l00048"></a>00048 <span class="comment">         *    metric map, is stored in an object of class CMultiMetricMapPDF.</span>
<a name="l00049"></a>00049 <span class="comment">         *</span>
<a name="l00050"></a>00050 <span class="comment">         *  This class processes robot actions and observations sequentially (through the method CMetricMapBuilderRBPF::processActionObservation)</span>
<a name="l00051"></a>00051 <span class="comment">         *   and exploits the generic design of metric map classes in MRPT to deal with any number and combination of maps simultaneously: the likelihood</span>
<a name="l00052"></a>00052 <span class="comment">         *   of observations is the product of the likelihood in the different maps, etc.</span>
<a name="l00053"></a>00053 <span class="comment">         *</span>
<a name="l00054"></a>00054 <span class="comment">         *   A number of particle filter methods are implemented as well, by selecting the appropriate values in TConstructionOptions::PF_options.</span>
<a name="l00055"></a>00055 <span class="comment">         *   Not all the PF algorithms are implemented for all kinds of maps.</span>
<a name="l00056"></a>00056 <span class="comment">         *</span>
<a name="l00057"></a>00057 <span class="comment">     *  For an example of usage, check the application &quot;rbpf-slam&quot;, in &quot;apps/RBPF-SLAM&quot;. See also the &lt;a href=&quot;http://www.mrpt.org/Application:RBPF-SLAM&quot; &gt;wiki page&lt;/a&gt;.</span>
<a name="l00058"></a>00058 <span class="comment">         *</span>
<a name="l00059"></a>00059 <span class="comment">         *  \note Since MRPT 0.7.2, the new variables &quot;localizeLinDistance,localizeAngDistance&quot; are introduced to provide a way to update the robot pose at a different rate than the map is updated.</span>
<a name="l00060"></a>00060 <span class="comment">         *  \note Since MRPT 0.7.1 the semantics of the parameters &quot;insertionLinDistance&quot; and &quot;insertionAngDistance&quot; changes: the entire RBFP is now NOT updated unless odometry increments surpass the threshold (previously, only the map was NOT updated). This is done to gain efficiency.</span>
<a name="l00061"></a>00061 <span class="comment">         *  \note Since MRPT 0.6.2 this class implements full 6D SLAM. Previous versions worked in 2D + heading only.</span>
<a name="l00062"></a>00062 <span class="comment">         *</span>
<a name="l00063"></a>00063 <span class="comment">         * \sa CMetricMap   \ingroup metric_slam_grp</span>
<a name="l00064"></a>00064 <span class="comment">         */</span>
<a name="l00065"></a>00065         <span class="keyword">class </span><a class="code" href="slam_2include_2mrpt_2slam_2link__pragmas_8h.html#a26118d9c67fb641718c989b57c9acf64">SLAM_IMPEXP</a> CMetricMapBuilderRBPF : <span class="keyword">public</span> CMetricMapBuilder
<a name="l00066"></a>00066         {
<a name="l00067"></a>00067         <span class="keyword">public</span>:<span class="comment"></span>
<a name="l00068"></a>00068 <span class="comment">                /** The map PDF: It includes a path and associated map for each particle.</span>
<a name="l00069"></a>00069 <span class="comment">                  */</span>
<a name="l00070"></a><a class="code" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#a567e3937c2c51bb6c91c5f4370a2a9a9">00070</a>                 <a class="code" href="classmrpt_1_1slam_1_1_c_multi_metric_map_p_d_f.html" title="Declares a class that represents a Rao-Blackwellized set of particles for solving the SLAM problem (T...">CMultiMetricMapPDF</a>                      <a class="code" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#a567e3937c2c51bb6c91c5f4370a2a9a9" title="The map PDF: It includes a path and associated map for each particle.">mapPDF</a>;
<a name="l00071"></a>00071 
<a name="l00072"></a>00072         <span class="keyword">protected</span>:<span class="comment"></span>
<a name="l00073"></a>00073 <span class="comment">        /** The configuration of the particle filter:</span>
<a name="l00074"></a>00074 <span class="comment">          */</span>
<a name="l00075"></a><a class="code" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#a9653b9c2e9afe2de7cc619eda9323b3c">00075</a>                 bayes<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.">::CParticleFilter::TParticleFilterOptions</a>  <a class="code" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#a9653b9c2e9afe2de7cc619eda9323b3c" title="The configuration of the particle filter:">m_PF_options</a>;
<a name="l00076"></a>00076 <span class="comment"></span>
<a name="l00077"></a>00077 <span class="comment">                /** Distances (linear and angular) for inserting a new observation into the map.</span>
<a name="l00078"></a>00078 <span class="comment">                  */</span>
<a name="l00079"></a><a class="code" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#ad0227fba9ff6b0e4b9ca491ed79b2f0e">00079</a>                 <span class="keywordtype">float</span>   <a class="code" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#ad0227fba9ff6b0e4b9ca491ed79b2f0e" title="Distances (linear and angular) for inserting a new observation into the map.">insertionLinDistance</a>,insertionAngDistance;
<a name="l00080"></a>00080 <span class="comment"></span>
<a name="l00081"></a>00081 <span class="comment">                /** Distances (linear and angular) for updating the robot pose estimate (and particles weighs, if applicable).</span>
<a name="l00082"></a>00082 <span class="comment">                  */</span>
<a name="l00083"></a><a class="code" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#ac23cc1def48847393932b55488103ac0">00083</a>                 <span class="keywordtype">float</span>   <a class="code" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#ac23cc1def48847393932b55488103ac0" title="Distances (linear and angular) for updating the robot pose estimate (and particles weighs...">localizeLinDistance</a>,localizeAngDistance;
<a name="l00084"></a>00084 
<a name="l00085"></a>00085 
<a name="l00086"></a><a class="code" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#abdfcc141c475abd6ad54cf0b657c63b8">00086</a>                 mrpt<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 ...">::poses::CPose3DPDFGaussian</a> <a class="code" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#abdfcc141c475abd6ad54cf0b657c63b8" title="Traveled distance since last localization update.">odoIncrementSinceLastLocalization</a>;      <span class="comment">//!&lt; Traveled distance since last localization update</span>
<a name="l00087"></a><a class="code" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#aad453e506dc2700b5c1d7ba9e652c39a">00087</a> <span class="comment"></span>                mrpt<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).">::poses::CPose3D</a>                    <a class="code" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#aad453e506dc2700b5c1d7ba9e652c39a" title="Traveled distance since last map update.">odoIncrementSinceLastMapUpdate</a>;         <span class="comment">//!&lt; Traveled distance since last map update</span>
<a name="l00088"></a>00088 <span class="comment"></span><span class="comment"></span>
<a name="l00089"></a>00089 <span class="comment">                /** A buffer: memory is actually hold within &quot;mapPDF&quot;.</span>
<a name="l00090"></a>00090 <span class="comment">                  */</span>
<a name="l00091"></a><a class="code" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#a9ed28ff34b052e1a82cedc5fd70c3e6a">00091</a>                 <a class="code" href="structmrpt_1_1utils_1_1non__copiable__ptr.html">non_copiable_ptr&lt;CMultiMetricMap&gt;</a>  <a class="code" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#a9ed28ff34b052e1a82cedc5fd70c3e6a" title="A buffer: memory is actually hold within &quot;mapPDF&quot;.">currentMetricMapEstimation</a>;
<a name="l00092"></a>00092 
<a name="l00093"></a>00093         <span class="keyword">public</span>:
<a name="l00094"></a>00094 <span class="comment"></span>
<a name="l00095"></a>00095 <span class="comment">                /** Options for building a CMetricMapBuilderRBPF object, passed to the constructor.</span>
<a name="l00096"></a>00096 <span class="comment">                  */</span>
<a name="l00097"></a>00097                 <span class="keyword">struct </span><a class="code" href="slam_2include_2mrpt_2slam_2link__pragmas_8h.html#a26118d9c67fb641718c989b57c9acf64">SLAM_IMPEXP</a> <a class="code" href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_construction_options.html" title="Options for building a CMetricMapBuilderRBPF object, passed to the constructor.">TConstructionOptions</a> : <span class="keyword">public</span> utils::<a class="code" href="classmrpt_1_1utils_1_1_c_loadable_options.html" title="This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...">CLoadableOptions</a>
<a name="l00098"></a>00098                 {
<a name="l00099"></a>00099                 <span class="keyword">public</span>:<span class="comment"></span>
<a name="l00100"></a>00100 <span class="comment">                        /** Constructor</span>
<a name="l00101"></a>00101 <span class="comment">                          */</span>
<a name="l00102"></a>00102                         <a class="code" href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_construction_options.html" title="Options for building a CMetricMapBuilderRBPF object, passed to the constructor.">TConstructionOptions</a>();
<a name="l00103"></a>00103 <span class="comment"></span>
<a name="l00104"></a>00104 <span class="comment">                        /** See utils::CLoadableOptions</span>
<a name="l00105"></a>00105 <span class="comment">                          */</span>
<a name="l00106"></a>00106                         <span class="keywordtype">void</span>  loadFromConfigFile(
<a name="l00107"></a>00107                                 <span class="keyword">const</span> <a class="code" href="classmrpt_1_1utils_1_1_c_config_file_base.html" title="This class allows loading and storing values and vectors of different types from a configuration text...">mrpt::utils::CConfigFileBase</a>  &amp;source,
<a name="l00108"></a>00108                                 <span class="keyword">const</span> <a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a> &amp;section);
<a name="l00109"></a>00109 <span class="comment"></span>
<a name="l00110"></a>00110 <span class="comment">                        /** See utils::CLoadableOptions</span>
<a name="l00111"></a>00111 <span class="comment">                          */</span>
<a name="l00112"></a>00112                         <span class="keywordtype">void</span>  dumpToTextStream(<a class="code" href="classmrpt_1_1utils_1_1_c_stream.html" title="This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...">CStream</a>  &amp;out) <span class="keyword">const</span>;
<a name="l00113"></a>00113 
<a name="l00114"></a><a class="code" href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_construction_options.html#a2dad221f20665133e0f974f22a85fb99">00114</a>                         <span class="keywordtype">float</span>   <a class="code" href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_construction_options.html#a2dad221f20665133e0f974f22a85fb99">insertionLinDistance</a>;
<a name="l00115"></a><a class="code" href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_construction_options.html#a919afd135d2ce580343daa9870351115">00115</a>                         <span class="keywordtype">float</span>   <a class="code" href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_construction_options.html#a919afd135d2ce580343daa9870351115">insertionAngDistance</a>;
<a name="l00116"></a>00116 
<a name="l00117"></a><a class="code" href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_construction_options.html#ac8570fdd728dc20600b97cf7e36b042f">00117</a>                         <span class="keywordtype">float</span>   <a class="code" href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_construction_options.html#ac8570fdd728dc20600b97cf7e36b042f">localizeLinDistance</a>;
<a name="l00118"></a><a class="code" href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_construction_options.html#a81c9a763f0d79a9930dd6d003267267b">00118</a>                         <span class="keywordtype">float</span>   <a class="code" href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_construction_options.html#a81c9a763f0d79a9930dd6d003267267b">localizeAngDistance</a>;
<a name="l00119"></a>00119 
<a name="l00120"></a><a class="code" href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_construction_options.html#a255075a9c12a6a5f41f87da67d4775ea">00120</a>                         bayes<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.">::CParticleFilter::TParticleFilterOptions</a>  <a class="code" href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_construction_options.html#a255075a9c12a6a5f41f87da67d4775ea">PF_options</a>;
<a name="l00121"></a>00121 
<a name="l00122"></a><a class="code" href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_construction_options.html#a2ef81efd3fb13aa6ab842f2c0b4a5f99">00122</a>                         <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>                                     <a class="code" href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_construction_options.html#a2ef81efd3fb13aa6ab842f2c0b4a5f99">mapsInitializers</a>;
<a name="l00123"></a><a class="code" href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_construction_options.html#a8a7d7d38cf366601c8daa9c00b5c0c10">00123</a>                         <a class="code" href="classmrpt_1_1slam_1_1_c_multi_metric_map_p_d_f.html" title="Declares a class that represents a Rao-Blackwellized set of particles for solving the SLAM problem (T...">CMultiMetricMapPDF</a>::TPredictionParams           <a class="code" href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_construction_options.html#a8a7d7d38cf366601c8daa9c00b5c0c10">predictionOptions</a>;
<a name="l00124"></a>00124                 };
<a name="l00125"></a>00125 <span class="comment"></span>
<a name="l00126"></a>00126 <span class="comment">                /** Constructor.</span>
<a name="l00127"></a>00127 <span class="comment">                 */</span>
<a name="l00128"></a>00128                 <a class="code" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html" title="This class implements a Rao-Blackwelized Particle Filter (RBPF) approach to map building (SLAM)...">CMetricMapBuilderRBPF</a>( <span class="keyword">const</span> <a class="code" href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_construction_options.html" title="Options for building a CMetricMapBuilderRBPF object, passed to the constructor.">TConstructionOptions</a> &amp;initializationOptions );
<a name="l00129"></a>00129 <span class="comment"></span>
<a name="l00130"></a>00130 <span class="comment">                /** Destructor.</span>
<a name="l00131"></a>00131 <span class="comment">                 */</span>
<a name="l00132"></a>00132                 <span class="keyword">virtual</span> ~<a class="code" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html" title="This class implements a Rao-Blackwelized Particle Filter (RBPF) approach to map building (SLAM)...">CMetricMapBuilderRBPF</a>( );
<a name="l00133"></a>00133 <span class="comment"></span>
<a name="l00134"></a>00134 <span class="comment">                /** Initialize the method, starting with a known location PDF &quot;x0&quot;(if supplied, set to NULL to left unmodified) and a given fixed, past map.</span>
<a name="l00135"></a>00135 <span class="comment">                  */</span>
<a name="l00136"></a>00136                 <span class="keywordtype">void</span>  initialize(
<a name="l00137"></a>00137                                 <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 &lt;Probabilistic Pose,SensoryFrame&gt; pairs, thus a &quot;metric map&quot; can be t...">CSimpleMap</a>                &amp;initialMap  = <a class="code" href="classmrpt_1_1slam_1_1_c_simple_map.html" title="This class stores a sequence of &lt;Probabilistic Pose,SensoryFrame&gt; pairs, thus a &quot;metric map&quot; can be t...">CSimpleMap</a>(),
<a name="l00138"></a>00138                                 <a class="code" href="classmrpt_1_1poses_1_1_c_pose_p_d_f.html" title="Declares a class that represents a probability density function (pdf) of a 2D pose (x...">CPosePDF</a>                                        *x0 = NULL
<a name="l00139"></a>00139                                 );
<a name="l00140"></a>00140 <span class="comment"></span>
<a name="l00141"></a>00141 <span class="comment">                /** Clear all elements of the maps.</span>
<a name="l00142"></a>00142 <span class="comment">                  */</span>
<a name="l00143"></a>00143                 <span class="keywordtype">void</span>  clear();
<a name="l00144"></a>00144 <span class="comment"></span>
<a name="l00145"></a>00145 <span class="comment">                /** Returns a copy of the current best pose estimation as a pose PDF.</span>
<a name="l00146"></a>00146 <span class="comment">                  */</span>
<a name="l00147"></a>00147                 <a class="code" href="structmrpt_1_1poses_1_1_c_pose3_d_p_d_f_ptr.html">CPose3DPDFPtr</a>  getCurrentPoseEstimation() <span class="keyword">const</span>;
<a name="l00148"></a>00148 <span class="comment"></span>
<a name="l00149"></a>00149 <span class="comment">                /** Returns the current most-likely path estimation (the path associated to the most likely particle).</span>
<a name="l00150"></a>00150 <span class="comment">                  */</span>
<a name="l00151"></a>00151                 <span class="keywordtype">void</span>  getCurrentMostLikelyPath( <a class="code" href="classstd_1_1deque.html">std::deque&lt;TPose3D&gt;</a> &amp;outPath ) <span class="keyword">const</span>;
<a name="l00152"></a>00152 <span class="comment"></span>
<a name="l00153"></a>00153 <span class="comment">                /** Appends a new action and observations to update this map: See the description of the class at the top of this page to see a more complete description.</span>
<a name="l00154"></a>00154 <span class="comment">                 *  \param action The incremental 2D pose change in the robot pose. This value is deterministic.</span>
<a name="l00155"></a>00155 <span class="comment">                 *      \param observations The set of observations that robot senses at the new pose.</span>
<a name="l00156"></a>00156 <span class="comment">                 *  Statistics will be saved to statsLastIteration</span>
<a name="l00157"></a>00157 <span class="comment">                 */</span>
<a name="l00158"></a>00158                 <span class="keywordtype">void</span>  processActionObservation(
<a name="l00159"></a>00159                                         <a class="code" href="classmrpt_1_1slam_1_1_c_action_collection.html" title="Declares a class for storing a collection of robot actions.">CActionCollection</a>       &amp;action,
<a name="l00160"></a>00160                                         <a class="code" href="classmrpt_1_1slam_1_1_c_sensory_frame.html" title="Declares a class for storing a &quot;sensory frame&quot;, a set of &quot;observations&quot; taken by the robot approximat...">CSensoryFrame</a>           &amp;observations );
<a name="l00161"></a>00161 <span class="comment"></span>
<a name="l00162"></a>00162 <span class="comment">                /** Fills &quot;out_map&quot; with the set of &quot;poses&quot;-&quot;sensory-frames&quot;, thus the so far built map.</span>
<a name="l00163"></a>00163 <span class="comment">                  */</span>
<a name="l00164"></a>00164                 <span class="keywordtype">void</span>  getCurrentlyBuiltMap(<a class="code" href="classmrpt_1_1slam_1_1_c_simple_map.html" title="This class stores a sequence of &lt;Probabilistic Pose,SensoryFrame&gt; pairs, thus a &quot;metric map&quot; can be t...">CSimpleMap</a> &amp;out_map) <span class="keyword">const</span>;
<a name="l00165"></a>00165 <span class="comment"></span>
<a name="l00166"></a>00166 <span class="comment">                /** Returns the map built so far. NOTE that for efficiency a pointer to the internal object is passed, DO NOT delete nor modify the object in any way, if desired, make a copy of ir with &quot;duplicate()&quot;.</span>
<a name="l00167"></a>00167 <span class="comment">                  */</span>
<a name="l00168"></a>00168                 <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>*   getCurrentlyBuiltMetricMap();
<a name="l00169"></a>00169 <span class="comment"></span>
<a name="l00170"></a>00170 <span class="comment">                /** Returns just how many sensory-frames are stored in the currently build map.</span>
<a name="l00171"></a>00171 <span class="comment">                  */</span>
<a name="l00172"></a>00172                 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span>  getCurrentlyBuiltMapSize();
<a name="l00173"></a>00173 <span class="comment"></span>
<a name="l00174"></a>00174 <span class="comment">                /** A useful method for debugging: the current map (and/or poses) estimation is dumped to an image file.</span>
<a name="l00175"></a>00175 <span class="comment">                  * \param file The output file name</span>
<a name="l00176"></a>00176 <span class="comment">                  * \param formatEMF_BMP Output format = true:EMF, false:BMP</span>
<a name="l00177"></a>00177 <span class="comment">                  */</span>
<a name="l00178"></a>00178                 <span class="keywordtype">void</span>  saveCurrentEstimationToImage(<span class="keyword">const</span> <a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a> &amp;file, <span class="keywordtype">bool</span> formatEMF_BMP = <span class="keyword">true</span>);
<a name="l00179"></a>00179 <span class="comment"></span>
<a name="l00180"></a>00180 <span class="comment">                /** A usefull method for debugging: draws the current map and path hypotheses to a CCanvas</span>
<a name="l00181"></a>00181 <span class="comment">                  */</span>
<a name="l00182"></a>00182                 <span class="keywordtype">void</span>  drawCurrentEstimationToImage( <a class="code" href="classmrpt_1_1utils_1_1_c_canvas.html" title="This virtual class defines the interface of any object accepting drawing primitives on it...">utils::CCanvas</a> *img );
<a name="l00183"></a>00183 <span class="comment"></span>
<a name="l00184"></a>00184 <span class="comment">                /** A logging utility: saves the current path estimation for each particle in a text file (a row per particle, each 3-column-entry is a set [x,y,phi], respectively).</span>
<a name="l00185"></a>00185 <span class="comment">                  */</span>
<a name="l00186"></a>00186                 <span class="keywordtype">void</span>  saveCurrentPathEstimationToTextFile( <a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a>  fil );
<a name="l00187"></a>00187 
<a name="l00188"></a>00188                 <span class="keywordtype">double</span>  getCurrentJointEntropy();
<a name="l00189"></a>00189 <span class="comment"></span>
<a name="l00190"></a>00190 <span class="comment">                /** This structure will hold stats after each execution of processActionObservation</span>
<a name="l00191"></a>00191 <span class="comment">                  */</span>
<a name="l00192"></a>00192                 <span class="keyword">struct </span><a class="code" href="slam_2include_2mrpt_2slam_2link__pragmas_8h.html#a26118d9c67fb641718c989b57c9acf64">SLAM_IMPEXP</a> <a class="code" href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_stats.html" title="This structure will hold stats after each execution of processActionObservation.">TStats</a>
<a name="l00193"></a>00193                 {
<a name="l00194"></a><a class="code" href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_stats.html#a63c85dfafc3eeb9e52f6f7c58f97f598">00194</a>                         <a class="code" href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_stats.html" title="This structure will hold stats after each execution of processActionObservation.">TStats</a>() :
<a name="l00195"></a>00195                                 observationsInserted(false)
<a name="l00196"></a>00196                         { }
<a name="l00197"></a>00197 <span class="comment"></span>
<a name="l00198"></a>00198 <span class="comment">                        /** Whether the SF has been inserted in the metric maps. */</span>
<a name="l00199"></a><a class="code" href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_stats.html#a867a89284628cf0c9122e2906d136fcd">00199</a>                         <span class="keywordtype">bool</span>    <a class="code" href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_stats.html#a867a89284628cf0c9122e2906d136fcd" title="Whether the SF has been inserted in the metric maps.">observationsInserted</a>;
<a name="l00200"></a>00200 
<a name="l00201"></a>00201                 };
<a name="l00202"></a>00202 
<a name="l00203"></a>00203 <span class="comment"></span>
<a name="l00204"></a>00204 <span class="comment">                /** This structure will hold stats after each execution of processActionObservation</span>
<a name="l00205"></a>00205 <span class="comment">                  */</span>
<a name="l00206"></a><a class="code" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#a7248f9700730c83e208f542f30899a3b">00206</a>                 <a class="code" href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_stats.html" title="This structure will hold stats after each execution of processActionObservation.">TStats</a>          <a class="code" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#a7248f9700730c83e208f542f30899a3b" title="This structure will hold stats after each execution of processActionObservation.">m_statsLastIteration</a>;
<a name="l00207"></a>00207 
<a name="l00208"></a>00208         }; <span class="comment">// End of class def.</span>
<a name="l00209"></a>00209 
<a name="l00210"></a>00210         } <span class="comment">// End of namespace</span>
<a name="l00211"></a>00211 } <span class="comment">// End of namespace</span>
<a name="l00212"></a>00212 
<a name="l00213"></a>00213 <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>