Sophie

Sophie

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

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::base::GoalLazySamples 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_1base.html">base</a>      </li>
      <li class="navelem"><a class="el" href="classompl_1_1base_1_1GoalLazySamples.html">GoalLazySamples</a>      </li>
    </ul>
  </div>
</div>
<div class="header">
  <div class="summary">
<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::base::GoalLazySamples Class Reference</div>  </div>
</div>
<div class="contents">
<!-- doxytag: class="ompl::base::GoalLazySamples" --><!-- doxytag: inherits="ompl::base::GoalStates" -->
<p>Definition of a goal region that can be sampled, but the sampling process can be slow. This class allows sampling the happen in a separate thread, and the number of goals may increase, as the planner is running, in a thread-safe manner.  
 <a href="classompl_1_1base_1_1GoalLazySamples.html#details">More...</a></p>

<p><code>#include &lt;<a class="el" href="GoalLazySamples_8h_source.html">GoalLazySamples.h</a>&gt;</code></p>
<div class="dynheader">
Inheritance diagram for ompl::base::GoalLazySamples:</div>
<div class="dyncontent">
<div class="center"><img src="classompl_1_1base_1_1GoalLazySamples__inherit__graph.png" border="0" usemap="#ompl_1_1base_1_1GoalLazySamples_inherit__map" alt="Inheritance graph"/></div>
<map name="ompl_1_1base_1_1GoalLazySamples_inherit__map" id="ompl_1_1base_1_1GoalLazySamples_inherit__map">
<area shape="rect" id="node2" href="classompl_1_1base_1_1GoalStates.html" title="Definition of a set of goal states." alt="" coords="41,237,199,267"/><area shape="rect" id="node4" href="classompl_1_1base_1_1GoalSampleableRegion.html" title="Abstract definition of a goal region that can be sampled." alt="" coords="5,160,235,189"/><area shape="rect" id="node6" href="classompl_1_1base_1_1GoalRegion.html" title="Definition of a goal region." alt="" coords="39,83,201,112"/><area shape="rect" id="node8" href="classompl_1_1base_1_1Goal.html" title="Abstract definition of goals. Will contain solutions, if found." alt="" coords="60,5,180,35"/></map>
<center><span class="legend">[<a href="graph_legend.html">legend</a>]</span></center></div>

<p><a href="classompl_1_1base_1_1GoalLazySamples-members.html">List of all members.</a></p>
<table class="memberdecls">
<tr><td colspan="2"><h2><a name="pub-methods"></a>
Public Member Functions</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalLazySamples.html#ad296cf0838d99bbd70fdf807432f2e67">GoalLazySamples</a> (const <a class="el" href="classompl_1_1base_1_1SpaceInformationPtr.html">SpaceInformationPtr</a> &amp;si, const <a class="el" href="namespaceompl_1_1base.html#a7ed818b17b8281f0dbb11b666a76aaa7">GoalSamplingFn</a> &amp;samplerFunc, bool autoStart=true, double minDist=std::numeric_limits&lt; double &gt;::epsilon())</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Create a goal region that can be sampled in a lazy fashion. A function that produces samples from that region needs to be passed to this constructor. The sampling thread is automatically started if <em>autoStart</em> is true.  <a href="#ad296cf0838d99bbd70fdf807432f2e67"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a0fb9e9d12bea1de967b6fbc6b6738719"></a><!-- doxytag: member="ompl::base::GoalLazySamples::sampleGoal" ref="a0fb9e9d12bea1de967b6fbc6b6738719" args="(State *st) const " -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalLazySamples.html#a0fb9e9d12bea1de967b6fbc6b6738719">sampleGoal</a> (<a class="el" href="classompl_1_1base_1_1State.html">State</a> *st) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Sample a state in the goal region. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a692bde395578c4fc7e9db960f724832e"></a><!-- doxytag: member="ompl::base::GoalLazySamples::distanceGoal" ref="a692bde395578c4fc7e9db960f724832e" args="(const State *st) const " -->
virtual double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalLazySamples.html#a692bde395578c4fc7e9db960f724832e">distanceGoal</a> (const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *st) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Compute the distance to the goal (heuristic). This function is the one used in computing the distance to the goal in a call to <a class="el" href="classompl_1_1base_1_1GoalRegion.html#a63180f3c2e53eb6feedae905cb858f39" title="Equivalent to calling isSatisfied(const State *, double *) with a NULL second argument.">isSatisfied()</a> <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a11885628f6b06904462165fd9d1fc08b"></a><!-- doxytag: member="ompl::base::GoalLazySamples::addState" ref="a11885628f6b06904462165fd9d1fc08b" args="(const State *st)" -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalLazySamples.html#a11885628f6b06904462165fd9d1fc08b">addState</a> (const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *st)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Add a goal state. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="af3894060ae99b12f00cdcc1ef2c7d0bf"></a><!-- doxytag: member="ompl::base::GoalLazySamples::startSampling" ref="af3894060ae99b12f00cdcc1ef2c7d0bf" args="(void)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalLazySamples.html#af3894060ae99b12f00cdcc1ef2c7d0bf">startSampling</a> (void)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Start the goal sampling thread. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a6581de7182b474a8f2c6ca6129a8ce9d"></a><!-- doxytag: member="ompl::base::GoalLazySamples::stopSampling" ref="a6581de7182b474a8f2c6ca6129a8ce9d" args="(void)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalLazySamples.html#a6581de7182b474a8f2c6ca6129a8ce9d">stopSampling</a> (void)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Stop the goal sampling thread. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ad524231e037fc7ce539ede485e240def"></a><!-- doxytag: member="ompl::base::GoalLazySamples::isSampling" ref="ad524231e037fc7ce539ede485e240def" args="(void) const " -->
bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalLazySamples.html#ad524231e037fc7ce539ede485e240def">isSampling</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Return true if the sampling thread is active. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a5f1ed43b242503b8031996f83d79e4ab"></a><!-- doxytag: member="ompl::base::GoalLazySamples::canSample" ref="a5f1ed43b242503b8031996f83d79e4ab" args="(void) const " -->
virtual bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalLazySamples.html#a5f1ed43b242503b8031996f83d79e4ab">canSample</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Return true of <a class="el" href="classompl_1_1base_1_1GoalSampleableRegion.html#a155c0de80eb09a969d6f3dce2093fdc5" title="Return the maximum number of samples that can be asked for before repeating.">maxSampleCount()</a> &gt; 0 or if the sampling thread is active, as in this case it is possible a sample can be produced. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ae19f97c741f2c0f48c7e3c88b16d432f"></a><!-- doxytag: member="ompl::base::GoalLazySamples::setMinNewSampleDistance" ref="ae19f97c741f2c0f48c7e3c88b16d432f" args="(double dist)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalLazySamples.html#ae19f97c741f2c0f48c7e3c88b16d432f">setMinNewSampleDistance</a> (double dist)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Set the minimum distance that a new state returned by the sampling thread needs to be away from previously added states, so that it is added to the list of goal states. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ae80dbaa527a1d5a234c28b83b392786e"></a><!-- doxytag: member="ompl::base::GoalLazySamples::getMinNewSampleDistance" ref="ae80dbaa527a1d5a234c28b83b392786e" args="(void) const " -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalLazySamples.html#ae80dbaa527a1d5a234c28b83b392786e">getMinNewSampleDistance</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Get the minimum distance that a new state returned by the sampling thread needs to be away from previously added states, so that it is added to the list of goal states. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a408682957039671f0cda9b031770f5c1"></a><!-- doxytag: member="ompl::base::GoalLazySamples::wasLastStateAdded" ref="a408682957039671f0cda9b031770f5c1" args="(void) const " -->
bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalLazySamples.html#a408682957039671f0cda9b031770f5c1">wasLastStateAdded</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Return true if the last state returned by the sampling function was added. Return false otherwise. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="aa7015a082cbebc65f76d57cc7fc8521a"></a><!-- doxytag: member="ompl::base::GoalLazySamples::addStateIfDifferent" ref="aa7015a082cbebc65f76d57cc7fc8521a" args="(const State *st, double minDistance)" -->
bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalLazySamples.html#aa7015a082cbebc65f76d57cc7fc8521a">addStateIfDifferent</a> (const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *st, double minDistance)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Add a state <em>st</em> if it further away that <em>minDistance</em> from previously added states. Return true if the state was added. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ab33e196cd1f63ca75146721ef6f9cdaa"></a><!-- doxytag: member="ompl::base::GoalLazySamples::clear" ref="ab33e196cd1f63ca75146721ef6f9cdaa" args="(void)" -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalLazySamples.html#ab33e196cd1f63ca75146721ef6f9cdaa">clear</a> (void)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Clear all goal states. <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="a787aad32e2abd6586ba29f3d3fd866fc"></a><!-- doxytag: member="ompl::base::GoalLazySamples::goalSamplingThread" ref="a787aad32e2abd6586ba29f3d3fd866fc" args="(void)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalLazySamples.html#a787aad32e2abd6586ba29f3d3fd866fc">goalSamplingThread</a> (void)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The function that samples goals by calling <em>samplerFunc_</em> in a separate thread. <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="a21473de193144c6885ed1de4c9f03354"></a><!-- doxytag: member="ompl::base::GoalLazySamples::lock_" ref="a21473de193144c6885ed1de4c9f03354" args="" -->
boost::mutex&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalLazySamples.html#a21473de193144c6885ed1de4c9f03354">lock_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Lock for updating the set of states. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ad3ce46e7898f2f001fcdd07a23b09987"></a><!-- doxytag: member="ompl::base::GoalLazySamples::samplerFunc_" ref="ad3ce46e7898f2f001fcdd07a23b09987" args="" -->
<a class="el" href="namespaceompl_1_1base.html#a7ed818b17b8281f0dbb11b666a76aaa7">GoalSamplingFn</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalLazySamples.html#ad3ce46e7898f2f001fcdd07a23b09987">samplerFunc_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Function that produces samples. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ac8bfb5596555a8f1ee48c8c75ee93205"></a><!-- doxytag: member="ompl::base::GoalLazySamples::terminateSamplingThread_" ref="ac8bfb5596555a8f1ee48c8c75ee93205" args="" -->
bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalLazySamples.html#ac8bfb5596555a8f1ee48c8c75ee93205">terminateSamplingThread_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Flag used to notify the sampling thread to terminate sampling. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a834ee816753de6f2bbc8e4684c48b4a3"></a><!-- doxytag: member="ompl::base::GoalLazySamples::samplingThread_" ref="a834ee816753de6f2bbc8e4684c48b4a3" args="" -->
boost::thread *&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalLazySamples.html#a834ee816753de6f2bbc8e4684c48b4a3">samplingThread_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Additional thread for sampling goal states. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a3178d4b6de7fde34a163182b98b98238"></a><!-- doxytag: member="ompl::base::GoalLazySamples::lastStateAdded_" ref="a3178d4b6de7fde34a163182b98b98238" args="" -->
bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalLazySamples.html#a3178d4b6de7fde34a163182b98b98238">lastStateAdded_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Flag indicating whether the last state returned by the sampling function was added or not. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a2872e6f726b36c7140d88b81921a5a81"></a><!-- doxytag: member="ompl::base::GoalLazySamples::minDist_" ref="a2872e6f726b36c7140d88b81921a5a81" args="" -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalLazySamples.html#a2872e6f726b36c7140d88b81921a5a81">minDist_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Samples returned by the sampling thread are added to the list of states only if they are at least minDist_ away from already added samples. <br/></td></tr>
</table>
<hr/><a name="details" id="details"></a><h2>Detailed Description</h2>
<div class="textblock"><p>Definition of a goal region that can be sampled, but the sampling process can be slow. This class allows sampling the happen in a separate thread, and the number of goals may increase, as the planner is running, in a thread-safe manner. </p>
<dl class="todo"><dt><b><a class="el" href="todo.html#_todo000001">Todo:</a></b></dt><dd>The Python bindings for <a class="el" href="classompl_1_1base_1_1GoalLazySamples.html" title="Definition of a goal region that can be sampled, but the sampling process can be slow. This class allows sampling the happen in a separate thread, and the number of goals may increase, as the planner is running, in a thread-safe manner.">GoalLazySamples</a> class are still broken. The OMPL C++ code creates a new thread from which you should be able to call a python <a class="el" href="classompl_1_1base_1_1Goal.html" title="Abstract definition of goals. Will contain solutions, if found.">Goal</a> sampling function. Acquiring the right threads and locks and messing around with the Python Global Interpreter Lock (GIL) is very tricky. See ompl/py-bindings/generate_bindings.py for an initial attempt to make this work. </dd></dl>

<p>Definition at line <a class="el" href="GoalLazySamples_8h_source.html#l00071">71</a> of file <a class="el" href="GoalLazySamples_8h_source.html">GoalLazySamples.h</a>.</p>
</div><hr/><h2>Constructor &amp; Destructor Documentation</h2>
<a class="anchor" id="ad296cf0838d99bbd70fdf807432f2e67"></a><!-- doxytag: member="ompl::base::GoalLazySamples::GoalLazySamples" ref="ad296cf0838d99bbd70fdf807432f2e67" args="(const SpaceInformationPtr &amp;si, const GoalSamplingFn &amp;samplerFunc, bool autoStart=true, double minDist=std::numeric_limits&lt; double &gt;::epsilon())" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">ompl::base::GoalLazySamples::GoalLazySamples </td>
          <td>(</td>
          <td class="paramtype">const <a class="el" href="classompl_1_1base_1_1SpaceInformationPtr.html">SpaceInformationPtr</a> &amp;&#160;</td>
          <td class="paramname"><em>si</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">const <a class="el" href="namespaceompl_1_1base.html#a7ed818b17b8281f0dbb11b666a76aaa7">GoalSamplingFn</a> &amp;&#160;</td>
          <td class="paramname"><em>samplerFunc</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">bool&#160;</td>
          <td class="paramname"><em>autoStart</em> = <code>true</code>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">double&#160;</td>
          <td class="paramname"><em>minDist</em> = <code>std::numeric_limits&lt;double&gt;::epsilon()</code>&#160;</td>
        </tr>
        <tr>
          <td></td>
          <td>)</td>
          <td></td><td></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Create a goal region that can be sampled in a lazy fashion. A function that produces samples from that region needs to be passed to this constructor. The sampling thread is automatically started if <em>autoStart</em> is true. </p>
<p>The function <em>samplerFunc</em> returns a truth value. If the return value is true, further calls to the function can be made. If the return is false, no more calls should be made. The function takes two arguments: the instance of <a class="el" href="classompl_1_1base_1_1GoalLazySamples.html" title="Definition of a goal region that can be sampled, but the sampling process can be slow. This class allows sampling the happen in a separate thread, and the number of goals may increase, as the planner is running, in a thread-safe manner.">GoalLazySamples</a> making the call and the state to fill with a goal state. For every state filled in by <em>samplerFunc</em>, <a class="el" href="classompl_1_1base_1_1GoalLazySamples.html#aa7015a082cbebc65f76d57cc7fc8521a" title="Add a state st if it further away that minDistance from previously added states. Return true if the s...">addStateIfDifferent()</a> is called. A state computed by the sampling thread is added if it is "sufficiently
                different" from previously added states. A state is considered "sufficiently different" if it is at least <em>minDist</em> away from previously added states. </p>

<p>Definition at line <a class="el" href="GoalLazySamples_8cpp_source.html#l00041">41</a> of file <a class="el" href="GoalLazySamples_8cpp_source.html">GoalLazySamples.cpp</a>.</p>

</div>
</div>
<hr/>The documentation for this class was generated from the following files:<ul>
<li>src/ompl/base/<a class="el" href="GoalLazySamples_8h_source.html">GoalLazySamples.h</a></li>
<li>src/ompl/base/src/<a class="el" href="GoalLazySamples_8cpp_source.html">GoalLazySamples.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:42 by&#160;<a href="http://www.doxygen.org/index.html">doxygen</a> 1.7.4</div>
</div>
</div>
</body>
</html>