Sophie

Sophie

distrib > Fedora > 14 > x86_64 > media > updates > by-pkgid > 727fa15453fcace956b835e2377d4269 > files > 618

player-doc-3.0.2-5.fc14.noarch.rpm

<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01//EN"
   "http://www.w3.org/TR/html4/strict.dtd">

<html>
<!-- $Id: header.html 8799 2010-06-28 04:12:42Z jpgr87 $ -->

<HEAD>


<meta HTTP-EQUIV="Content-Type" CONTENT="text/html;CHARSET=utf-8">
<meta name="keywords" content="stage, robot, simulation, player, player/stage">
<link href="doxygen.css" rel="stylesheet" type="text/css">

<style type="text/css">

.floatright { float: right; margin: 0 0 1em 1em; }

body {
  font-family: sans-serif;
  #font-family: Geneva, Verdana, Helvetica, Arial, sans-serif;
  background-color: #FFF;
  color:#000;
}


a:link { 
	color: #A00;
}

a:visited { 
	color: #800;
}

a { text-decoration: none; }
a:hover { text-decoration: underline; }


.timestamp { text-align:right; background-color: #DDD; font-size:75%;}

h1 { 
  font-size:160%; 
}

h2 {
  font-size:110%;
  #color: #FFF;
  #background-color: #666;
  #padding:3px;
}

h3 { text-align:left; }

img {
  border: 0;
}

ul.menu { 
    position:relative;
    left:-2.5em;
    margin-bottom:0px;
    margin-top:0px;
}

ul.menu1 { 
    position:relative;
    left:-2.1em;
    margin-bottom:0px;
    margin-top:0px;
}

li.menu { 
    list-style-type: none;
    position:relative;
    #left:-0.5em;
}


#sidebar { position: absolute; left:0px; padding:2em; top:0em; width:12em;}

#content { position: absolute; left:12em; top:0em; padding-left:3em; padding-right:3em; padding-bottom:2em; margin-top:1em; margin-right:2em; }

div.box { background-color:#EEE; border: 1px solid #000; padding: 0.5ex 0.4em 0.5ex 0.6em; margin:1em;  }
div.title { font-weight:bold; background-color:#eee; margin-bottom:2px;}

div.topbar { position: absolute; top:0px; left:9em; margin:1em; }

</style>

<TITLE>Player Manual</TITLE>

</HEAD>

<body>

<div id="sidebar"> 

<h2 style="text-align:center;">
<a href="index.html">
<img width=140 src="http://playerstage.sourceforge.net/images/player_button_v3.png" alt="Player logo"><br></a>
</h2>



<div class="box">
<div class=title>Player</div>

<ul class=menu>
<li class=menu><a href="index.html">Frontpage</a>
<li class=menu><a href="modules.html">Contents</a>
</ul>
</div>

<div class="box">
<div class=title>User</div>

<ul class=menu>
<li class=menu><a href="install.html">Installation</a>
<li class=menu><a href="start.html">Quick start</a>
<li class=menu><a href="supported_hardware.html">Supported&nbsp;devices</a>
<li class=menu><a href="group__tutorials.html">Tutorials</a>
<li class=menu><a href="group__utils.html">Utilities</a>
<li class=menu><a href="group__clientlibs.html">Client&nbsp;libraries</a>
<li class=menu><a href="http://playerstage.sourceforge.net/wiki/Basic_FAQ">FAQ</a>
<li class=menu><a href="help.html">Help</a>

</ul>
</div>

<div class=box>
<div class="title">Developer</div>
<ul class=menu>
<li class=menu><a href="architecture.html">Architecture</a>
<li class=menu><a href="group__libplayercore.html">libplayercore</a>
<ul class=menu1>
<li class=menu><a href="group__interfaces.html">interfaces</a></li>
</ul>
<li class=menu><a href="group__libplayerdrivers.html">libplayerdrivers</a>
<ul class=menu1>
<li class=menu><a href="group__drivers.html">drivers</a></li>
</ul>
<li class=menu><a href="group__libplayercommon.html">libplayercommon</a>
<li class=menu><a href="group__libplayerutils.html">libplayerutils</a>
<li class=menu><a href="group__libplayersd.html">libplayersd</a>
<li class=menu><a href="group__libplayertcp.html">libplayertcp</a>
<li class=menu><a href="group__libplayerxdr.html">libplayerxdr</a>
<li class=menu><a href="todo.html">TODO</a>
</ul>
</div>

<div class=box>
<!-- <a href="http://sourceforge.net"><img border=0 src="http://sourceforge.net/sflogo.php?group_id=42445&type=1"></a> -->
<div class="title">Online</div>
<a href="http://playerstage.sourceforge.net">Homepage</a><br>
<a href="http://sourceforge.net/project/showfiles.php?group_id=42445">Download</a><br>
<a href="http://sourceforge.net/projects/playerstage">Project</a><br>
<a href="http://sourceforge.net/tracker/?group_id=42445">Bugs</a><br>
<a href="http://sourceforge.net/mail/?group_id=42445">Help</a>
</div>


</div>

<div id="content" >
<!-- Generated by Doxygen 1.7.1 -->
<div class="header">
  <div class="headertitle">
<h1>nd<br/>
<small>
[<a class="el" href="group__drivers.html">Drivers</a>]</small>
</h1>  </div>
</div>
<div class="contents">

<p>Nearness Diagram Navigation.  
<a href="#_details">More...</a></p>
<table class="memberdecls">
</table>
<p>Nearness Diagram Navigation. </p>
<p>This driver implements the Nearness Diagram Navigation algorithm. This algorithm handles local collision-avoidance and goal-seeking and is designed for non-holonomic, non-circular robots operating in tight spaces. The algorithm is in the following papers:</p>
<ul>
<li>J. Minguez, L. Montano. Nearness Diagram Navigation (ND): Collision Avoidance in Troublesome Scenarios. IEEE Transactions on Robotics and Automation, pp 154, 2004. <a href="http://webdiis.unizar.es/~jminguez/TRAND.pdf">PDF</a></li>
</ul>
<ul>
<li>J. Minguez, J. Osuna, L. Montano. A Divide and Conquer Strategy based on Situations to Achieve Reactive Collision Avoidance in Troublesome Scenarios. IEEE International Conference on Robotics and Automation (ICRA 2004), 2004. New Orleans, USA. <a href="http://webdiis.unizar.es/~jminguez/810.pdf">PDF</a></li>
</ul>
<p>This driver reads pose information from a <a class="el" href="group__interface__position2d.html">position2d</a> device, sensor data from a <a class="el" href="group__interface__laser.html">laser</a> device and/or <a class="el" href="group__interface__sonar.html">sonar</a> device, and writes commands to a <a class="el" href="group__interface__position2d.html">position2d</a> device. The two <a class="el" href="group__interface__position2d.html">position2d</a> devices can be the same. At least one device of type <a class="el" href="group__interface__laser.html">laser</a> or <a class="el" href="group__interface__sonar.html">sonar</a> must be provided.</p>
<p>The driver itself supports the  interface. Send <a class="el" href="group__interface__position2d.html#gaf0801065c6a46fda7e2734be3528911c">PLAYER_POSITION2D_CMD_POS</a> commands to set the goal pose. The driver also accepts <a class="el" href="group__interface__position2d.html#gacaf0b14c255b47d09fef5efd7dd0fb22">PLAYER_POSITION2D_CMD_VEL</a> commands, simply passing them through to the underlying output device.</p>
<dl class="user"><dt><b>Compile-time dependencies</b></dt><dd></dd></dl>
<ul>
<li>none</li>
</ul>
<dl class="user"><dt><b>Provides</b></dt><dd></dd></dl>
<ul>
<li><a class="el" href="group__interface__position2d.html">position2d</a></li>
</ul>
<dl class="user"><dt><b>Requires</b></dt><dd></dd></dl>
<ul>
<li>"input" <a class="el" href="group__interface__position2d.html">position2d</a> : source of pose and velocity information</li>
<li>"output" <a class="el" href="group__interface__position2d.html">position2d</a> : sink for velocity commands to control the robot</li>
<li><a class="el" href="group__interface__laser.html">laser</a> : the laser to read from</li>
<li><a class="el" href="group__interface__sonar.html">sonar</a> : the sonar to read from</li>
</ul>
<dl class="user"><dt><b>Configuration requests</b></dt><dd></dd></dl>
<ul>
<li>all <a class="el" href="group__interface__position2d.html">position2d</a> requests are passed through to the underlying "output" <a class="el" href="group__interface__position2d.html">position2d</a> device.</li>
</ul>
<dl class="user"><dt><b>Configuration file options</b></dt><dd></dd></dl>
<ul>
<li>goal_tol (tuple: [length angle])<ul>
<li>Default: [0.5 10.0] (m deg)</li>
<li>Respectively, translational and rotational goal tolerance. When the robot is within these bounds of the current target pose, it will be stopped.</li>
</ul>
</li>
</ul>
<ul>
<li>max_speed (tuple: [length/sec angle/sec])<ul>
<li>Default: [0.3 45.0] (m/s deg/s)</li>
<li>Respectively, maximum absolute translational and rotational velocities to be used in commanding the robot.</li>
</ul>
</li>
</ul>
<ul>
<li>min_speed (tuple: [length/sec angle/sec])<ul>
<li>Default: [0.05 10.0] (m/s deg/s)</li>
<li>Respectively, minimum absolute non-zero translational and rotational velocities to be used in commanding the robot.</li>
</ul>
</li>
</ul>
<ul>
<li>avoid_dist (length)<ul>
<li>Default: 0.5 m</li>
<li>Distance at which obstacle avoidance begins</li>
</ul>
</li>
</ul>
<ul>
<li>safety_dist (length)<ul>
<li>Default: 0.0 m</li>
<li>Extra extent added to the robot on all sides when doing obstacle avoidance.</li>
</ul>
</li>
</ul>
<ul>
<li>rotate_stuck_time (float)<ul>
<li>Default: 2.0 seconds</li>
<li>How long the robot is allowed to rotate in place without making any progress toward the goal orientation before giving up.</li>
</ul>
</li>
</ul>
<ul>
<li>translate_stuck_time (float)<ul>
<li>Default: 2.0 seconds</li>
<li>How long the robot is allowed to translate without making sufficient progress toward the goal position before giving up.</li>
</ul>
</li>
</ul>
<ul>
<li>translate_stuck_dist (length)<ul>
<li>Default: 0.25 m</li>
<li>How far the robot must translate during translate stuck time in order to not give up.</li>
</ul>
</li>
</ul>
<ul>
<li>translate_stuck_angle (angle)<ul>
<li>Default: 20 deg</li>
<li>How far the robot must rotate during translate stuck time in order to not give up.</li>
</ul>
</li>
</ul>
<ul>
<li>wait_on_stall (integer)<ul>
<li>Default: 0</li>
<li>Should local navigation be paused if the stall flag is set on the input:position2d device? This option is useful if the robot's pose is being read from a SLAM system that sets the stall flag when it is performing intensive computation and can no longer guarantee the validity of pose estimates.</li>
</ul>
</li>
</ul>
<ul>
<li>laser_buffer (integer)<ul>
<li>Default: 10</li>
<li>How many recent laser scans to consider in the local navigation.</li>
</ul>
</li>
</ul>
<ul>
<li>sonar_buffer (integer)<ul>
<li>Default: 10</li>
<li>How many recent sonar scans to consider in the local navigation</li>
</ul>
</li>
</ul>
<ul>
<li>sonar_bad_transducers (tuple [integers])<ul>
<li>Default: [] (empty tuple)</li>
<li>Indices of sonar transducers that should be ignored. This option is useful when particular sonars are known to be bad, or if they tend to give returns from the robot's body (usually the wheels), or if they are just not needed because of overlap with the laser.</li>
</ul>
</li>
</ul>
<dl class="user"><dt><b>Example</b></dt><dd></dd></dl>
<div class="fragment"><pre class="fragment">
driver
(
  name "nd"
  provides ["position2d:1"]
  requires ["output:::position2d:0" "input:::position2d:0" "laser:0" "sonar:0"]

  max_speed [0.3 30.0]
  min_speed [0.1 10.0]
  goal_tol [0.3 15.0]
  wait_on_stall 1

  rotate_stuck_time 5.0
  translate_stuck_time 5.0
  translate_stuck_dist 0.15
  translate_stuck_angle 10.0

  avoid_dist 0.4
  safety_dist 0.0

  laser_buffer 1
  sonar_buffer 1
)
</pre></div><dl class="author"><dt><b>Author:</b></dt><dd>Javier Minguez (underlying algorithm), Brian Gerkey (driver integration) </dd></dl>
</div>
<!-- render the modification time of the source file -->


<div class="timestamp">
<hr>

<table style="width:100%;">
<tr>
<td style="text-align:left;">
Last updated 12 September 2005 21:38:45
<!--
<td style="text-align:right;">
<a href="http://validator.w3.org/check/referer"><img style="vertical-align:middle;border:0;width:88px;height:31px"
          src="http://www.w3.org/Icons/valid-html401"
          alt="Valid HTML 4.01!"></a>

 <a href="http://jigsaw.w3.org/css-validator/">
  <img style="vertical-align:middle;border:0;width:88px;height:31px"
       src="http://jigsaw.w3.org/css-validator/images/vcss"
       alt="Valid CSS!">
 </a>
-->
</tr>
</table>
</div>


</tr>
</table>

</BODY>
</HTML>