Sophie

Sophie

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

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::reactivenav::CReactiveInterfaceImplementation 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_1reactivenav.html">reactivenav</a>      </li>
      <li class="navelem"><a class="el" href="classmrpt_1_1reactivenav_1_1_c_reactive_interface_implementation.html">CReactiveInterfaceImplementation</a>      </li>
    </ul>
  </div>
</div>
<div class="header">
  <div class="summary">
<a href="#pub-methods">Public Member Functions</a>  </div>
  <div class="headertitle">
<div class="title">mrpt::reactivenav::CReactiveInterfaceImplementation Class Reference<div class="ingroups"><a class="el" href="group__mrpt__reactivenav__grp.html">[mrpt-reactivenav]</a></div></div>  </div>
</div>
<div class="contents">
<!-- doxytag: class="mrpt::reactivenav::CReactiveInterfaceImplementation" --><hr/><a name="details" id="details"></a><h2>Detailed Description</h2>
<div class="textblock"><p>The pure virtual class that a user of CAbstractReactiveNavigationSystem-derived classes must implement in order to allow the navigator sense the world and send motion commands to the robot. </p>
<p>The user must define a new class derived from <a class="el" href="classmrpt_1_1reactivenav_1_1_c_reactive_interface_implementation.html" title="The pure virtual class that a user of CAbstractReactiveNavigationSystem-derived classes must implemen...">CReactiveInterfaceImplementation</a> and reimplement all pure virtual and the desired virtual methods according to the documentation in this class.</p>
<dl class="see"><dt><b>See also:</b></dt><dd><a class="el" href="classmrpt_1_1reactivenav_1_1_c_reactive_navigation_system.html" title="Implements a reactive navigation system based on TP-Space, with an arbitrary holonomic reactive metho...">CReactiveNavigationSystem</a>, <a class="el" href="classmrpt_1_1reactivenav_1_1_c_abstract_reactive_navigation_system.html" title="This is the base class for any reactive navigation system.">CAbstractReactiveNavigationSystem</a> </dd></dl>
</div>
<p><code>#include &lt;<a class="el" href="_c_abstract_reactive_navigation_system_8h_source.html">mrpt/reactivenav/CAbstractReactiveNavigationSystem.h</a>&gt;</code></p>

<p><a href="classmrpt_1_1reactivenav_1_1_c_reactive_interface_implementation-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">virtual bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1reactivenav_1_1_c_reactive_interface_implementation.html#aaf91d1e42e1246dead71ebd432dbfa12">getCurrentPoseAndSpeeds</a> (<a class="el" href="classmrpt_1_1poses_1_1_c_pose2_d.html">mrpt::poses::CPose2D</a> &amp;curPose, float &amp;curV, float &amp;curW)=0</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Get the current pose and speeds of the robot.  <a href="#aaf91d1e42e1246dead71ebd432dbfa12"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">virtual bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1reactivenav_1_1_c_reactive_interface_implementation.html#aee9f9188dbb4bfe19d18ef7fd1c39bec">changeSpeeds</a> (float v, float w)=0</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Change the instantaneous speeds of robot.  <a href="#aee9f9188dbb4bfe19d18ef7fd1c39bec"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">virtual bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1reactivenav_1_1_c_reactive_interface_implementation.html#a492e2caa47f7dc58f2e36fb9798a63bb">stop</a> ()</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Stop the robot right now.  <a href="#a492e2caa47f7dc58f2e36fb9798a63bb"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">virtual bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1reactivenav_1_1_c_reactive_interface_implementation.html#a2c1eaf4dc7631e133a8512a1669c77aa">startWatchdog</a> (float T_ms)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Start the watchdog timer of the robot platform, if any.  <a href="#a2c1eaf4dc7631e133a8512a1669c77aa"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">virtual bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1reactivenav_1_1_c_reactive_interface_implementation.html#a97cd96cf3d001e5e5158a1246a0cb36c">stopWatchdog</a> ()</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Stop the watchdog timer.  <a href="#a97cd96cf3d001e5e5158a1246a0cb36c"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">virtual bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1reactivenav_1_1_c_reactive_interface_implementation.html#abfc26ae79ba331137731546e1ff37d3d">senseObstacles</a> (<a class="el" href="classmrpt_1_1slam_1_1_c_simple_points_map.html">mrpt::slam::CSimplePointsMap</a> &amp;obstacles)=0</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Return the current set of obstacle points.  <a href="#abfc26ae79ba331137731546e1ff37d3d"></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_1reactivenav_1_1_c_reactive_interface_implementation.html#a5fdfa5fbbb2df7bc9c9d38a57cdd4881">sendNavigationStartEvent</a> ()</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_1reactivenav_1_1_c_reactive_interface_implementation.html#a953f7697b09d28457ab07f1509f3d712">sendNavigationEndEvent</a> ()</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_1reactivenav_1_1_c_reactive_interface_implementation.html#ad5ea8765471c5b89956140c109636ffb">sendNavigationEndDueToErrorEvent</a> ()</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_1reactivenav_1_1_c_reactive_interface_implementation.html#a69ff8b55c4b9608fdf35c2a471fb938f">sendWaySeemsBlockedEvent</a> ()</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_1reactivenav_1_1_c_reactive_interface_implementation.html#ae8cb79aa7c0309f0d33fc146928d410b">notifyHeadingDirection</a> (const double heading_dir_angle)</td></tr>
</table>
<hr/><h2>Member Function Documentation</h2>
<a class="anchor" id="aee9f9188dbb4bfe19d18ef7fd1c39bec"></a><!-- doxytag: member="mrpt::reactivenav::CReactiveInterfaceImplementation::changeSpeeds" ref="aee9f9188dbb4bfe19d18ef7fd1c39bec" args="(float v, float w)=0" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">virtual bool mrpt::reactivenav::CReactiveInterfaceImplementation::changeSpeeds </td>
          <td>(</td>
          <td class="paramtype">float&#160;</td>
          <td class="paramname"><em>v</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">float&#160;</td>
          <td class="paramname"><em>w</em>&#160;</td>
        </tr>
        <tr>
          <td></td>
          <td>)</td>
          <td></td><td><code> [pure virtual]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Change the instantaneous speeds of robot. </p>
<dl><dt><b>Parameters:</b></dt><dd>
  <table class="params">
    <tr><td class="paramname">v</td><td>Linear speed, in meters per second. </td></tr>
    <tr><td class="paramname">w</td><td>Angular speed, in radians per second. </td></tr>
  </table>
  </dd>
</dl>
<dl class="return"><dt><b>Returns:</b></dt><dd>false on any error. </dd></dl>

</div>
</div>
<a class="anchor" id="aaf91d1e42e1246dead71ebd432dbfa12"></a><!-- doxytag: member="mrpt::reactivenav::CReactiveInterfaceImplementation::getCurrentPoseAndSpeeds" ref="aaf91d1e42e1246dead71ebd432dbfa12" args="(mrpt::poses::CPose2D &amp;curPose, float &amp;curV, float &amp;curW)=0" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">virtual bool mrpt::reactivenav::CReactiveInterfaceImplementation::getCurrentPoseAndSpeeds </td>
          <td>(</td>
          <td class="paramtype"><a class="el" href="classmrpt_1_1poses_1_1_c_pose2_d.html">mrpt::poses::CPose2D</a> &amp;&#160;</td>
          <td class="paramname"><em>curPose</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">float &amp;&#160;</td>
          <td class="paramname"><em>curV</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">float &amp;&#160;</td>
          <td class="paramname"><em>curW</em>&#160;</td>
        </tr>
        <tr>
          <td></td>
          <td>)</td>
          <td></td><td><code> [pure virtual]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Get the current pose and speeds of the robot. </p>
<dl><dt><b>Parameters:</b></dt><dd>
  <table class="params">
    <tr><td class="paramname">curPose</td><td>Current robot pose. </td></tr>
    <tr><td class="paramname">curV</td><td>Current linear speed, in meters per second. </td></tr>
    <tr><td class="paramname">curW</td><td>Current angular speed, in radians per second. </td></tr>
  </table>
  </dd>
</dl>
<dl class="return"><dt><b>Returns:</b></dt><dd>false on any error. </dd></dl>

</div>
</div>
<a class="anchor" id="ae8cb79aa7c0309f0d33fc146928d410b"></a><!-- doxytag: member="mrpt::reactivenav::CReactiveInterfaceImplementation::notifyHeadingDirection" ref="ae8cb79aa7c0309f0d33fc146928d410b" args="(const double heading_dir_angle)" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">virtual void mrpt::reactivenav::CReactiveInterfaceImplementation::notifyHeadingDirection </td>
          <td>(</td>
          <td class="paramtype">const double&#160;</td>
          <td class="paramname"><em>heading_dir_angle</em></td><td>)</td>
          <td><code> [inline, virtual]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Definition at line <a class="el" href="_c_abstract_reactive_navigation_system_8h_source.html#l00104">104</a> of file <a class="el" href="_c_abstract_reactive_navigation_system_8h_source.html">CAbstractReactiveNavigationSystem.h</a>.</p>

</div>
</div>
<a class="anchor" id="ad5ea8765471c5b89956140c109636ffb"></a><!-- doxytag: member="mrpt::reactivenav::CReactiveInterfaceImplementation::sendNavigationEndDueToErrorEvent" ref="ad5ea8765471c5b89956140c109636ffb" args="()" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">virtual void mrpt::reactivenav::CReactiveInterfaceImplementation::sendNavigationEndDueToErrorEvent </td>
          <td>(</td>
          <td class="paramname"></td><td>)</td>
          <td><code> [inline, virtual]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Definition at line <a class="el" href="_c_abstract_reactive_navigation_system_8h_source.html#l00100">100</a> of file <a class="el" href="_c_abstract_reactive_navigation_system_8h_source.html">CAbstractReactiveNavigationSystem.h</a>.</p>

</div>
</div>
<a class="anchor" id="a953f7697b09d28457ab07f1509f3d712"></a><!-- doxytag: member="mrpt::reactivenav::CReactiveInterfaceImplementation::sendNavigationEndEvent" ref="a953f7697b09d28457ab07f1509f3d712" args="()" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">virtual void mrpt::reactivenav::CReactiveInterfaceImplementation::sendNavigationEndEvent </td>
          <td>(</td>
          <td class="paramname"></td><td>)</td>
          <td><code> [inline, virtual]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Definition at line <a class="el" href="_c_abstract_reactive_navigation_system_8h_source.html#l00098">98</a> of file <a class="el" href="_c_abstract_reactive_navigation_system_8h_source.html">CAbstractReactiveNavigationSystem.h</a>.</p>

</div>
</div>
<a class="anchor" id="a5fdfa5fbbb2df7bc9c9d38a57cdd4881"></a><!-- doxytag: member="mrpt::reactivenav::CReactiveInterfaceImplementation::sendNavigationStartEvent" ref="a5fdfa5fbbb2df7bc9c9d38a57cdd4881" args="()" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">virtual void mrpt::reactivenav::CReactiveInterfaceImplementation::sendNavigationStartEvent </td>
          <td>(</td>
          <td class="paramname"></td><td>)</td>
          <td><code> [inline, virtual]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Definition at line <a class="el" href="_c_abstract_reactive_navigation_system_8h_source.html#l00096">96</a> of file <a class="el" href="_c_abstract_reactive_navigation_system_8h_source.html">CAbstractReactiveNavigationSystem.h</a>.</p>

</div>
</div>
<a class="anchor" id="a69ff8b55c4b9608fdf35c2a471fb938f"></a><!-- doxytag: member="mrpt::reactivenav::CReactiveInterfaceImplementation::sendWaySeemsBlockedEvent" ref="a69ff8b55c4b9608fdf35c2a471fb938f" args="()" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">virtual void mrpt::reactivenav::CReactiveInterfaceImplementation::sendWaySeemsBlockedEvent </td>
          <td>(</td>
          <td class="paramname"></td><td>)</td>
          <td><code> [inline, virtual]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Definition at line <a class="el" href="_c_abstract_reactive_navigation_system_8h_source.html#l00102">102</a> of file <a class="el" href="_c_abstract_reactive_navigation_system_8h_source.html">CAbstractReactiveNavigationSystem.h</a>.</p>

</div>
</div>
<a class="anchor" id="abfc26ae79ba331137731546e1ff37d3d"></a><!-- doxytag: member="mrpt::reactivenav::CReactiveInterfaceImplementation::senseObstacles" ref="abfc26ae79ba331137731546e1ff37d3d" args="(mrpt::slam::CSimplePointsMap &amp;obstacles)=0" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">virtual bool mrpt::reactivenav::CReactiveInterfaceImplementation::senseObstacles </td>
          <td>(</td>
          <td class="paramtype"><a class="el" href="classmrpt_1_1slam_1_1_c_simple_points_map.html">mrpt::slam::CSimplePointsMap</a> &amp;&#160;</td>
          <td class="paramname"><em>obstacles</em></td><td>)</td>
          <td><code> [pure virtual]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Return the current set of obstacle points. </p>
<dl class="return"><dt><b>Returns:</b></dt><dd>false on any error. </dd></dl>

</div>
</div>
<a class="anchor" id="a2c1eaf4dc7631e133a8512a1669c77aa"></a><!-- doxytag: member="mrpt::reactivenav::CReactiveInterfaceImplementation::startWatchdog" ref="a2c1eaf4dc7631e133a8512a1669c77aa" args="(float T_ms)" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">virtual bool mrpt::reactivenav::CReactiveInterfaceImplementation::startWatchdog </td>
          <td>(</td>
          <td class="paramtype">float&#160;</td>
          <td class="paramname"><em>T_ms</em></td><td>)</td>
          <td><code> [inline, virtual]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Start the watchdog timer of the robot platform, if any. </p>
<dl><dt><b>Parameters:</b></dt><dd>
  <table class="params">
    <tr><td class="paramname">T_ms</td><td>Period, in ms. </td></tr>
  </table>
  </dd>
</dl>
<dl class="return"><dt><b>Returns:</b></dt><dd>false on any error. </dd></dl>

<p>Definition at line <a class="el" href="_c_abstract_reactive_navigation_system_8h_source.html#l00084">84</a> of file <a class="el" href="_c_abstract_reactive_navigation_system_8h_source.html">CAbstractReactiveNavigationSystem.h</a>.</p>

</div>
</div>
<a class="anchor" id="a492e2caa47f7dc58f2e36fb9798a63bb"></a><!-- doxytag: member="mrpt::reactivenav::CReactiveInterfaceImplementation::stop" ref="a492e2caa47f7dc58f2e36fb9798a63bb" args="()" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">virtual bool mrpt::reactivenav::CReactiveInterfaceImplementation::stop </td>
          <td>(</td>
          <td class="paramname"></td><td>)</td>
          <td><code> [inline, virtual]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Stop the robot right now. </p>
<dl class="return"><dt><b>Returns:</b></dt><dd>false on any error. </dd></dl>

<p>Definition at line <a class="el" href="_c_abstract_reactive_navigation_system_8h_source.html#l00076">76</a> of file <a class="el" href="_c_abstract_reactive_navigation_system_8h_source.html">CAbstractReactiveNavigationSystem.h</a>.</p>

</div>
</div>
<a class="anchor" id="a97cd96cf3d001e5e5158a1246a0cb36c"></a><!-- doxytag: member="mrpt::reactivenav::CReactiveInterfaceImplementation::stopWatchdog" ref="a97cd96cf3d001e5e5158a1246a0cb36c" args="()" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">virtual bool mrpt::reactivenav::CReactiveInterfaceImplementation::stopWatchdog </td>
          <td>(</td>
          <td class="paramname"></td><td>)</td>
          <td><code> [inline, virtual]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Stop the watchdog timer. </p>
<dl class="return"><dt><b>Returns:</b></dt><dd>false on any error. </dd></dl>

<p>Definition at line <a class="el" href="_c_abstract_reactive_navigation_system_8h_source.html#l00089">89</a> of file <a class="el" href="_c_abstract_reactive_navigation_system_8h_source.html">CAbstractReactiveNavigationSystem.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>