Sophie

Sophie

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

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::BKPIECE1 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_1BKPIECE1.html">BKPIECE1</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-attribs">Protected Attributes</a>  </div>
  <div class="headertitle">
<div class="title">ompl::geometric::BKPIECE1 Class Reference</div>  </div>
</div>
<div class="contents">
<!-- doxytag: class="ompl::geometric::BKPIECE1" --><!-- doxytag: inherits="ompl::base::Planner" -->
<p>Bi-directional KPIECE with one level of discretization.  
 <a href="classompl_1_1geometric_1_1BKPIECE1.html#details">More...</a></p>

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

<p><a href="classompl_1_1geometric_1_1BKPIECE1-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_1BKPIECE1_1_1Motion.html">Motion</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Representation of a motion for this algorithm.  <a href="classompl_1_1geometric_1_1BKPIECE1_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="a1e61534ba2f912016e00d94cfc5449e5"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::BKPIECE1" ref="a1e61534ba2f912016e00d94cfc5449e5" args="(const base::SpaceInformationPtr &amp;si)" -->
&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BKPIECE1.html#a1e61534ba2f912016e00d94cfc5449e5">BKPIECE1</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="a0e505ace63ee03e5ccde6e9820aeabdb"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::setProjectionEvaluator" ref="a0e505ace63ee03e5ccde6e9820aeabdb" args="(const base::ProjectionEvaluatorPtr &amp;projectionEvaluator)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BKPIECE1.html#a0e505ace63ee03e5ccde6e9820aeabdb">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="a0dbd0c85fa51f8ebce39a0ddc18517d8"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::setProjectionEvaluator" ref="a0dbd0c85fa51f8ebce39a0ddc18517d8" args="(const std::string &amp;name)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BKPIECE1.html#a0dbd0c85fa51f8ebce39a0ddc18517d8">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="aa47204082c17945322327fbbccb8d9eb"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::getProjectionEvaluator" ref="aa47204082c17945322327fbbccb8d9eb" 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_1BKPIECE1.html#aa47204082c17945322327fbbccb8d9eb">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_1BKPIECE1.html#ab803b4859de12fd5788e87b99c672679">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="#ab803b4859de12fd5788e87b99c672679"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a00df8bda844faf9cf0d37c3cceb86ff8"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::getRange" ref="a00df8bda844faf9cf0d37c3cceb86ff8" args="(void) const " -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BKPIECE1.html#a00df8bda844faf9cf0d37c3cceb86ff8">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="a57e4e557bbd43543c4fe5d5d3733b443"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::setBorderFraction" ref="a57e4e557bbd43543c4fe5d5d3733b443" args="(double bp)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BKPIECE1.html#a57e4e557bbd43543c4fe5d5d3733b443">setBorderFraction</a> (double bp)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Set the fraction of time for focusing on the border (between 0 and 1). This is the minimum fraction used to select cells that are exterior (minimum because if 95% of cells are on the border, they will be selected with 95% chance, even if this fraction is set to 90%) <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a8ff03b3a78056009bb8c33eea8fdc03b"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::getBorderFraction" ref="a8ff03b3a78056009bb8c33eea8fdc03b" args="(void) const " -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BKPIECE1.html#a8ff03b3a78056009bb8c33eea8fdc03b">getBorderFraction</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Get the fraction of time to focus exploration on boundary. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a0815c456908ed60997364dc38ae30b6a"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::setCellScoreFactor" ref="a0815c456908ed60997364dc38ae30b6a" args="(double good, double bad)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BKPIECE1.html#a0815c456908ed60997364dc38ae30b6a">setCellScoreFactor</a> (double good, double bad)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">When extending a motion from a cell, the extension can be successful or it can fail. If the extension is successful, the score of the cell is multiplied by <em>good</em>. If the extension fails, the score of the cell is multiplied by <em>bad</em>. These numbers should be in the range (0, 1]. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="afeb0b2d18996a411de88f7177e999375"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::getGoodCellScoreFactor" ref="afeb0b2d18996a411de88f7177e999375" args="(void) const " -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BKPIECE1.html#afeb0b2d18996a411de88f7177e999375">getGoodCellScoreFactor</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Get the factor that is multiplied to a cell's score if extending a motion from that cell succeeded. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ae771df27dd0652c868e65cc8938eb9d7"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::getBadCellScoreFactor" ref="ae771df27dd0652c868e65cc8938eb9d7" args="(void) const " -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BKPIECE1.html#ae771df27dd0652c868e65cc8938eb9d7">getBadCellScoreFactor</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Get the factor that is multiplied to a cell's score if extending a motion from that cell failed. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a1cc89cb07e13a333f6eed645a3dfcda3"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::setMinValidPathFraction" ref="a1cc89cb07e13a333f6eed645a3dfcda3" args="(double fraction)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BKPIECE1.html#a1cc89cb07e13a333f6eed645a3dfcda3">setMinValidPathFraction</a> (double fraction)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">When extending a motion, the planner can decide to keep the first valid part of it, even if invalid states are found, as long as the valid part represents a sufficiently large fraction from the original motion. This function sets the minimum acceptable fraction. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a5408b9c364367bd9374804c6292bff44"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::getMinValidPathFraction" ref="a5408b9c364367bd9374804c6292bff44" args="(void) const " -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BKPIECE1.html#a5408b9c364367bd9374804c6292bff44">getMinValidPathFraction</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Get the value of the fraction set by <a class="el" href="classompl_1_1geometric_1_1BKPIECE1.html#a1cc89cb07e13a333f6eed645a3dfcda3" title="When extending a motion, the planner can decide to keep the first valid part of it, even if invalid states are found, as long as the valid part represents a sufficiently large fraction from the original motion. This function sets the minimum acceptable fraction.">setMinValidPathFraction()</a> <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a65a7fce6f697fa96ffaf93126f2796f6"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::setup" ref="a65a7fce6f697fa96ffaf93126f2796f6" args="(void)" -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BKPIECE1.html#a65a7fce6f697fa96ffaf93126f2796f6">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="a41192852cfc32f0db883e18cb8dee94a"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::solve" ref="a41192852cfc32f0db883e18cb8dee94a" args="(const base::PlannerTerminationCondition &amp;ptc)" -->
virtual bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BKPIECE1.html#a41192852cfc32f0db883e18cb8dee94a">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_1BKPIECE1.html#a4f5bb7c1cbd59e657650a9c4211b989a" 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="a4f5bb7c1cbd59e657650a9c4211b989a"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::clear" ref="a4f5bb7c1cbd59e657650a9c4211b989a" args="(void)" -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BKPIECE1.html#a4f5bb7c1cbd59e657650a9c4211b989a">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_1BKPIECE1.html#a41192852cfc32f0db883e18cb8dee94a" 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="a1e43aa6d5965a85004951302954de5d5"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::getPlannerData" ref="a1e43aa6d5965a85004951302954de5d5" args="(base::PlannerData &amp;data) const " -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BKPIECE1.html#a1e43aa6d5965a85004951302954de5d5">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_1BKPIECE1.html#a41192852cfc32f0db883e18cb8dee94a" 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_1BKPIECE1.html#a4f5bb7c1cbd59e657650a9c4211b989a" 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-methods"></a>
Protected Member Functions</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ae81ac9338565790508efaebbef3d8459"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::freeMotion" ref="ae81ac9338565790508efaebbef3d8459" args="(Motion *motion)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BKPIECE1.html#ae81ac9338565790508efaebbef3d8459">freeMotion</a> (<a class="el" href="classompl_1_1geometric_1_1BKPIECE1_1_1Motion.html">Motion</a> *motion)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Free the memory for a motion. <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="a88a3a9f2986351a001955070e7d22046"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::sampler_" ref="a88a3a9f2986351a001955070e7d22046" args="" -->
<a class="el" href="classompl_1_1base_1_1ValidStateSamplerPtr.html">base::ValidStateSamplerPtr</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BKPIECE1.html#a88a3a9f2986351a001955070e7d22046">sampler_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The employed state sampler. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ac4b29de63c1a79e5ab2b819b182e230f"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::projectionEvaluator_" ref="ac4b29de63c1a79e5ab2b819b182e230f" args="" -->
<a class="el" href="classompl_1_1base_1_1ProjectionEvaluatorPtr.html">base::ProjectionEvaluatorPtr</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BKPIECE1.html#ac4b29de63c1a79e5ab2b819b182e230f">projectionEvaluator_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The employed projection evaluator. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="aa70b018d82b7bf967b7ed5ade3c51a81"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::dStart_" ref="aa70b018d82b7bf967b7ed5ade3c51a81" args="" -->
<a class="el" href="classompl_1_1geometric_1_1Discretization.html">Discretization</a>&lt; <a class="el" href="classompl_1_1geometric_1_1BKPIECE1_1_1Motion.html">Motion</a> &gt;&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BKPIECE1.html#aa70b018d82b7bf967b7ed5ade3c51a81">dStart_</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="a6083e1178d64a2064b8403a6e4d7f5be"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::dGoal_" ref="a6083e1178d64a2064b8403a6e4d7f5be" args="" -->
<a class="el" href="classompl_1_1geometric_1_1Discretization.html">Discretization</a>&lt; <a class="el" href="classompl_1_1geometric_1_1BKPIECE1_1_1Motion.html">Motion</a> &gt;&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BKPIECE1.html#a6083e1178d64a2064b8403a6e4d7f5be">dGoal_</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="af37f1c448a18b763debbb7c146abbcb1"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::goodScoreFactor_" ref="af37f1c448a18b763debbb7c146abbcb1" args="" -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BKPIECE1.html#af37f1c448a18b763debbb7c146abbcb1">goodScoreFactor_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">When extending a motion from a cell, the extension can be successful. If it is, the score of the cell is multiplied by this factor. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a5f67febd07173b94f73337009b23f08e"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::badScoreFactor_" ref="a5f67febd07173b94f73337009b23f08e" args="" -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BKPIECE1.html#a5f67febd07173b94f73337009b23f08e">badScoreFactor_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">When extending a motion from a cell, the extension can fail. If it is, the score of the cell is multiplied by this factor. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="aa0962644ccc8c2cf71dd42ca0bac3ff3"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::minValidPathFraction_" ref="aa0962644ccc8c2cf71dd42ca0bac3ff3" args="" -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BKPIECE1.html#aa0962644ccc8c2cf71dd42ca0bac3ff3">minValidPathFraction_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">When extending a motion, the planner can decide to keep the first valid part of it, even if invalid states are found, as long as the valid part represents a sufficiently large fraction from the original motion. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a15a290a36bac34264d12f0ca3c3dc46d"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::maxDistance_" ref="a15a290a36bac34264d12f0ca3c3dc46d" args="" -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1geometric_1_1BKPIECE1.html#a15a290a36bac34264d12f0ca3c3dc46d">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="a422ff4aa4fe25dd13e40e8c9962ccc12"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::rng_" ref="a422ff4aa4fe25dd13e40e8c9962ccc12" 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_1BKPIECE1.html#a422ff4aa4fe25dd13e40e8c9962ccc12">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>Bi-directional KPIECE with one level of discretization. </p>
<p><a class="anchor" id="gBKPIECE1"></a></p>
<dl class="user"><dt><b>Short description</b></dt><dd>KPIECE is a tree-based planner that uses a discretization (multiple levels, in general) to guide the exploration of the continuous space. This implementation is a simplified one, using a single level of discretization: one grid. The grid is imposed on a projection of the state space. When exploring the space, preference is given to the boundary of this grid. The boundary is computed to be the set of grid cells that have less than 2n non-diagonal neighbors in an n-dimensional projection space. It is important to set the projection the algorithm uses (<a class="el" href="classompl_1_1geometric_1_1BKPIECE1.html#a0e505ace63ee03e5ccde6e9820aeabdb" title="Set the projection evaluator. This class is able to compute the projection of a given state...">setProjectionEvaluator()</a> function). 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. This variant of the implementation use two trees of exploration, hence the B prefix.</dd></dl>
<dl class="user"><dt><b>External documentation</b></dt><dd><ul>
<li>I.A. Şucan and L.E. Kavraki, Kinodynamic motion planning by interior-exterior cell exploration, in <em>Workshop on the Algorithmic Foundations of Robotics</em>, Dec. 2008.<br/>
 <a href="http://ioan.sucan.ro/files/pubs/wafr2008.pdf">[PDF]</a></li>
<li>R. Bohlin and L.E. Kavraki, Path planning using lazy <a class="el" href="classompl_1_1geometric_1_1PRM.html" title="Probabilistic RoadMap planner.">PRM</a>, in <em>Proc. 2000 IEEE Intl. Conf. on Robotics and Automation</em>, pp. 521–528, 2000. DOI: <a href="http://dx.doi.org/10.1109/ROBOT.2000.844107">10.1109/ROBOT.2000.844107</a><br/>
 <a href="http://ieeexplore.ieee.org/ielx5/6794/18235/00844107.pdf?tp=&amp;arnumber=844107&amp;isnumber=18235">[PDF] </a></li>
</ul>
</dd></dl>

<p>Definition at line <a class="el" href="BKPIECE1_8h_source.html#l00080">80</a> of file <a class="el" href="BKPIECE1_8h_source.html">BKPIECE1.h</a>.</p>
</div><hr/><h2>Member Function Documentation</h2>
<a class="anchor" id="ab803b4859de12fd5788e87b99c672679"></a><!-- doxytag: member="ompl::geometric::BKPIECE1::setRange" ref="ab803b4859de12fd5788e87b99c672679" args="(double distance)" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">void ompl::geometric::BKPIECE1::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="BKPIECE1_8h_source.html#l00126">126</a> of file <a class="el" href="BKPIECE1_8h_source.html">BKPIECE1.h</a>.</p>

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