Sophie

Sophie

distrib > Fedora > 14 > x86_64 > media > updates > by-pkgid > e7618febbb9cbed15bb79e326774c050 > files > 852

ompl-devel-0.9.5-1.fc14.i686.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::RRTConnect 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_1RRTConnect.html">RRTConnect</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-types">Protected Types</a> &#124;
<a href="#pro-methods">Protected Member Functions</a> &#124;
<a href="#pro-attribs">Protected Attributes</a>  </div>
  <div class="headertitle">
<div class="title">ompl::geometric::RRTConnect Class Reference</div>  </div>
</div>
<div class="contents">
<!-- doxytag: class="ompl::geometric::RRTConnect" --><!-- doxytag: inherits="ompl::base::Planner" -->
<p>RRT-Connect (<a class="el" href="classompl_1_1geometric_1_1RRTConnect.html" title="RRT-Connect (RRTConnect)">RRTConnect</a>)  
 <a href="classompl_1_1geometric_1_1RRTConnect.html#details">More...</a></p>

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

<p><a href="classompl_1_1geometric_1_1RRTConnect-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_1RRTConnect_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_1RRTConnect_1_1Motion.html#details">More...</a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">struct &#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="structompl_1_1geometric_1_1RRTConnect_1_1TreeGrowingInfo.html">TreeGrowingInfo</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Information attached to growing a tree of motions (used internally)  <a href="structompl_1_1geometric_1_1RRTConnect_1_1TreeGrowingInfo.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="a918795ad317b8cee40184c3e289f8d51"></a><!-- doxytag: member="ompl::geometric::RRTConnect::RRTConnect" ref="a918795ad317b8cee40184c3e289f8d51" args="(const base::SpaceInformationPtr &amp;si)" -->
&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1RRTConnect.html#a918795ad317b8cee40184c3e289f8d51">RRTConnect</a> (const <a class="el" href="classompl_1_1base_1_1SpaceInformationPtr.html">base::SpaceInformationPtr</a> &amp;si)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Constructor. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a32e3f019f790cb85b1f97a6cacb02e02"></a><!-- doxytag: member="ompl::geometric::RRTConnect::getPlannerData" ref="a32e3f019f790cb85b1f97a6cacb02e02" args="(base::PlannerData &amp;data) const " -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1RRTConnect.html#a32e3f019f790cb85b1f97a6cacb02e02">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_1RRTConnect.html#ad092b4c369524ec515a0e034ca0841a8" 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_1RRTConnect.html#a326036b610e5499a9a670ea4710e8836" 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="ad092b4c369524ec515a0e034ca0841a8"></a><!-- doxytag: member="ompl::geometric::RRTConnect::solve" ref="ad092b4c369524ec515a0e034ca0841a8" args="(const base::PlannerTerminationCondition &amp;ptc)" -->
virtual bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1RRTConnect.html#ad092b4c369524ec515a0e034ca0841a8">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_1RRTConnect.html#a326036b610e5499a9a670ea4710e8836" 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="a326036b610e5499a9a670ea4710e8836"></a><!-- doxytag: member="ompl::geometric::RRTConnect::clear" ref="a326036b610e5499a9a670ea4710e8836" args="(void)" -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1RRTConnect.html#a326036b610e5499a9a670ea4710e8836">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_1RRTConnect.html#ad092b4c369524ec515a0e034ca0841a8" 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_1RRTConnect.html#a6d672e3b8c4e5f09719a5db74c75ca41">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="#a6d672e3b8c4e5f09719a5db74c75ca41"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a3f06e1c02794be2aa0772c24a884e23d"></a><!-- doxytag: member="ompl::geometric::RRTConnect::getRange" ref="a3f06e1c02794be2aa0772c24a884e23d" args="(void) const " -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1RRTConnect.html#a3f06e1c02794be2aa0772c24a884e23d">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="memTemplParams" colspan="2"><a class="anchor" id="aaba0205ad436dc8d4e339ce5d06c159a"></a><!-- doxytag: member="ompl::geometric::RRTConnect::setNearestNeighbors" ref="aaba0205ad436dc8d4e339ce5d06c159a" 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_1RRTConnect.html#aaba0205ad436dc8d4e339ce5d06c159a">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="a860d8f7ab5c9b791dac4bf4aaaf305e6"></a><!-- doxytag: member="ompl::geometric::RRTConnect::setup" ref="a860d8f7ab5c9b791dac4bf4aaaf305e6" args="(void)" -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1RRTConnect.html#a860d8f7ab5c9b791dac4bf4aaaf305e6">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-types"></a>
Protected Types</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">enum &#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1RRTConnect.html#a6df5b0ed7234e4a70f82fd84f3e83c4b">GrowState</a> { <a class="el" href="classompl_1_1geometric_1_1RRTConnect.html#a6df5b0ed7234e4a70f82fd84f3e83c4ba8c504cf08c1829a11f98ce4d6f38320b">TRAPPED</a>, 
<a class="el" href="classompl_1_1geometric_1_1RRTConnect.html#a6df5b0ed7234e4a70f82fd84f3e83c4ba0969940dcdb34f22e1a1ce0c9129e7ca">ADVANCED</a>, 
<a class="el" href="classompl_1_1geometric_1_1RRTConnect.html#a6df5b0ed7234e4a70f82fd84f3e83c4baf7876405ca61b09872f30ab8c79a12eb">REACHED</a>
 }</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The state of the tree after an attempt to extend it.  <a href="classompl_1_1geometric_1_1RRTConnect.html#a6df5b0ed7234e4a70f82fd84f3e83c4b">More...</a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a605e6a7c713167b8655d06a8a30b91ef"></a><!-- doxytag: member="ompl::geometric::RRTConnect::TreeData" ref="a605e6a7c713167b8655d06a8a30b91ef" args="" -->
typedef 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_1RRTConnect_1_1Motion.html">Motion</a> * &gt; &gt;&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1RRTConnect.html#a605e6a7c713167b8655d06a8a30b91ef">TreeData</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">A nearest-neighbor datastructure representing a tree of motions. <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="a9d0cee3c86dff92db60fe02806f5a27c"></a><!-- doxytag: member="ompl::geometric::RRTConnect::freeMemory" ref="a9d0cee3c86dff92db60fe02806f5a27c" args="(void)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1RRTConnect.html#a9d0cee3c86dff92db60fe02806f5a27c">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="a96e7a7a8ed32a88c490204fcb8847fb5"></a><!-- doxytag: member="ompl::geometric::RRTConnect::distanceFunction" ref="a96e7a7a8ed32a88c490204fcb8847fb5" args="(const Motion *a, const Motion *b) const " -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1RRTConnect.html#a96e7a7a8ed32a88c490204fcb8847fb5">distanceFunction</a> (const <a class="el" href="classompl_1_1geometric_1_1RRTConnect_1_1Motion.html">Motion</a> *a, const <a class="el" href="classompl_1_1geometric_1_1RRTConnect_1_1Motion.html">Motion</a> *b) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Compute distance between motions (actually distance between contained states) <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a140a2bf524fe7c39dfbe1e8d5f55fe80"></a><!-- doxytag: member="ompl::geometric::RRTConnect::growTree" ref="a140a2bf524fe7c39dfbe1e8d5f55fe80" args="(TreeData &amp;tree, TreeGrowingInfo &amp;tgi, Motion *rmotion)" -->
<a class="el" href="classompl_1_1geometric_1_1RRTConnect.html#a6df5b0ed7234e4a70f82fd84f3e83c4b">GrowState</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1RRTConnect.html#a140a2bf524fe7c39dfbe1e8d5f55fe80">growTree</a> (<a class="el" href="classompl_1_1geometric_1_1RRTConnect.html#a605e6a7c713167b8655d06a8a30b91ef">TreeData</a> &amp;tree, <a class="el" href="structompl_1_1geometric_1_1RRTConnect_1_1TreeGrowingInfo.html">TreeGrowingInfo</a> &amp;tgi, <a class="el" href="classompl_1_1geometric_1_1RRTConnect_1_1Motion.html">Motion</a> *rmotion)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Grow a tree towards a random state. <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="abb9c22bc9815d896ae9c029b2047b0da"></a><!-- doxytag: member="ompl::geometric::RRTConnect::sampler_" ref="abb9c22bc9815d896ae9c029b2047b0da" 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_1RRTConnect.html#abb9c22bc9815d896ae9c029b2047b0da">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="a91ce4e34b670b36588fdcc7030fe692d"></a><!-- doxytag: member="ompl::geometric::RRTConnect::tStart_" ref="a91ce4e34b670b36588fdcc7030fe692d" args="" -->
<a class="el" href="classompl_1_1geometric_1_1RRTConnect.html#a605e6a7c713167b8655d06a8a30b91ef">TreeData</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1RRTConnect.html#a91ce4e34b670b36588fdcc7030fe692d">tStart_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The start tree. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="aeeb74200ede46e3d1eef584325ec1484"></a><!-- doxytag: member="ompl::geometric::RRTConnect::tGoal_" ref="aeeb74200ede46e3d1eef584325ec1484" args="" -->
<a class="el" href="classompl_1_1geometric_1_1RRTConnect.html#a605e6a7c713167b8655d06a8a30b91ef">TreeData</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1RRTConnect.html#aeeb74200ede46e3d1eef584325ec1484">tGoal_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The goal tree. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a299caf818f757d96793d1bc092a665b3"></a><!-- doxytag: member="ompl::geometric::RRTConnect::maxDistance_" ref="a299caf818f757d96793d1bc092a665b3" args="" -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1RRTConnect.html#a299caf818f757d96793d1bc092a665b3">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="a89885ce34b34c5c880993f3ad553bffa"></a><!-- doxytag: member="ompl::geometric::RRTConnect::rng_" ref="a89885ce34b34c5c880993f3ad553bffa" 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_1RRTConnect.html#a89885ce34b34c5c880993f3ad553bffa">rng_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The random number generator. <br/></td></tr>
</table>
<hr/><a name="details" id="details"></a><h2>Detailed Description</h2>
<div class="textblock"><p>RRT-Connect (<a class="el" href="classompl_1_1geometric_1_1RRTConnect.html" title="RRT-Connect (RRTConnect)">RRTConnect</a>) </p>
<p><a class="anchor" id="gRRTC"></a></p>
<dl class="user"><dt><b>Short description</b></dt><dd>The basic idea is to grow to RRTs, one from the start and one from the goal, and attempt to connect them.</dd></dl>
<dl class="user"><dt><b>External documentation</b></dt><dd>J. Kuffner and S.M. LaValle, RRT-connect: An efficient approach to single-query path planning, in <em>Proc. 2000 IEEE Intl. Conf. on Robotics and Automation</em>, pp. 995–1001, Apr. 2000. DOI: <a href="http://dx.doi.org/10.1109/ROBOT.2000.844730">10.1109/ROBOT.2000.844730</a><br/>
 <a href="http://ieeexplore.ieee.org/ielx5/6794/18246/00844730.pdf?tp=&amp;arnumber=844730&amp;isnumber=18246">[PDF]</a> <a href="http://msl.cs.uiuc.edu/~lavalle/rrtpubs.html">[more]</a> </dd></dl>

<p>Definition at line <a class="el" href="RRTConnect_8h_source.html#l00063">63</a> of file <a class="el" href="RRTConnect_8h_source.html">RRTConnect.h</a>.</p>
</div><hr/><h2>Member Enumeration Documentation</h2>
<a class="anchor" id="a6df5b0ed7234e4a70f82fd84f3e83c4b"></a><!-- doxytag: member="ompl::geometric::RRTConnect::GrowState" ref="a6df5b0ed7234e4a70f82fd84f3e83c4b" args="" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">enum <a class="el" href="classompl_1_1geometric_1_1RRTConnect.html#a6df5b0ed7234e4a70f82fd84f3e83c4b">ompl::geometric::RRTConnect::GrowState</a><code> [protected]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>The state of the tree after an attempt to extend it. </p>
<dl><dt><b>Enumerator: </b></dt><dd><table border="0" cellspacing="2" cellpadding="0">
<tr><td valign="top"><em><a class="anchor" id="a6df5b0ed7234e4a70f82fd84f3e83c4ba8c504cf08c1829a11f98ce4d6f38320b"></a><!-- doxytag: member="TRAPPED" ref="a6df5b0ed7234e4a70f82fd84f3e83c4ba8c504cf08c1829a11f98ce4d6f38320b" args="" -->TRAPPED</em>&nbsp;</td><td>
<p>no progress has been made </p>
</td></tr>
<tr><td valign="top"><em><a class="anchor" id="a6df5b0ed7234e4a70f82fd84f3e83c4ba0969940dcdb34f22e1a1ce0c9129e7ca"></a><!-- doxytag: member="ADVANCED" ref="a6df5b0ed7234e4a70f82fd84f3e83c4ba0969940dcdb34f22e1a1ce0c9129e7ca" args="" -->ADVANCED</em>&nbsp;</td><td>
<p>progress has been made towards the randomly sampled state </p>
</td></tr>
<tr><td valign="top"><em><a class="anchor" id="a6df5b0ed7234e4a70f82fd84f3e83c4baf7876405ca61b09872f30ab8c79a12eb"></a><!-- doxytag: member="REACHED" ref="a6df5b0ed7234e4a70f82fd84f3e83c4baf7876405ca61b09872f30ab8c79a12eb" args="" -->REACHED</em>&nbsp;</td><td>
<p>the randomly sampled state was reached </p>
</td></tr>
</table>
</dd>
</dl>

<p>Definition at line <a class="el" href="RRTConnect_8h_source.html#l00149">149</a> of file <a class="el" href="RRTConnect_8h_source.html">RRTConnect.h</a>.</p>

</div>
</div>
<hr/><h2>Member Function Documentation</h2>
<a class="anchor" id="a6d672e3b8c4e5f09719a5db74c75ca41"></a><!-- doxytag: member="ompl::geometric::RRTConnect::setRange" ref="a6d672e3b8c4e5f09719a5db74c75ca41" args="(double distance)" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">void ompl::geometric::RRTConnect::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="RRTConnect_8h_source.html#l00090">90</a> of file <a class="el" href="RRTConnect_8h_source.html">RRTConnect.h</a>.</p>

</div>
</div>
<hr/>The documentation for this class was generated from the following files:<ul>
<li>src/ompl/geometric/planners/rrt/<a class="el" href="RRTConnect_8h_source.html">RRTConnect.h</a></li>
<li>src/ompl/geometric/planners/rrt/src/<a class="el" href="RRTConnect_8cpp_source.html">RRTConnect.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:43 by&#160;<a href="http://www.doxygen.org/index.html">doxygen</a> 1.7.4</div>
</div>
</div>
</body>
</html>