Sophie

Sophie

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

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>mrpt::hmtslam::CLSLAMAlgorithmBase Class Reference</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 class="current"><a href="annotated.html"><span>Classes</span></a></li>
      <li><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="annotated.html"><span>Class&#160;List</span></a></li>
      <li><a href="classes.html"><span>Class&#160;Index</span></a></li>
      <li><a href="inherits.html"><span>Class&#160;Hierarchy</span></a></li>
      <li><a href="functions.html"><span>Class&#160;Members</span></a></li>
    </ul>
  </div>
  <div id="nav-path" class="navpath">
    <ul>
      <li class="navelem"><a class="el" href="namespacemrpt.html">mrpt</a>      </li>
      <li class="navelem"><a class="el" href="namespacemrpt_1_1hmtslam.html">hmtslam</a>      </li>
      <li class="navelem"><a class="el" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m_algorithm_base.html">CLSLAMAlgorithmBase</a>      </li>
    </ul>
  </div>
</div>
<div class="header">
  <div class="summary">
<a href="#pub-methods">Public Member Functions</a> &#124;
<a href="#pro-attribs">Protected Attributes</a> &#124;
<a href="#friends">Friends</a>  </div>
  <div class="headertitle">
<div class="title">mrpt::hmtslam::CLSLAMAlgorithmBase Class Reference</div>  </div>
</div>
<div class="contents">
<!-- doxytag: class="mrpt::hmtslam::CLSLAMAlgorithmBase" --><hr/><a name="details" id="details"></a><h2>Detailed Description</h2>
<div class="textblock"><p>Virtual base for local SLAM methods, used in mrpt::slam::CHMTSLAM. </p>
</div>
<p><code>#include &lt;<a class="el" href="_c_h_m_t_s_l_a_m_8h_source.html">mrpt/hmtslam/CHMTSLAM.h</a>&gt;</code></p>
<div class="dynheader">
Inheritance diagram for mrpt::hmtslam::CLSLAMAlgorithmBase:</div>
<div class="dyncontent">
<div class="center"><img src="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m_algorithm_base__inherit__graph.png" border="0" usemap="#mrpt_1_1hmtslam_1_1_c_l_s_l_a_m_algorithm_base_inherit__map" alt="Inheritance graph"/></div>
<map name="mrpt_1_1hmtslam_1_1_c_l_s_l_a_m_algorithm_base_inherit__map" id="mrpt_1_1hmtslam_1_1_c_l_s_l_a_m_algorithm_base_inherit__map">
<area shape="rect" id="node3" 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." alt="" coords="5,80,283,107"/></map>
<center><span class="legend">[<a href="graph_legend.html">legend</a>]</span></center></div>

<p><a href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m_algorithm_base-members.html">List of all members.</a></p>
<table class="memberdecls">
<tr><td colspan="2"><h2><a name="pub-methods"></a>
Public Member Functions</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m_algorithm_base.html#ac1de06d65dfc1b051c1c21bd77c6cd16">CLSLAMAlgorithmBase</a> (<a class="el" href="classmrpt_1_1hmtslam_1_1_c_h_m_t_s_l_a_m.html">CHMTSLAM</a> *parent)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Constructor.  <a href="#ac1de06d65dfc1b051c1c21bd77c6cd16"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">virtual&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m_algorithm_base.html#a71e840844a7041637a107b885ef5bd5f">~CLSLAMAlgorithmBase</a> ()</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Destructor.  <a href="#a71e840844a7041637a107b885ef5bd5f"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m_algorithm_base.html#a21d3c172cb3ac6a371b8c46b0164c3f6">processOneLMH</a> (<a class="el" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html">CLocalMetricHypothesis</a> *LMH, const <a class="el" href="structmrpt_1_1slam_1_1_c_action_collection_ptr.html">CActionCollectionPtr</a> &amp;act, const <a class="el" href="structmrpt_1_1slam_1_1_c_sensory_frame_ptr.html">CSensoryFramePtr</a> &amp;sf)=0</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Main entry point from HMT-SLAM: process some actions &amp; observations.  <a href="#a21d3c172cb3ac6a371b8c46b0164c3f6"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m_algorithm_base.html#a28469cf7e21f441a35db66e42b5e0866">prediction_and_update_pfAuxiliaryPFOptimal</a> (<a class="el" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html">CLocalMetricHypothesis</a> *LMH, const <a class="el" href="classmrpt_1_1slam_1_1_c_action_collection.html">mrpt::slam::CActionCollection</a> *action, const <a class="el" href="classmrpt_1_1slam_1_1_c_sensory_frame.html">mrpt::slam::CSensoryFrame</a> *observation, const <a class="el" href="structmrpt_1_1bayes_1_1_c_particle_filter_1_1_t_particle_filter_options.html">bayes::CParticleFilter::TParticleFilterOptions</a> &amp;PF_options)=0</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The PF algorithm implementation.  <a href="#a28469cf7e21f441a35db66e42b5e0866"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m_algorithm_base.html#ad6e794f4bccd7375f00c00706d7a27aa">prediction_and_update_pfOptimalProposal</a> (<a class="el" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html">CLocalMetricHypothesis</a> *LMH, const <a class="el" href="classmrpt_1_1slam_1_1_c_action_collection.html">mrpt::slam::CActionCollection</a> *action, const <a class="el" href="classmrpt_1_1slam_1_1_c_sensory_frame.html">mrpt::slam::CSensoryFrame</a> *observation, const <a class="el" href="structmrpt_1_1bayes_1_1_c_particle_filter_1_1_t_particle_filter_options.html">bayes::CParticleFilter::TParticleFilterOptions</a> &amp;PF_options)=0</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The PF algorithm implementation.  <a href="#ad6e794f4bccd7375f00c00706d7a27aa"></a><br/></td></tr>
<tr><td colspan="2"><h2><a name="pro-attribs"></a>
Protected Attributes</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="structmrpt_1_1utils_1_1safe__ptr.html">safe_ptr</a>&lt; <a class="el" href="classmrpt_1_1hmtslam_1_1_c_h_m_t_s_l_a_m.html">CHMTSLAM</a> &gt;&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m_algorithm_base.html#a7fbb8903f004411c76e55d45df946efe">m_parent</a></td></tr>
<tr><td colspan="2"><h2><a name="friends"></a>
Friends</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">class HMTSLAM_IMPEXP&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m_algorithm_base.html#a8be947851baa9c04c2c4d71eae9b76cf">CLocalMetricHypothesis</a></td></tr>
</table>
<hr/><h2>Constructor &amp; Destructor Documentation</h2>
<a class="anchor" id="ac1de06d65dfc1b051c1c21bd77c6cd16"></a><!-- doxytag: member="mrpt::hmtslam::CLSLAMAlgorithmBase::CLSLAMAlgorithmBase" ref="ac1de06d65dfc1b051c1c21bd77c6cd16" args="(CHMTSLAM *parent)" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">mrpt::hmtslam::CLSLAMAlgorithmBase::CLSLAMAlgorithmBase </td>
          <td>(</td>
          <td class="paramtype"><a class="el" href="classmrpt_1_1hmtslam_1_1_c_h_m_t_s_l_a_m.html">CHMTSLAM</a> *&#160;</td>
          <td class="paramname"><em>parent</em></td><td>)</td>
          <td><code> [inline]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Constructor. </p>

<p>Definition at line <a class="el" href="_c_h_m_t_s_l_a_m_8h_source.html#l00515">515</a> of file <a class="el" href="_c_h_m_t_s_l_a_m_8h_source.html">CHMTSLAM.h</a>.</p>

</div>
</div>
<a class="anchor" id="a71e840844a7041637a107b885ef5bd5f"></a><!-- doxytag: member="mrpt::hmtslam::CLSLAMAlgorithmBase::~CLSLAMAlgorithmBase" ref="a71e840844a7041637a107b885ef5bd5f" args="()" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">virtual mrpt::hmtslam::CLSLAMAlgorithmBase::~CLSLAMAlgorithmBase </td>
          <td>(</td>
          <td class="paramname"></td><td>)</td>
          <td><code> [inline, virtual]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Destructor. </p>

<p>Definition at line <a class="el" href="_c_h_m_t_s_l_a_m_8h_source.html#l00519">519</a> of file <a class="el" href="_c_h_m_t_s_l_a_m_8h_source.html">CHMTSLAM.h</a>.</p>

</div>
</div>
<hr/><h2>Member Function Documentation</h2>
<a class="anchor" id="a28469cf7e21f441a35db66e42b5e0866"></a><!-- doxytag: member="mrpt::hmtslam::CLSLAMAlgorithmBase::prediction_and_update_pfAuxiliaryPFOptimal" ref="a28469cf7e21f441a35db66e42b5e0866" args="(CLocalMetricHypothesis *LMH, const mrpt::slam::CActionCollection *action, const mrpt::slam::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &amp;PF_options)=0" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">virtual void mrpt::hmtslam::CLSLAMAlgorithmBase::prediction_and_update_pfAuxiliaryPFOptimal </td>
          <td>(</td>
          <td class="paramtype"><a class="el" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html">CLocalMetricHypothesis</a> *&#160;</td>
          <td class="paramname"><em>LMH</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">const <a class="el" href="classmrpt_1_1slam_1_1_c_action_collection.html">mrpt::slam::CActionCollection</a> *&#160;</td>
          <td class="paramname"><em>action</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">const <a class="el" href="classmrpt_1_1slam_1_1_c_sensory_frame.html">mrpt::slam::CSensoryFrame</a> *&#160;</td>
          <td class="paramname"><em>observation</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">const <a class="el" href="structmrpt_1_1bayes_1_1_c_particle_filter_1_1_t_particle_filter_options.html">bayes::CParticleFilter::TParticleFilterOptions</a> &amp;&#160;</td>
          <td class="paramname"><em>PF_options</em>&#160;</td>
        </tr>
        <tr>
          <td></td>
          <td>)</td>
          <td></td><td><code> [pure virtual]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>The PF algorithm implementation. </p>

<p>Implemented in <a class="el" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m___r_b_p_f__2_d_l_a_s_e_r.html#a7c0ddcdcf68f022a040f13ecf39acaa8">mrpt::hmtslam::CLSLAM_RBPF_2DLASER</a>.</p>

</div>
</div>
<a class="anchor" id="ad6e794f4bccd7375f00c00706d7a27aa"></a><!-- doxytag: member="mrpt::hmtslam::CLSLAMAlgorithmBase::prediction_and_update_pfOptimalProposal" ref="ad6e794f4bccd7375f00c00706d7a27aa" args="(CLocalMetricHypothesis *LMH, const mrpt::slam::CActionCollection *action, const mrpt::slam::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &amp;PF_options)=0" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">virtual void mrpt::hmtslam::CLSLAMAlgorithmBase::prediction_and_update_pfOptimalProposal </td>
          <td>(</td>
          <td class="paramtype"><a class="el" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html">CLocalMetricHypothesis</a> *&#160;</td>
          <td class="paramname"><em>LMH</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">const <a class="el" href="classmrpt_1_1slam_1_1_c_action_collection.html">mrpt::slam::CActionCollection</a> *&#160;</td>
          <td class="paramname"><em>action</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">const <a class="el" href="classmrpt_1_1slam_1_1_c_sensory_frame.html">mrpt::slam::CSensoryFrame</a> *&#160;</td>
          <td class="paramname"><em>observation</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">const <a class="el" href="structmrpt_1_1bayes_1_1_c_particle_filter_1_1_t_particle_filter_options.html">bayes::CParticleFilter::TParticleFilterOptions</a> &amp;&#160;</td>
          <td class="paramname"><em>PF_options</em>&#160;</td>
        </tr>
        <tr>
          <td></td>
          <td>)</td>
          <td></td><td><code> [pure virtual]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>The PF algorithm implementation. </p>

<p>Implemented in <a class="el" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m___r_b_p_f__2_d_l_a_s_e_r.html#a7443f72dcce5078df8dc3dc9267ac7b9">mrpt::hmtslam::CLSLAM_RBPF_2DLASER</a>.</p>

</div>
</div>
<a class="anchor" id="a21d3c172cb3ac6a371b8c46b0164c3f6"></a><!-- doxytag: member="mrpt::hmtslam::CLSLAMAlgorithmBase::processOneLMH" ref="a21d3c172cb3ac6a371b8c46b0164c3f6" args="(CLocalMetricHypothesis *LMH, const CActionCollectionPtr &amp;act, const CSensoryFramePtr &amp;sf)=0" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">virtual void mrpt::hmtslam::CLSLAMAlgorithmBase::processOneLMH </td>
          <td>(</td>
          <td class="paramtype"><a class="el" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html">CLocalMetricHypothesis</a> *&#160;</td>
          <td class="paramname"><em>LMH</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">const <a class="el" href="structmrpt_1_1slam_1_1_c_action_collection_ptr.html">CActionCollectionPtr</a> &amp;&#160;</td>
          <td class="paramname"><em>act</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">const <a class="el" href="structmrpt_1_1slam_1_1_c_sensory_frame_ptr.html">CSensoryFramePtr</a> &amp;&#160;</td>
          <td class="paramname"><em>sf</em>&#160;</td>
        </tr>
        <tr>
          <td></td>
          <td>)</td>
          <td></td><td><code> [pure virtual]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Main entry point from HMT-SLAM: process some actions &amp; observations. </p>
<p>The passed action/observation will be deleted, so a copy must be made if necessary. This method must be in charge of updating the robot pose estimates and also to update the map when required.</p>
<dl><dt><b>Parameters:</b></dt><dd>
  <table class="params">
    <tr><td class="paramname">LMH</td><td>The local metric hypothesis which must be updated by this SLAM algorithm. </td></tr>
    <tr><td class="paramname">act</td><td>The action to process (or NULL). </td></tr>
    <tr><td class="paramname">sf</td><td>The observations to process (or NULL). </td></tr>
  </table>
  </dd>
</dl>

<p>Implemented in <a class="el" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m___r_b_p_f__2_d_l_a_s_e_r.html#a95aff47f829003c18c48ade373d98d5b">mrpt::hmtslam::CLSLAM_RBPF_2DLASER</a>.</p>

</div>
</div>
<hr/><h2>Friends And Related Function Documentation</h2>
<a class="anchor" id="a8be947851baa9c04c2c4d71eae9b76cf"></a><!-- doxytag: member="mrpt::hmtslam::CLSLAMAlgorithmBase::CLocalMetricHypothesis" ref="a8be947851baa9c04c2c4d71eae9b76cf" args="" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">friend class HMTSLAM_IMPEXP <a class="el" href="classmrpt_1_1hmtslam_1_1_c_local_metric_hypothesis.html">CLocalMetricHypothesis</a><code> [friend]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Reimplemented in <a class="el" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m___r_b_p_f__2_d_l_a_s_e_r.html#a8be947851baa9c04c2c4d71eae9b76cf">mrpt::hmtslam::CLSLAM_RBPF_2DLASER</a>.</p>

<p>Definition at line <a class="el" href="_c_h_m_t_s_l_a_m_8h_source.html#l00508">508</a> of file <a class="el" href="_c_h_m_t_s_l_a_m_8h_source.html">CHMTSLAM.h</a>.</p>

</div>
</div>
<hr/><h2>Member Data Documentation</h2>
<a class="anchor" id="a7fbb8903f004411c76e55d45df946efe"></a><!-- doxytag: member="mrpt::hmtslam::CLSLAMAlgorithmBase::m_parent" ref="a7fbb8903f004411c76e55d45df946efe" args="" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname"><a class="el" href="structmrpt_1_1utils_1_1safe__ptr.html">safe_ptr</a>&lt;<a class="el" href="classmrpt_1_1hmtslam_1_1_c_h_m_t_s_l_a_m.html">CHMTSLAM</a>&gt; <a class="el" href="classmrpt_1_1hmtslam_1_1_c_l_s_l_a_m_algorithm_base.html#a7fbb8903f004411c76e55d45df946efe">mrpt::hmtslam::CLSLAMAlgorithmBase::m_parent</a><code> [protected]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Definition at line <a class="el" href="_c_h_m_t_s_l_a_m_8h_source.html#l00510">510</a> of file <a class="el" href="_c_h_m_t_s_l_a_m_8h_source.html">CHMTSLAM.h</a>.</p>

</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>