Sophie

Sophie

distrib > Fedora > 14 > x86_64 > by-pkgid > 1099e73f16f15ba3cf656e619f52a447 > files > 786

ompl-devel-0.9.5-1.fc14.x86_64.rpm

<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta http-equiv="Content-Type" content="text/xhtml; charset=UTF-8"/>
<title>OMPL: ompl::geometric::BallTreeRRTstar Class Reference</title>
<meta name="author" content="Ioan A. Șucan, Mark Moll, Lydia E. Kavraki">
<link rel="stylesheet" href="../css/screen.css" type="text/css" media="screen, projection">
<link rel="stylesheet" href="../css/print.css" type="text/css" media="print">
<!--[if lt IE 7]>
<script type="text/javascript" src="../js/jquery/jquery.js"></script>
<script type="text/javascript" src="../js/jquery/jquery.dropdown.js"></script>
<![endif]-->
<script type="text/javaScript" src="search/search.js"></script>
<script type="text/javascript">
  var _gaq = _gaq || [];
  _gaq.push(['_setAccount', 'UA-9156598-2']);
  _gaq.push(['_trackPageview']);
  (function() {
    var ga = document.createElement('script'); ga.type = 'text/javascript'; ga.async = true;
    ga.src = ('https:' == document.location.protocol ? 'https://ssl' : 'http://www') + '.google-analytics.com/ga.js';
    var s = document.getElementsByTagName('script')[0]; s.parentNode.insertBefore(ga, s);
  })();
</script>
</head>
<body onload='searchBox.OnSelectItem(0);'>
<script type="text/javascript"><!--
var searchBox = new SearchBox("searchBox", "search",false,'Search API');
--></script>
<div class="navigation" id="top">
  <div class="tabs" id="ompltitle">
    <ul class="tablist">
      <li>The Open Motion Planning Library</li>
      <li id="searchli">
        <div id="MSearchBox" class="MSearchBoxInactive">
        <span class="left">
          <img id="MSearchSelect" src="search/mag_sel.png"
               onmouseover="return searchBox.OnSearchSelectShow()"
               onmouseout="return searchBox.OnSearchSelectHide()"
               alt=""/>
          <input type="text" id="MSearchField" value="Search API" accesskey="S"
               onfocus="searchBox.OnSearchFieldFocus(true)"
               onblur="searchBox.OnSearchFieldFocus(false)"
               onkeyup="searchBox.OnSearchFieldChange(event)"/>
          </span><span class="right">
            <a id="MSearchClose" href="javascript:searchBox.CloseResultsWindow()"><img id="MSearchCloseImg" border="0" src="search/close.png" alt=""/></a>
          </span>
        </div>
      </li>
    </ul>
  </div>

  <ul id="nav" class="dropdown">
    <li class="first"><a href="index.html">Home</a></li>
    <li><a href="download.html">Download</a></li>
    <li><a href="documentation.html">Documentation</a></li>
    <li><span class="dir">Code API</span>
      <ul>
        <li><a href="api_overview.html">API Overview</a></li>
        <li><a href="namespaces.html">Namespaces</a></li>
        <li><a href="annotated.html">Classes</a></li>
        <li><a href="files.html">Files</a></li>
        <li><a href="dirs.html">Directories</a></li>
      </ul>
    </li>
    <li><span class="dir">Community</span>
      <ul>
        <li><a href="developers.html">Developers</a></li>
        <li><a href="thirdparty.html">Contributions</a></li>
        <li><a href="education.html">Education</a></li>
        <li><a href="gallery.html">Gallery</a></li>
      </ul>
    </li>
    <li><span class="dir">About</span>
      <ul>
        <li><a href="license.html">License</a></li>
        <li><a href="citations.html">Citations</a></li>
        <li><a href="acknowledgements.html">Acknowledgments</a></li>
        <li><a href="contact.html">Contact Us</a></li>
      </ul>
    </li>
  </ul>
</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">&#160;</span>All</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(1)"><span class="SelectionMark">&#160;</span>Classes</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(2)"><span class="SelectionMark">&#160;</span>Namespaces</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(3)"><span class="SelectionMark">&#160;</span>Functions</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(4)"><span class="SelectionMark">&#160;</span>Variables</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(5)"><span class="SelectionMark">&#160;</span>Typedefs</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(6)"><span class="SelectionMark">&#160;</span>Enumerations</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(7)"><span class="SelectionMark">&#160;</span>Enumerator</a></div>

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

<div class="container">
  <div class="span-22 push-2 first last">
  <div>
<!-- Generated by Doxygen 1.7.4 -->
<script type="text/javascript"><!--
var searchBox = new SearchBox("searchBox", "search",false,'Search');
--></script>
  <div id="nav-path" class="navpath">
    <ul>
      <li class="navelem"><a class="el" href="namespaceompl.html">ompl</a>      </li>
      <li class="navelem"><a class="el" href="namespaceompl_1_1geometric.html">geometric</a>      </li>
      <li class="navelem"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html">BallTreeRRTstar</a>      </li>
    </ul>
  </div>
</div>
<div class="header">
  <div class="summary">
<a href="#nested-classes">Classes</a> &#124;
<a href="#pub-methods">Public Member Functions</a> &#124;
<a href="#pro-methods">Protected Member Functions</a> &#124;
<a href="#pro-static-methods">Static Protected Member Functions</a> &#124;
<a href="#pro-attribs">Protected Attributes</a>  </div>
  <div class="headertitle">
<div class="title">ompl::geometric::BallTreeRRTstar Class Reference</div>  </div>
</div>
<div class="contents">
<!-- doxytag: class="ompl::geometric::BallTreeRRTstar" --><!-- doxytag: inherits="ompl::base::Planner" -->
<p>Optimal Rapidly-exploring Random Trees with Ball Trees.  
 <a href="classompl_1_1geometric_1_1BallTreeRRTstar.html#details">More...</a></p>

<p><code>#include &lt;<a class="el" href="BallTreeRRTstar_8h_source.html">BallTreeRRTstar.h</a>&gt;</code></p>
<div class="dynheader">
Inheritance diagram for ompl::geometric::BallTreeRRTstar:</div>
<div class="dyncontent">
<div class="center"><img src="classompl_1_1geometric_1_1BallTreeRRTstar__inherit__graph.png" border="0" usemap="#ompl_1_1geometric_1_1BallTreeRRTstar_inherit__map" alt="Inheritance graph"/></div>
<map name="ompl_1_1geometric_1_1BallTreeRRTstar_inherit__map" id="ompl_1_1geometric_1_1BallTreeRRTstar_inherit__map">
<area shape="rect" id="node2" href="classompl_1_1base_1_1Planner.html" title="Base class for a planner." alt="" coords="47,5,185,35"/></map>
<center><span class="legend">[<a href="graph_legend.html">legend</a>]</span></center></div>

<p><a href="classompl_1_1geometric_1_1BallTreeRRTstar-members.html">List of all members.</a></p>
<table class="memberdecls">
<tr><td colspan="2"><h2><a name="nested-classes"></a>
Classes</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">class &#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html">Motion</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Representation of a motion.  <a href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#details">More...</a><br/></td></tr>
<tr><td colspan="2"><h2><a name="pub-methods"></a>
Public Member Functions</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a68c80c02facdbd94ac70d0a6fbc78df3"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::BallTreeRRTstar" ref="a68c80c02facdbd94ac70d0a6fbc78df3" args="(const base::SpaceInformationPtr &amp;si)" -->
&#160;</td><td class="memItemRight" valign="bottom"><b>BallTreeRRTstar</b> (const <a class="el" href="classompl_1_1base_1_1SpaceInformationPtr.html">base::SpaceInformationPtr</a> &amp;si)</td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a8ea2d6a703307a13272b52588acca8ef"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::getPlannerData" ref="a8ea2d6a703307a13272b52588acca8ef" args="(base::PlannerData &amp;data) const " -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a8ea2d6a703307a13272b52588acca8ef">getPlannerData</a> (<a class="el" href="classompl_1_1base_1_1PlannerData.html">base::PlannerData</a> &amp;data) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Get information about the current run of the motion planner. Repeated calls to this function will update <em>data</em> (only additions are made). This is useful to see what changed in the exploration datastructure, between calls to <a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#aca33b01960299c9fd1704e6cdaf06c06" title="Function that can solve the motion planning problem. This function can be called multiple times on th...">solve()</a>, for example (without calling <a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a450aea782c10383dc22e21cfcb72dcea" title="Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...">clear()</a> in between). <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="aca33b01960299c9fd1704e6cdaf06c06"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::solve" ref="aca33b01960299c9fd1704e6cdaf06c06" args="(const base::PlannerTerminationCondition &amp;ptc)" -->
virtual bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#aca33b01960299c9fd1704e6cdaf06c06">solve</a> (const <a class="el" href="classompl_1_1base_1_1PlannerTerminationCondition.html">base::PlannerTerminationCondition</a> &amp;ptc)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Function that can solve the motion planning problem. This function can be called multiple times on the same problem, without calling <a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a450aea782c10383dc22e21cfcb72dcea" title="Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...">clear()</a> in between. This allows the planner to continue work more time on an unsolved problem, for example. If this option is used, it is assumed the problem definition is not changed (unpredictable results otherwise). The only change in the problem definition that is accounted for is the addition of starting or goal states (but not changing previously added start/goal states). The function terminates if the call to <em>ptc</em> returns true. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a450aea782c10383dc22e21cfcb72dcea"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::clear" ref="a450aea782c10383dc22e21cfcb72dcea" args="(void)" -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a450aea782c10383dc22e21cfcb72dcea">clear</a> (void)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Clear all internal datastructures. Planner settings are not affected. Subsequent calls to <a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#aca33b01960299c9fd1704e6cdaf06c06" title="Function that can solve the motion planning problem. This function can be called multiple times on th...">solve()</a> will ignore all previous work. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a70b2c08354698e9db840bbf1c6948ef0">setGoalBias</a> (double goalBias)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Set the goal bias.  <a href="#a70b2c08354698e9db840bbf1c6948ef0"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a3e21418a91e339c1ef88d6f230137f97"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::getGoalBias" ref="a3e21418a91e339c1ef88d6f230137f97" args="(void) const " -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a3e21418a91e339c1ef88d6f230137f97">getGoalBias</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Get the goal bias the planner is using. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a419daaa5e348bffc0910cd7c20f3ae7d">setRange</a> (double distance)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Set the range the planner is supposed to use.  <a href="#a419daaa5e348bffc0910cd7c20f3ae7d"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a94bbec9d263a902069a90a70ddb3d715"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::getRange" ref="a94bbec9d263a902069a90a70ddb3d715" args="(void) const " -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a94bbec9d263a902069a90a70ddb3d715">getRange</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Get the range the planner is using. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a4a58f01c44cce7010f946a51d326df96"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::setBallRadiusConstant" ref="a4a58f01c44cce7010f946a51d326df96" args="(double ballRadiusConstant)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a4a58f01c44cce7010f946a51d326df96">setBallRadiusConstant</a> (double ballRadiusConstant)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">When the planner attempts to rewire the tree, it does so by looking at some of the neighbors within a computed radius. The computation of that radius depends on the multiplicative factor set here. Set this parameter should be set at least to the side length of the (bounded) state space. E.g., if the state space is a box with side length L, then this parameter should be set to at least L for rapid and efficient convergence in trajectory space. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ad88faf8fc58653cf3318c270961713bf"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::getBallRadiusConstant" ref="ad88faf8fc58653cf3318c270961713bf" args="(void) const " -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#ad88faf8fc58653cf3318c270961713bf">getBallRadiusConstant</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Get the multiplicative factor used in the computation of the radius whithin which tree rewiring is done. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ad2d37a360030644b484ce3963d4ed348"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::setMaxBallRadius" ref="ad2d37a360030644b484ce3963d4ed348" args="(double maxBallRadius)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#ad2d37a360030644b484ce3963d4ed348">setMaxBallRadius</a> (double maxBallRadius)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">When the planner attempts to rewire the tree, it does so by looking at some of the neighbors within a computed radius. That radius is bounded by the value set here. This parameter should ideally be equal longest straight line from the initial state to anywhere in the state space. In other words, this parameter should be "sqrt(d) L", where d is the dimensionality of space and L is the side length of a box containing the obstacle free space. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a4f12db53111f2b1fe7bd1b2377207c19"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::getMaxBallRadius" ref="a4f12db53111f2b1fe7bd1b2377207c19" args="(void) const " -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a4f12db53111f2b1fe7bd1b2377207c19">getMaxBallRadius</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Get the maximum radius the planner uses in the tree rewiring step. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a84af5186357ce1d7380254d1cf59b83e"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::setInitialVolumeRadius" ref="a84af5186357ce1d7380254d1cf59b83e" args="(double rO)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a84af5186357ce1d7380254d1cf59b83e">setInitialVolumeRadius</a> (double rO)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Each vertex in the tree has a volume (hyper-sphere) associated with it. The radius of said volume is decreased when collisions are found within it. Samples found within any of the existing volumes are rejected. The value set here is the initial radius assigned to volumes added to the tree. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ad7518f0df19cdde74920c420736ca3c8"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::getInitialVolumeRadius" ref="ad7518f0df19cdde74920c420736ca3c8" args="(void) const " -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#ad7518f0df19cdde74920c420736ca3c8">getInitialVolumeRadius</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Get the initial volume radius. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a0eb8816c4b6f104969c7a416c0d2a5d1"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::inVolume" ref="a0eb8816c4b6f104969c7a416c0d2a5d1" args="(base::State *state)" -->
bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a0eb8816c4b6f104969c7a416c0d2a5d1">inVolume</a> (<a class="el" href="classompl_1_1base_1_1State.html">base::State</a> *state)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Verify if a state is inside an existing volume. <br/></td></tr>
<tr><td class="memTemplParams" colspan="2"><a class="anchor" id="ab055cfe175c683d665f2649e87d59006"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::setNearestNeighbors" ref="ab055cfe175c683d665f2649e87d59006" args="(void)" -->
template&lt;template&lt; typename T &gt; class NN&gt; </td></tr>
<tr><td class="memTemplItemLeft" align="right" valign="top">void&#160;</td><td class="memTemplItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#ab055cfe175c683d665f2649e87d59006">setNearestNeighbors</a> (void)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Set a different nearest neighbors datastructure. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ab66c1d17aef42d231e326f229d371cac"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::setDelayCC" ref="ab66c1d17aef42d231e326f229d371cac" args="(bool delayCC)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#ab66c1d17aef42d231e326f229d371cac">setDelayCC</a> (bool delayCC)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Option that delays collision checking procedures. When it is enabled, all neighbors are sorted by cost. The planner then goes through this list, starting with the lowest cost, checking for collisions in order to find a parent. The planner stops iterating through the list when a collision free parent is found. This prevents the planner from collsion checking each neighbor, reducing computation time in scenarios where collision checking procedures are expensive. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a81097da98a166e5d9d5a3c804e97d0cc"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::getDelayCC" ref="a81097da98a166e5d9d5a3c804e97d0cc" args="(void) const " -->
bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a81097da98a166e5d9d5a3c804e97d0cc">getDelayCC</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Get the state of the delayed collision checking option. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="afd5af5d5217dff1115820202d9c85ac3"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::setup" ref="afd5af5d5217dff1115820202d9c85ac3" args="(void)" -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#afd5af5d5217dff1115820202d9c85ac3">setup</a> (void)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Perform extra configuration steps, if needed. This call will also issue a call to <a class="el" href="classompl_1_1base_1_1SpaceInformation.html#ac39aa0c4b92e3ca5acfa75eeb56b080f" title="Perform additional setup tasks (run once, before use). If state validity checking resolution has not ...">ompl::base::SpaceInformation::setup()</a> if needed. This must be called before solving. <br/></td></tr>
<tr><td colspan="2"><h2><a name="pro-methods"></a>
Protected Member Functions</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ace1165ebcf8b4712422bc53a73ae5dec"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::freeMemory" ref="ace1165ebcf8b4712422bc53a73ae5dec" args="(void)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#ace1165ebcf8b4712422bc53a73ae5dec">freeMemory</a> (void)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Free the memory allocated by this planner. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a8c21342a5f17ed28477efe458e123195"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::addMotion" ref="a8c21342a5f17ed28477efe458e123195" args="(Motion *m)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a8c21342a5f17ed28477efe458e123195">addMotion</a> (<a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html">Motion</a> *m)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Add a motion to the tree. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ad23854a908038c8caf45c9ab8421acc1"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::distanceFunction" ref="ad23854a908038c8caf45c9ab8421acc1" args="(const Motion *a, const Motion *b) const " -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#ad23854a908038c8caf45c9ab8421acc1">distanceFunction</a> (const <a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html">Motion</a> *a, const <a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html">Motion</a> *b) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Distance calculation considering volumes. <br/></td></tr>
<tr><td colspan="2"><h2><a name="pro-static-methods"></a>
Static Protected Member Functions</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a449342b8dd1ff55891a0f567607e53be"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::compareMotion" ref="a449342b8dd1ff55891a0f567607e53be" args="(const Motion *a, const Motion *b)" -->
static bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a449342b8dd1ff55891a0f567607e53be">compareMotion</a> (const <a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html">Motion</a> *a, const <a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html">Motion</a> *b)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Sort the near neighbors by cost. <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="anchor" id="a6e8cc8d05aa98c353c6c048c17835e54"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::sampler_" ref="a6e8cc8d05aa98c353c6c048c17835e54" args="" -->
<a class="el" href="classompl_1_1base_1_1StateSamplerPtr.html">base::StateSamplerPtr</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a6e8cc8d05aa98c353c6c048c17835e54">sampler_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">State sampler. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="acc4f6c9bc0eab53494c14c1410c11484"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::nn_" ref="acc4f6c9bc0eab53494c14c1410c11484" args="" -->
boost::shared_ptr<br class="typebreak"/>
&lt; <a class="el" href="classompl_1_1NearestNeighbors.html">NearestNeighbors</a>&lt; <a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html">Motion</a> * &gt; &gt;&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#acc4f6c9bc0eab53494c14c1410c11484">nn_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">A nearest-neighbors datastructure containing the tree of motions. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a0e00059a9ab09563c25d7bc378ae65f6"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::motions_" ref="a0e00059a9ab09563c25d7bc378ae65f6" args="" -->
std::vector&lt; <a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html">Motion</a> * &gt;&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a0e00059a9ab09563c25d7bc378ae65f6">motions_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">A copy of the list of motions in the tree used for faser verification of samples. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a33a19e26f0cec791f0bdf871155f603b"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::goalBias_" ref="a33a19e26f0cec791f0bdf871155f603b" args="" -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a33a19e26f0cec791f0bdf871155f603b">goalBias_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The fraction of time the goal is picked as the state to expand towards (if such a state is available) <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a74f84ff8f56b4413a617bee1dc5ee68d"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::maxDistance_" ref="a74f84ff8f56b4413a617bee1dc5ee68d" args="" -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a74f84ff8f56b4413a617bee1dc5ee68d">maxDistance_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The maximum length of a motion to be added to a tree. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a9c8c838fdf405d6720a282688e1918c7"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::rng_" ref="a9c8c838fdf405d6720a282688e1918c7" args="" -->
<a class="el" href="classompl_1_1RNG.html">RNG</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a9c8c838fdf405d6720a282688e1918c7">rng_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The random number generator. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ae031c5ecc5c5a557692862f41d325f11"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::ballRadiusConst_" ref="ae031c5ecc5c5a557692862f41d325f11" args="" -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#ae031c5ecc5c5a557692862f41d325f11">ballRadiusConst_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Shrink rate of radius the planner uses to find near neighbors and rewire. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a313137f73961f360e6eebaba79f21315"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::ballRadiusMax_" ref="a313137f73961f360e6eebaba79f21315" args="" -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a313137f73961f360e6eebaba79f21315">ballRadiusMax_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Maximum radius the planner uses to find near neighbors and rewire. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ace5c17f5eae277cbe6c9e2dc8f3fb1ed"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::delayCC_" ref="ace5c17f5eae277cbe6c9e2dc8f3fb1ed" args="" -->
bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#ace5c17f5eae277cbe6c9e2dc8f3fb1ed">delayCC_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Option to delay and reduce collision checking within iterations. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a55358bb64b5f55532df2961ccccd8a5a"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::rO_" ref="a55358bb64b5f55532df2961ccccd8a5a" args="" -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a55358bb64b5f55532df2961ccccd8a5a">rO_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Initial radius of volumes assigned to new vertices in the tree. <br/></td></tr>
</table>
<hr/><a name="details" id="details"></a><h2>Detailed Description</h2>
<div class="textblock"><p>Optimal Rapidly-exploring Random Trees with Ball Trees. </p>
<p><a class="anchor" id="gBallTreeRRTstar"></a></p>
<dl class="user"><dt><b>Short description</b></dt><dd>Implementation of <a class="el" href="classompl_1_1geometric_1_1RRTstar.html#gRRTstar">RRT*</a> that incorporates Ball Trees to approximate connected regions of free space with volumes in configuration space instead of points. Every vertex added to the tree has an initial volume of an infinite radius associated with it. This radius is gradually reduced as collisions are found. All samples within any of the existing volumes are discarded. However, discarded samples are collision checked. If a collision is found, the nearest volume is trimmed at the collision point. Information from all collision checking procedures within iterations is also used to trim volumes accordingly. The radii of volumes are considered when computing nearest/near neighbors. This implementation is suited for high-dimensional planning problems with narrow collision boundary passages.</dd></dl>
<dl class="user"><dt><b>External documentation</b></dt><dd>A. Perez, S. Karaman, M. Walter, A. Shkolnik, E. Frazzoli, S. Teller, Asymptotically-optimal Manipulation Planning using Incremental Sampling-based Algorithms, IEEE/RSJ International Conference on Intelligent Robots and Systems, 2011. <br/>
<br/>
 S. Karaman and E. Frazzoli, Sampling-based Algorithms for Optimal <a class="el" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html" title="Representation of a motion.">Motion</a> Planning, International Journal of Robotics Research (to appear), 2011. <a href="http://arxiv.org/abs/1105.1186">http://arxiv.org/abs/1105.1186</a> </dd></dl>

<p>Definition at line <a class="el" href="BallTreeRRTstar_8h_source.html#l00080">80</a> of file <a class="el" href="BallTreeRRTstar_8h_source.html">BallTreeRRTstar.h</a>.</p>
</div><hr/><h2>Member Function Documentation</h2>
<a class="anchor" id="a70b2c08354698e9db840bbf1c6948ef0"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::setGoalBias" ref="a70b2c08354698e9db840bbf1c6948ef0" args="(double goalBias)" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">void ompl::geometric::BallTreeRRTstar::setGoalBias </td>
          <td>(</td>
          <td class="paramtype">double&#160;</td>
          <td class="paramname"><em>goalBias</em></td><td>)</td>
          <td><code> [inline]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Set the goal bias. </p>
<p>In the process of randomly selecting states in the state space to attempt to go towards, the algorithm may in fact choose the actual goal state, if it knows it, with some probability. This probability is a real number between 0.0 and 1.0; its value should usually be around 0.05 and should not be too large. It is probably a good idea to use the default value. </p>

<p>Definition at line <a class="el" href="BallTreeRRTstar_8h_source.html#l00117">117</a> of file <a class="el" href="BallTreeRRTstar_8h_source.html">BallTreeRRTstar.h</a>.</p>

</div>
</div>
<a class="anchor" id="a419daaa5e348bffc0910cd7c20f3ae7d"></a><!-- doxytag: member="ompl::geometric::BallTreeRRTstar::setRange" ref="a419daaa5e348bffc0910cd7c20f3ae7d" args="(double distance)" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">void ompl::geometric::BallTreeRRTstar::setRange </td>
          <td>(</td>
          <td class="paramtype">double&#160;</td>
          <td class="paramname"><em>distance</em></td><td>)</td>
          <td><code> [inline]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Set the range the planner is supposed to use. </p>
<p>This parameter greatly influences the runtime of the algorithm. It represents the maximum length of a motion to be added in the tree of motions. </p>

<p>Definition at line <a class="el" href="BallTreeRRTstar_8h_source.html#l00133">133</a> of file <a class="el" href="BallTreeRRTstar_8h_source.html">BallTreeRRTstar.h</a>.</p>

</div>
</div>
<hr/>The documentation for this class was generated from the following files:<ul>
<li>src/ompl/contrib/rrt_star/<a class="el" href="BallTreeRRTstar_8h_source.html">BallTreeRRTstar.h</a></li>
<li>src/ompl/contrib/rrt_star/src/<a class="el" href="BallTreeRRTstar_8cpp_source.html">BallTreeRRTstar.cpp</a></li>
</ul>
</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">&#160;</span>All</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(1)"><span class="SelectionMark">&#160;</span>Classes</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(2)"><span class="SelectionMark">&#160;</span>Namespaces</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(3)"><span class="SelectionMark">&#160;</span>Functions</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(4)"><span class="SelectionMark">&#160;</span>Variables</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(5)"><span class="SelectionMark">&#160;</span>Typedefs</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(6)"><span class="SelectionMark">&#160;</span>Enumerations</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(7)"><span class="SelectionMark">&#160;</span>Enumerator</a></div>

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

</div>

<div class="footer span-22 push-2 last">
  <a href="http://www.kavrakilab.org">Physical and Biological Computing Group</a> &bull;
  <a href="http://www.cs.rice.edu">Department of Computer Science</a> &bull;
  <a href="http://www.rice.edu">Rice University</a><br>
  <div class="gray">Generated on Sun Oct 9 2011 23:04:32 by&#160;<a href="http://www.doxygen.org/index.html">doxygen</a> 1.7.4</div>
</div>
</div>
</body>
</html>