Sophie

Sophie

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

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::pSBL 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_1pSBL.html">pSBL</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::pSBL Class Reference</div>  </div>
</div>
<div class="contents">
<!-- doxytag: class="ompl::geometric::pSBL" --><!-- doxytag: inherits="ompl::base::Planner" -->
<p>Parallel Single-query Bi-directional Lazy collision checking planner.  
 <a href="classompl_1_1geometric_1_1pSBL.html#details">More...</a></p>

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

<p><a href="classompl_1_1geometric_1_1pSBL-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_1pSBL_1_1Motion.html">Motion</a></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_1pSBL_1_1MotionsToBeRemoved.html">MotionsToBeRemoved</a></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_1pSBL_1_1PendingRemoveMotion.html">PendingRemoveMotion</a></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_1pSBL_1_1SolutionInfo.html">SolutionInfo</a></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_1pSBL_1_1TreeData.html">TreeData</a></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="aacebf35422f656c75876c64f2d23c613"></a><!-- doxytag: member="ompl::geometric::pSBL::pSBL" ref="aacebf35422f656c75876c64f2d23c613" args="(const base::SpaceInformationPtr &amp;si)" -->
&#160;</td><td class="memItemRight" valign="bottom"><b>pSBL</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="a8c706561dc3d5256a69f8aff5a6a4dab"></a><!-- doxytag: member="ompl::geometric::pSBL::setProjectionEvaluator" ref="a8c706561dc3d5256a69f8aff5a6a4dab" args="(const base::ProjectionEvaluatorPtr &amp;projectionEvaluator)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1pSBL.html#a8c706561dc3d5256a69f8aff5a6a4dab">setProjectionEvaluator</a> (const <a class="el" href="classompl_1_1base_1_1ProjectionEvaluatorPtr.html">base::ProjectionEvaluatorPtr</a> &amp;projectionEvaluator)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Set the projection evaluator. This class is able to compute the projection of a given state. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a3ef968832cbe29236891c5ae731219fc"></a><!-- doxytag: member="ompl::geometric::pSBL::setProjectionEvaluator" ref="a3ef968832cbe29236891c5ae731219fc" args="(const std::string &amp;name)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1pSBL.html#a3ef968832cbe29236891c5ae731219fc">setProjectionEvaluator</a> (const std::string &amp;name)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Set the projection evaluator (select one from the ones registered with the state space). <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a20eedcfed1958742d8544019c9b0aa1b"></a><!-- doxytag: member="ompl::geometric::pSBL::getProjectionEvaluator" ref="a20eedcfed1958742d8544019c9b0aa1b" args="(void) const " -->
const <br class="typebreak"/>
<a class="el" href="classompl_1_1base_1_1ProjectionEvaluatorPtr.html">base::ProjectionEvaluatorPtr</a> &amp;&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1pSBL.html#a20eedcfed1958742d8544019c9b0aa1b">getProjectionEvaluator</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Get the projection evaluator. <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_1pSBL.html#a684881ad135214cf17dc1d417a921805">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="#a684881ad135214cf17dc1d417a921805"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a47a7c09e116767f3f65bdcddb27efe06"></a><!-- doxytag: member="ompl::geometric::pSBL::getRange" ref="a47a7c09e116767f3f65bdcddb27efe06" args="(void) const " -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1pSBL.html#a47a7c09e116767f3f65bdcddb27efe06">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="aa4ac4755ecdf651d5d0e584cbf742393"></a><!-- doxytag: member="ompl::geometric::pSBL::setThreadCount" ref="aa4ac4755ecdf651d5d0e584cbf742393" args="(unsigned int nthreads)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1pSBL.html#aa4ac4755ecdf651d5d0e584cbf742393">setThreadCount</a> (unsigned int nthreads)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Set the number of threads the planner should use. Default is 2. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="af708e182215462c0f20e3898bc8ba058"></a><!-- doxytag: member="ompl::geometric::pSBL::getThreadCount" ref="af708e182215462c0f20e3898bc8ba058" args="(void) const " -->
unsigned int&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1pSBL.html#af708e182215462c0f20e3898bc8ba058">getThreadCount</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Get the thread count. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a851c7b44dba6a0fd1bcb34398648cd4e"></a><!-- doxytag: member="ompl::geometric::pSBL::setup" ref="a851c7b44dba6a0fd1bcb34398648cd4e" args="(void)" -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1pSBL.html#a851c7b44dba6a0fd1bcb34398648cd4e">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 class="memItemLeft" align="right" valign="top"><a class="anchor" id="a530a526d834942258dd8a9b3a834169c"></a><!-- doxytag: member="ompl::geometric::pSBL::solve" ref="a530a526d834942258dd8a9b3a834169c" args="(const base::PlannerTerminationCondition &amp;ptc)" -->
virtual bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1pSBL.html#a530a526d834942258dd8a9b3a834169c">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_1pSBL.html#a67d9f5777ea40053c65a354663965d93" 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="a67d9f5777ea40053c65a354663965d93"></a><!-- doxytag: member="ompl::geometric::pSBL::clear" ref="a67d9f5777ea40053c65a354663965d93" args="(void)" -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1pSBL.html#a67d9f5777ea40053c65a354663965d93">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_1pSBL.html#a530a526d834942258dd8a9b3a834169c" 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"><a class="anchor" id="ab9f5004971fe0571e6145a64e4a8772c"></a><!-- doxytag: member="ompl::geometric::pSBL::getPlannerData" ref="ab9f5004971fe0571e6145a64e4a8772c" args="(base::PlannerData &amp;data) const " -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1pSBL.html#ab9f5004971fe0571e6145a64e4a8772c">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_1pSBL.html#a530a526d834942258dd8a9b3a834169c" 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_1pSBL.html#a67d9f5777ea40053c65a354663965d93" title="Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...">clear()</a> in between). <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"><a class="anchor" id="ae977e1d5b5a097bcb186a4edaecc61b8"></a><!-- doxytag: member="ompl::geometric::pSBL::MotionSet" ref="ae977e1d5b5a097bcb186a4edaecc61b8" args="" -->
typedef std::vector&lt; <a class="el" href="classompl_1_1geometric_1_1pSBL_1_1Motion.html">Motion</a> * &gt;&#160;</td><td class="memItemRight" valign="bottom"><b>MotionSet</b></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="ae7238d186ae66d8ab4572ae6817b7cf8"></a><!-- doxytag: member="ompl::geometric::pSBL::threadSolve" ref="ae7238d186ae66d8ab4572ae6817b7cf8" args="(unsigned int tid, const base::PlannerTerminationCondition &amp;ptc, SolutionInfo *sol)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><b>threadSolve</b> (unsigned int tid, const <a class="el" href="classompl_1_1base_1_1PlannerTerminationCondition.html">base::PlannerTerminationCondition</a> &amp;ptc, <a class="el" href="structompl_1_1geometric_1_1pSBL_1_1SolutionInfo.html">SolutionInfo</a> *sol)</td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a9b282d7ec9caab961b33c6bac753bec0"></a><!-- doxytag: member="ompl::geometric::pSBL::freeMemory" ref="a9b282d7ec9caab961b33c6bac753bec0" args="(void)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><b>freeMemory</b> (void)</td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="add325731806e40c48ce4cd43e24b1352"></a><!-- doxytag: member="ompl::geometric::pSBL::freeGridMotions" ref="add325731806e40c48ce4cd43e24b1352" args="(Grid&lt; MotionSet &gt; &amp;grid)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><b>freeGridMotions</b> (<a class="el" href="classompl_1_1Grid.html">Grid</a>&lt; MotionSet &gt; &amp;grid)</td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a08949a5f5458d9df051724fd0a2b5709"></a><!-- doxytag: member="ompl::geometric::pSBL::addMotion" ref="a08949a5f5458d9df051724fd0a2b5709" args="(TreeData &amp;tree, Motion *motion)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><b>addMotion</b> (<a class="el" href="structompl_1_1geometric_1_1pSBL_1_1TreeData.html">TreeData</a> &amp;tree, <a class="el" href="classompl_1_1geometric_1_1pSBL_1_1Motion.html">Motion</a> *motion)</td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a4149fb6d3aec41a904ed996ee500bcb5"></a><!-- doxytag: member="ompl::geometric::pSBL::selectMotion" ref="a4149fb6d3aec41a904ed996ee500bcb5" args="(RNG &amp;rng, TreeData &amp;tree)" -->
<a class="el" href="classompl_1_1geometric_1_1pSBL_1_1Motion.html">Motion</a> *&#160;</td><td class="memItemRight" valign="bottom"><b>selectMotion</b> (<a class="el" href="classompl_1_1RNG.html">RNG</a> &amp;rng, <a class="el" href="structompl_1_1geometric_1_1pSBL_1_1TreeData.html">TreeData</a> &amp;tree)</td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a207f989e20b02df5f7ed78acd7534c45"></a><!-- doxytag: member="ompl::geometric::pSBL::removeMotion" ref="a207f989e20b02df5f7ed78acd7534c45" args="(TreeData &amp;tree, Motion *motion, std::map&lt; Motion *, bool &gt; &amp;seen)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><b>removeMotion</b> (<a class="el" href="structompl_1_1geometric_1_1pSBL_1_1TreeData.html">TreeData</a> &amp;tree, <a class="el" href="classompl_1_1geometric_1_1pSBL_1_1Motion.html">Motion</a> *motion, std::map&lt; <a class="el" href="classompl_1_1geometric_1_1pSBL_1_1Motion.html">Motion</a> *, bool &gt; &amp;seen)</td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a6d23c46579ff6a554ed800d30bfe5c81"></a><!-- doxytag: member="ompl::geometric::pSBL::isPathValid" ref="a6d23c46579ff6a554ed800d30bfe5c81" args="(TreeData &amp;tree, Motion *motion)" -->
bool&#160;</td><td class="memItemRight" valign="bottom"><b>isPathValid</b> (<a class="el" href="structompl_1_1geometric_1_1pSBL_1_1TreeData.html">TreeData</a> &amp;tree, <a class="el" href="classompl_1_1geometric_1_1pSBL_1_1Motion.html">Motion</a> *motion)</td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a3d388e9d2035d55863ff09257dfcfb5c"></a><!-- doxytag: member="ompl::geometric::pSBL::checkSolution" ref="a3d388e9d2035d55863ff09257dfcfb5c" args="(RNG &amp;rng, bool start, TreeData &amp;tree, TreeData &amp;otherTree, Motion *motion, std::vector&lt; Motion * &gt; &amp;solution)" -->
bool&#160;</td><td class="memItemRight" valign="bottom"><b>checkSolution</b> (<a class="el" href="classompl_1_1RNG.html">RNG</a> &amp;rng, bool start, <a class="el" href="structompl_1_1geometric_1_1pSBL_1_1TreeData.html">TreeData</a> &amp;tree, <a class="el" href="structompl_1_1geometric_1_1pSBL_1_1TreeData.html">TreeData</a> &amp;otherTree, <a class="el" href="classompl_1_1geometric_1_1pSBL_1_1Motion.html">Motion</a> *motion, std::vector&lt; <a class="el" href="classompl_1_1geometric_1_1pSBL_1_1Motion.html">Motion</a> * &gt; &amp;solution)</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="a774572736222992b55dcfa1c9eb60a61"></a><!-- doxytag: member="ompl::geometric::pSBL::samplerArray_" ref="a774572736222992b55dcfa1c9eb60a61" args="" -->
<a class="el" href="classompl_1_1base_1_1StateSamplerArray.html">base::StateSamplerArray</a><br class="typebreak"/>
&lt; <a class="el" href="classompl_1_1base_1_1ValidStateSampler.html">base::ValidStateSampler</a> &gt;&#160;</td><td class="memItemRight" valign="bottom"><b>samplerArray_</b></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a02fdba76e3486e038eb54633feea5ff4"></a><!-- doxytag: member="ompl::geometric::pSBL::projectionEvaluator_" ref="a02fdba76e3486e038eb54633feea5ff4" args="" -->
<a class="el" href="classompl_1_1base_1_1ProjectionEvaluatorPtr.html">base::ProjectionEvaluatorPtr</a>&#160;</td><td class="memItemRight" valign="bottom"><b>projectionEvaluator_</b></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a42720872d254218face09f33d6fc1b72"></a><!-- doxytag: member="ompl::geometric::pSBL::tStart_" ref="a42720872d254218face09f33d6fc1b72" args="" -->
<a class="el" href="structompl_1_1geometric_1_1pSBL_1_1TreeData.html">TreeData</a>&#160;</td><td class="memItemRight" valign="bottom"><b>tStart_</b></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a2fe6ca00643816e6eae508e446ebb08b"></a><!-- doxytag: member="ompl::geometric::pSBL::tGoal_" ref="a2fe6ca00643816e6eae508e446ebb08b" args="" -->
<a class="el" href="structompl_1_1geometric_1_1pSBL_1_1TreeData.html">TreeData</a>&#160;</td><td class="memItemRight" valign="bottom"><b>tGoal_</b></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="aedb4dde823d000402e274be080ab46c6"></a><!-- doxytag: member="ompl::geometric::pSBL::removeList_" ref="aedb4dde823d000402e274be080ab46c6" args="" -->
<a class="el" href="structompl_1_1geometric_1_1pSBL_1_1MotionsToBeRemoved.html">MotionsToBeRemoved</a>&#160;</td><td class="memItemRight" valign="bottom"><b>removeList_</b></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a2ebcf61b9a2a9a0f664de3f3513b5463"></a><!-- doxytag: member="ompl::geometric::pSBL::loopLock_" ref="a2ebcf61b9a2a9a0f664de3f3513b5463" args="" -->
boost::mutex&#160;</td><td class="memItemRight" valign="bottom"><b>loopLock_</b></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ab355035ff3f154c0ad560627c082a133"></a><!-- doxytag: member="ompl::geometric::pSBL::loopLockCounter_" ref="ab355035ff3f154c0ad560627c082a133" args="" -->
boost::mutex&#160;</td><td class="memItemRight" valign="bottom"><b>loopLockCounter_</b></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a8c7c6398285b195ac2086745f8b37068"></a><!-- doxytag: member="ompl::geometric::pSBL::loopCounter_" ref="a8c7c6398285b195ac2086745f8b37068" args="" -->
unsigned int&#160;</td><td class="memItemRight" valign="bottom"><b>loopCounter_</b></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a499a0776d3cec0d429a83d234e81eca4"></a><!-- doxytag: member="ompl::geometric::pSBL::maxDistance_" ref="a499a0776d3cec0d429a83d234e81eca4" args="" -->
double&#160;</td><td class="memItemRight" valign="bottom"><b>maxDistance_</b></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a09703d7e75393391e14daa6a6dd71968"></a><!-- doxytag: member="ompl::geometric::pSBL::threadCount_" ref="a09703d7e75393391e14daa6a6dd71968" args="" -->
unsigned int&#160;</td><td class="memItemRight" valign="bottom"><b>threadCount_</b></td></tr>
</table>
<hr/><a name="details" id="details"></a><h2>Detailed Description</h2>
<div class="textblock"><p>Parallel Single-query Bi-directional Lazy collision checking planner. </p>
<p><a class="anchor" id="gpSBL"></a></p>
<dl class="user"><dt><b>Short description</b></dt><dd><a class="el" href="classompl_1_1geometric_1_1SBL.html" title="Single-Query Bi-Directional Probabilistic Roadmap Planner with Lazy Collision Checking.">SBL</a> is a tree-based motion planner that attempts to grow two trees at once: one grows from the starting state and the other from the goal state. The tree expansion strategy is the same as for <a class="el" href="classompl_1_1geometric_1_1EST.html#gEST">EST</a>. Attempts are made to connect these trees at every step of the expansion. If they are connected, a solution path is obtained. However, this solution path is not certain to be valid (the lazy part of the algorithm) so it is checked for validity. If invalid parts are found, they are removed from the tree and exploration of the state space continues until a solution is found. To guide the exploration, an additional grid data structure is maintained. <a class="el" href="classompl_1_1Grid.html" title="Representation of a simple grid.">Grid</a> cells contain states that have been previously visited. When deciding which state to use for further expansion, this grid is used; least-filled grid cells have most chances of being selected. The grid is usually imposed on a projection of the state space. This projection needs to be set before using the planner (<a class="el" href="classompl_1_1geometric_1_1pSBL.html#a8c706561dc3d5256a69f8aff5a6a4dab" title="Set the projection evaluator. This class is able to compute the projection of a given state...">setProjectionEvaluator()</a> function). Connection of states in different trees is attempted if they fall in the same grid cell. If no projection is set, the planner will attempt to use the default projection associated to the state space. An exception is thrown if no default projection is available either.</dd></dl>
<dl class="user"><dt><b>External documentation</b></dt><dd>G. Sánchez and J.-C. Latombe, A single-query bi-directional probabilistic roadmap planner with lazy collision checking, in <em>The Tenth International Symposium on Robotics Research</em>, pp. 403–417, 2001. DOI: <a href="http://dx.doi.org/10.1007/3-540-36460-9_27">10.1007/3-540-36460-9_27</a><br/>
 <a href="http://www.springerlink.com/content/9843341054386hh6/fulltext.pdf">[PDF]</a> </dd></dl>

<p>Definition at line <a class="el" href="pSBL_8h_source.html#l00088">88</a> of file <a class="el" href="pSBL_8h_source.html">pSBL.h</a>.</p>
</div><hr/><h2>Member Function Documentation</h2>
<a class="anchor" id="a684881ad135214cf17dc1d417a921805"></a><!-- doxytag: member="ompl::geometric::pSBL::setRange" ref="a684881ad135214cf17dc1d417a921805" args="(double distance)" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">void ompl::geometric::pSBL::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="pSBL_8h_source.html#l00131">131</a> of file <a class="el" href="pSBL_8h_source.html">pSBL.h</a>.</p>

</div>
</div>
<hr/>The documentation for this class was generated from the following files:<ul>
<li>src/ompl/geometric/planners/sbl/<a class="el" href="pSBL_8h_source.html">pSBL.h</a></li>
<li>src/ompl/geometric/planners/sbl/src/<a class="el" href="pSBL_8cpp_source.html">pSBL.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>