Sophie

Sophie

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

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

<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta http-equiv="Content-Type" content="text/xhtml; charset=UTF-8"/>
<title>OMPL: src/ompl/geometric/planners/sbl/src/SBL.cpp Source File</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="dir_f5421e52a658cd938113ed6044324834.html">src</a>      </li>
      <li class="navelem"><a class="el" href="dir_ae92c2ff78847f0cb49b545f9089bbbc.html">ompl</a>      </li>
      <li class="navelem"><a class="el" href="dir_09c87af92e12dad9ad42621ff12ca21c.html">geometric</a>      </li>
      <li class="navelem"><a class="el" href="dir_ea5fd944e8f903b1c975832ff4982cc4.html">planners</a>      </li>
      <li class="navelem"><a class="el" href="dir_a1033c165fa060888fc80b6dfdd919f4.html">sbl</a>      </li>
      <li class="navelem"><a class="el" href="dir_62da1012418a085f1d06cd336d22f78d.html">src</a>      </li>
    </ul>
  </div>
</div>
<div class="header">
  <div class="headertitle">
<div class="title">SBL.cpp</div>  </div>
</div>
<div class="contents">
<div class="fragment"><pre class="fragment"><a name="l00001"></a>00001 <span class="comment">/*********************************************************************</span>
<a name="l00002"></a>00002 <span class="comment">* Software License Agreement (BSD License)</span>
<a name="l00003"></a>00003 <span class="comment">*</span>
<a name="l00004"></a>00004 <span class="comment">*  Copyright (c) 2008, Willow Garage, Inc.</span>
<a name="l00005"></a>00005 <span class="comment">*  All rights reserved.</span>
<a name="l00006"></a>00006 <span class="comment">*</span>
<a name="l00007"></a>00007 <span class="comment">*  Redistribution and use in source and binary forms, with or without</span>
<a name="l00008"></a>00008 <span class="comment">*  modification, are permitted provided that the following conditions</span>
<a name="l00009"></a>00009 <span class="comment">*  are met:</span>
<a name="l00010"></a>00010 <span class="comment">*</span>
<a name="l00011"></a>00011 <span class="comment">*   * Redistributions of source code must retain the above copyright</span>
<a name="l00012"></a>00012 <span class="comment">*     notice, this list of conditions and the following disclaimer.</span>
<a name="l00013"></a>00013 <span class="comment">*   * Redistributions in binary form must reproduce the above</span>
<a name="l00014"></a>00014 <span class="comment">*     copyright notice, this list of conditions and the following</span>
<a name="l00015"></a>00015 <span class="comment">*     disclaimer in the documentation and/or other materials provided</span>
<a name="l00016"></a>00016 <span class="comment">*     with the distribution.</span>
<a name="l00017"></a>00017 <span class="comment">*   * Neither the name of the Willow Garage nor the names of its</span>
<a name="l00018"></a>00018 <span class="comment">*     contributors may be used to endorse or promote products derived</span>
<a name="l00019"></a>00019 <span class="comment">*     from this software without specific prior written permission.</span>
<a name="l00020"></a>00020 <span class="comment">*</span>
<a name="l00021"></a>00021 <span class="comment">*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS</span>
<a name="l00022"></a>00022 <span class="comment">*  &quot;AS IS&quot; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT</span>
<a name="l00023"></a>00023 <span class="comment">*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS</span>
<a name="l00024"></a>00024 <span class="comment">*  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE</span>
<a name="l00025"></a>00025 <span class="comment">*  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,</span>
<a name="l00026"></a>00026 <span class="comment">*  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,</span>
<a name="l00027"></a>00027 <span class="comment">*  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;</span>
<a name="l00028"></a>00028 <span class="comment">*  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER</span>
<a name="l00029"></a>00029 <span class="comment">*  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT</span>
<a name="l00030"></a>00030 <span class="comment">*  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN</span>
<a name="l00031"></a>00031 <span class="comment">*  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE</span>
<a name="l00032"></a>00032 <span class="comment">*  POSSIBILITY OF SUCH DAMAGE.</span>
<a name="l00033"></a>00033 <span class="comment">*********************************************************************/</span>
<a name="l00034"></a>00034 
<a name="l00035"></a>00035 <span class="comment">/* Author: Ioan Sucan */</span>
<a name="l00036"></a>00036 
<a name="l00037"></a>00037 <span class="preprocessor">#include &quot;ompl/geometric/planners/sbl/SBL.h&quot;</span>
<a name="l00038"></a>00038 <span class="preprocessor">#include &quot;ompl/base/GoalSampleableRegion.h&quot;</span>
<a name="l00039"></a>00039 <span class="preprocessor">#include &quot;ompl/tools/config/SelfConfig.h&quot;</span>
<a name="l00040"></a>00040 <span class="preprocessor">#include &lt;limits&gt;</span>
<a name="l00041"></a>00041 <span class="preprocessor">#include &lt;cassert&gt;</span>
<a name="l00042"></a>00042 
<a name="l00043"></a><a class="code" href="classompl_1_1geometric_1_1SBL.html#aa49720ab997e4b14d2eb8afc4b4c3341">00043</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1SBL.html#aa49720ab997e4b14d2eb8afc4b4c3341" title="Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...">ompl::geometric::SBL::setup</a>(<span class="keywordtype">void</span>)
<a name="l00044"></a>00044 {
<a name="l00045"></a>00045     <a class="code" href="classompl_1_1geometric_1_1SBL.html#aa49720ab997e4b14d2eb8afc4b4c3341" title="Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...">Planner::setup</a>();
<a name="l00046"></a>00046     <a class="code" href="classompl_1_1SelfConfig.html" title="This class contains methods that automatically configure various parameters for motion planning...">SelfConfig</a> sc(<a class="code" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e" title="The space information for which planning is done.">si_</a>, <a class="code" href="classompl_1_1base_1_1Planner.html#a79bac96f3b6f6e07c24f4b407054f8a3" title="Get the name of the planner.">getName</a>());
<a name="l00047"></a>00047     sc.<a class="code" href="classompl_1_1SelfConfig.html#ad2b1dc5899d8fab0744bacab31bc1661" title="If proj is undefined, it is set to the default projection reported by base::StateSpace::getDefaultPro...">configureProjectionEvaluator</a>(<a class="code" href="classompl_1_1geometric_1_1SBL.html#a63cfcb2e97c2a1904202ccc81569958c" title="The employed projection evaluator.">projectionEvaluator_</a>);
<a name="l00048"></a>00048     sc.<a class="code" href="classompl_1_1SelfConfig.html#a86d0c4b1dc9a9a25bd53a6820a6b973c" title="Compute what a good length for motion segments is.">configurePlannerRange</a>(<a class="code" href="classompl_1_1geometric_1_1SBL.html#afd6d54cc164f50d105aa615a2052daa6" title="The maximum length of a motion to be added in the tree.">maxDistance_</a>);
<a name="l00049"></a>00049 
<a name="l00050"></a>00050     <a class="code" href="classompl_1_1geometric_1_1SBL.html#a33a1bf5cb144b453e4b69855e19f3d18" title="The start tree.">tStart_</a>.<a class="code" href="structompl_1_1geometric_1_1SBL_1_1TreeData.html#a06d446c1f27927f0155ecaff80520d7e" title="The grid of motions corresponding to this tree.">grid</a>.<a class="code" href="classompl_1_1Grid.html#a118373bcfe70886449d94782b0a7c783">setDimension</a>(<a class="code" href="classompl_1_1geometric_1_1SBL.html#a63cfcb2e97c2a1904202ccc81569958c" title="The employed projection evaluator.">projectionEvaluator_</a>-&gt;getDimension());
<a name="l00051"></a>00051     <a class="code" href="classompl_1_1geometric_1_1SBL.html#ad917d94e5877b0a1f65c861e73329c58" title="The goal tree.">tGoal_</a>.<a class="code" href="structompl_1_1geometric_1_1SBL_1_1TreeData.html#a06d446c1f27927f0155ecaff80520d7e" title="The grid of motions corresponding to this tree.">grid</a>.<a class="code" href="classompl_1_1Grid.html#a118373bcfe70886449d94782b0a7c783">setDimension</a>(<a class="code" href="classompl_1_1geometric_1_1SBL.html#a63cfcb2e97c2a1904202ccc81569958c" title="The employed projection evaluator.">projectionEvaluator_</a>-&gt;getDimension());
<a name="l00052"></a>00052 }
<a name="l00053"></a>00053 
<a name="l00054"></a><a class="code" href="classompl_1_1geometric_1_1SBL.html#afcf4e0a17d9ac8fe70e296213aac32bd">00054</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1SBL.html#afcf4e0a17d9ac8fe70e296213aac32bd" title="Free the memory used by the motions contained in a grid.">ompl::geometric::SBL::freeGridMotions</a>(<a class="code" href="classompl_1_1Grid.html">Grid&lt;MotionSet&gt;</a> &amp;grid)
<a name="l00055"></a>00055 {
<a name="l00056"></a>00056     <span class="keywordflow">for</span> (<a class="code" href="classompl_1_1Grid.html" title="Representation of a simple grid.">Grid&lt;MotionSet&gt;::iterator</a> it = grid.<a class="code" href="classompl_1_1Grid.html#ad74c5df97cf3d54a1a15eff55596973c" title="Return the begin() iterator for the grid.">begin</a>(); it != grid.<a class="code" href="classompl_1_1Grid.html#ac5d360c8fa02bd6ec58aa8cbbc450dd7" title="Return the end() iterator for the grid.">end</a>() ; ++it)
<a name="l00057"></a>00057     {
<a name="l00058"></a>00058         <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i &lt; it-&gt;second-&gt;data.size() ; ++i)
<a name="l00059"></a>00059         {
<a name="l00060"></a>00060             <span class="keywordflow">if</span> (it-&gt;second-&gt;data[i]-&gt;state)
<a name="l00061"></a>00061                 si_-&gt;freeState(it-&gt;second-&gt;data[i]-&gt;state);
<a name="l00062"></a>00062             <span class="keyword">delete</span> it-&gt;second-&gt;data[i];
<a name="l00063"></a>00063         }
<a name="l00064"></a>00064     }
<a name="l00065"></a>00065 }
<a name="l00066"></a>00066 
<a name="l00067"></a><a class="code" href="classompl_1_1geometric_1_1SBL.html#a189047f6ea684c283b12d1365249e9f2">00067</a> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1geometric_1_1SBL.html#a189047f6ea684c283b12d1365249e9f2" title="Function that can solve the motion planning problem. This function can be called multiple times on th...">ompl::geometric::SBL::solve</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1PlannerTerminationCondition.html" title="Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...">base::PlannerTerminationCondition</a> &amp;ptc)
<a name="l00068"></a>00068 {
<a name="l00069"></a>00069     checkValidity();
<a name="l00070"></a>00070     <a class="code" href="classompl_1_1base_1_1GoalSampleableRegion.html" title="Abstract definition of a goal region that can be sampled.">base::GoalSampleableRegion</a> *goal = <span class="keyword">dynamic_cast&lt;</span><a class="code" href="classompl_1_1base_1_1GoalSampleableRegion.html" title="Abstract definition of a goal region that can be sampled.">base::GoalSampleableRegion</a>*<span class="keyword">&gt;</span>(pdef_-&gt;getGoal().get());
<a name="l00071"></a>00071 
<a name="l00072"></a>00072     <span class="keywordflow">if</span> (!goal)
<a name="l00073"></a>00073     {
<a name="l00074"></a>00074         msg_.error(<span class="stringliteral">&quot;Unknown type of goal (or goal undefined)&quot;</span>);
<a name="l00075"></a>00075         <span class="keywordflow">return</span> <span class="keyword">false</span>;
<a name="l00076"></a>00076     }
<a name="l00077"></a>00077 
<a name="l00078"></a>00078     <span class="keywordflow">while</span> (<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">base::State</a> *st = pis_.nextStart())
<a name="l00079"></a>00079     {
<a name="l00080"></a>00080         <a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html" title="Representation of a motion.">Motion</a> *motion = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html" title="Representation of a motion.">Motion</a>(si_);
<a name="l00081"></a>00081         si_-&gt;copyState(motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a1961e2628ac13bd2946f32a0df0e0644" title="The state this motion leads to.">state</a>, st);
<a name="l00082"></a>00082         motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#af10d75ce5c240a98e1ccf1daa34e3d26" title="Flag indicating whether this motion has been checked for validity.">valid</a> = <span class="keyword">true</span>;
<a name="l00083"></a>00083         motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#ab4c75449dee78c54accf15a27e45a138" title="The root of the tree this motion would get to, if we were to follow parent pointers.">root</a> = motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a1961e2628ac13bd2946f32a0df0e0644" title="The state this motion leads to.">state</a>;
<a name="l00084"></a>00084         addMotion(tStart_, motion);
<a name="l00085"></a>00085     }
<a name="l00086"></a>00086 
<a name="l00087"></a>00087     <span class="keywordflow">if</span> (tStart_.size == 0)
<a name="l00088"></a>00088     {
<a name="l00089"></a>00089         msg_.error(<span class="stringliteral">&quot;Motion planning start tree could not be initialized!&quot;</span>);
<a name="l00090"></a>00090         <span class="keywordflow">return</span> <span class="keyword">false</span>;
<a name="l00091"></a>00091     }
<a name="l00092"></a>00092 
<a name="l00093"></a>00093     <span class="keywordflow">if</span> (!goal-&gt;<a class="code" href="classompl_1_1base_1_1GoalSampleableRegion.html#a60329b89ea7217a7550197e5866c28c7" title="Return true of maxSampleCount() &gt; 0, since in this case samples can certainly be produced.">canSample</a>())
<a name="l00094"></a>00094     {
<a name="l00095"></a>00095         msg_.error(<span class="stringliteral">&quot;Insufficient states in sampleable goal region&quot;</span>);
<a name="l00096"></a>00096         <span class="keywordflow">return</span> <span class="keyword">false</span>;
<a name="l00097"></a>00097     }
<a name="l00098"></a>00098 
<a name="l00099"></a>00099     <span class="keywordflow">if</span> (!sampler_)
<a name="l00100"></a>00100         sampler_ = si_-&gt;allocValidStateSampler();
<a name="l00101"></a>00101 
<a name="l00102"></a>00102     msg_.inform(<span class="stringliteral">&quot;Starting with %d states&quot;</span>, (<span class="keywordtype">int</span>)(tStart_.size + tGoal_.size));
<a name="l00103"></a>00103 
<a name="l00104"></a>00104     std::vector&lt;Motion*&gt; solution;
<a name="l00105"></a>00105     <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">base::State</a> *xstate = si_-&gt;allocState();
<a name="l00106"></a>00106 
<a name="l00107"></a>00107     <span class="keywordtype">bool</span>      startTree = <span class="keyword">true</span>;
<a name="l00108"></a>00108 
<a name="l00109"></a>00109     <span class="keywordflow">while</span> (ptc() == <span class="keyword">false</span>)
<a name="l00110"></a>00110     {
<a name="l00111"></a>00111         <a class="code" href="structompl_1_1geometric_1_1SBL_1_1TreeData.html" title="Representation of a search tree. Two instances will be used. One for start and one for goal...">TreeData</a> &amp;tree      = startTree ? tStart_ : tGoal_;
<a name="l00112"></a>00112         startTree = !startTree;
<a name="l00113"></a>00113         <a class="code" href="structompl_1_1geometric_1_1SBL_1_1TreeData.html" title="Representation of a search tree. Two instances will be used. One for start and one for goal...">TreeData</a> &amp;otherTree = startTree ? tStart_ : tGoal_;
<a name="l00114"></a>00114 
<a name="l00115"></a>00115         <span class="comment">// if we have not sampled too many goals already</span>
<a name="l00116"></a>00116         <span class="keywordflow">if</span> (tGoal_.size == 0 || pis_.getSampledGoalsCount() &lt; tGoal_.size / 2)
<a name="l00117"></a>00117         {
<a name="l00118"></a>00118             <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">base::State</a> *st = tGoal_.size == 0 ? pis_.nextGoal(ptc) : pis_.nextGoal();
<a name="l00119"></a>00119             <span class="keywordflow">if</span> (st)
<a name="l00120"></a>00120             {
<a name="l00121"></a>00121                 <a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html" title="Representation of a motion.">Motion</a>* motion = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html" title="Representation of a motion.">Motion</a>(si_);
<a name="l00122"></a>00122                 si_-&gt;copyState(motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a1961e2628ac13bd2946f32a0df0e0644" title="The state this motion leads to.">state</a>, st);
<a name="l00123"></a>00123                 motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#ab4c75449dee78c54accf15a27e45a138" title="The root of the tree this motion would get to, if we were to follow parent pointers.">root</a> = motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a1961e2628ac13bd2946f32a0df0e0644" title="The state this motion leads to.">state</a>;
<a name="l00124"></a>00124                 motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#af10d75ce5c240a98e1ccf1daa34e3d26" title="Flag indicating whether this motion has been checked for validity.">valid</a> = <span class="keyword">true</span>;
<a name="l00125"></a>00125                 addMotion(tGoal_, motion);
<a name="l00126"></a>00126             }
<a name="l00127"></a>00127             <span class="keywordflow">if</span> (tGoal_.size == 0)
<a name="l00128"></a>00128             {
<a name="l00129"></a>00129                 msg_.error(<span class="stringliteral">&quot;Unable to sample any valid states for goal tree&quot;</span>);
<a name="l00130"></a>00130                 <span class="keywordflow">break</span>;
<a name="l00131"></a>00131             }
<a name="l00132"></a>00132         }
<a name="l00133"></a>00133 
<a name="l00134"></a>00134         <a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html" title="Representation of a motion.">Motion</a> *existing = selectMotion(tree);
<a name="l00135"></a>00135         assert(existing);
<a name="l00136"></a>00136         <span class="keywordflow">if</span> (!sampler_-&gt;sampleNear(xstate, existing-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a1961e2628ac13bd2946f32a0df0e0644" title="The state this motion leads to.">state</a>, maxDistance_))
<a name="l00137"></a>00137             <span class="keywordflow">continue</span>;
<a name="l00138"></a>00138 
<a name="l00139"></a>00139         <span class="comment">/* create a motion */</span>
<a name="l00140"></a>00140         <a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html" title="Representation of a motion.">Motion</a> *motion = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html" title="Representation of a motion.">Motion</a>(si_);
<a name="l00141"></a>00141         si_-&gt;copyState(motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a1961e2628ac13bd2946f32a0df0e0644" title="The state this motion leads to.">state</a>, xstate);
<a name="l00142"></a>00142         motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a6909be2bcc8fc942027be974fc583035" title="The parent motion -- it contains the state this motion originates at.">parent</a> = existing;
<a name="l00143"></a>00143         motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#ab4c75449dee78c54accf15a27e45a138" title="The root of the tree this motion would get to, if we were to follow parent pointers.">root</a> = existing-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#ab4c75449dee78c54accf15a27e45a138" title="The root of the tree this motion would get to, if we were to follow parent pointers.">root</a>;
<a name="l00144"></a>00144         existing-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a7fb9efdcee594786f85fba6acd6a8fdd" title="The set of motions descending from the current motion.">children</a>.push_back(motion);
<a name="l00145"></a>00145 
<a name="l00146"></a>00146         addMotion(tree, motion);
<a name="l00147"></a>00147 
<a name="l00148"></a>00148         <span class="keywordflow">if</span> (checkSolution(!startTree, tree, otherTree, motion, solution))
<a name="l00149"></a>00149         {
<a name="l00150"></a>00150             <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html" title="Definition of a geometric path.">PathGeometric</a> *path = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html" title="Definition of a geometric path.">PathGeometric</a>(si_);
<a name="l00151"></a>00151             <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i &lt; solution.size() ; ++i)
<a name="l00152"></a>00152                 path-&gt;<a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a3a729dab22338b733888bc2f9c9769a4" title="The list of states that make up the path.">states</a>.push_back(si_-&gt;cloneState(solution[i]-&gt;state));
<a name="l00153"></a>00153 
<a name="l00154"></a>00154             goal-&gt;<a class="code" href="classompl_1_1base_1_1Goal.html#afbfc02ebac97049ebdd28d040ce44c37" title="Set the difference between the found solution path and the desired solution path.">setDifference</a>(0.0);
<a name="l00155"></a>00155             goal-&gt;<a class="code" href="classompl_1_1base_1_1Goal.html#ade528c0fefb9094abc1a2d1518a5f860" title="Update the solution path. If a previous solution path exists, it is deleted.">setSolutionPath</a>(<a class="code" href="classompl_1_1base_1_1PathPtr.html" title="A boost shared pointer wrapper for ompl::base::Path.">base::PathPtr</a>(path));
<a name="l00156"></a>00156             <span class="keywordflow">break</span>;
<a name="l00157"></a>00157         }
<a name="l00158"></a>00158     }
<a name="l00159"></a>00159 
<a name="l00160"></a>00160     si_-&gt;freeState(xstate);
<a name="l00161"></a>00161 
<a name="l00162"></a>00162     msg_.inform(<span class="stringliteral">&quot;Created %u (%u start + %u goal) states in %u cells (%u start + %u goal)&quot;</span>, tStart_.size + tGoal_.size, tStart_.size, tGoal_.size,
<a name="l00163"></a>00163                  tStart_.grid.size() + tGoal_.grid.size(), tStart_.grid.size(), tGoal_.grid.size());
<a name="l00164"></a>00164 
<a name="l00165"></a>00165     <span class="keywordflow">return</span> goal-&gt;<a class="code" href="classompl_1_1base_1_1Goal.html#a9a6e44d33f848108d0beeb1cf7a6c1ad" title="Returns true if a solution path has been found (could be approximate)">isAchieved</a>();
<a name="l00166"></a>00166 }
<a name="l00167"></a>00167 
<a name="l00168"></a><a class="code" href="classompl_1_1geometric_1_1SBL.html#af71623082dc34713a0584baddf327bf1">00168</a> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1geometric_1_1SBL.html#af71623082dc34713a0584baddf327bf1" title="Check if a solution can be obtained by connecting two trees using a specified motion.">ompl::geometric::SBL::checkSolution</a>(<span class="keywordtype">bool</span> start, <a class="code" href="structompl_1_1geometric_1_1SBL_1_1TreeData.html" title="Representation of a search tree. Two instances will be used. One for start and one for goal...">TreeData</a> &amp;tree, <a class="code" href="structompl_1_1geometric_1_1SBL_1_1TreeData.html" title="Representation of a search tree. Two instances will be used. One for start and one for goal...">TreeData</a> &amp;otherTree, <a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html" title="Representation of a motion.">Motion</a> *motion, std::vector&lt;Motion*&gt; &amp;solution)
<a name="l00169"></a>00169 {
<a name="l00170"></a>00170     <a class="code" href="classompl_1_1Grid.html" title="Representation of a simple grid.">Grid&lt;MotionSet&gt;::Coord</a> coord;
<a name="l00171"></a>00171     projectionEvaluator_-&gt;computeCoordinates(motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a1961e2628ac13bd2946f32a0df0e0644" title="The state this motion leads to.">state</a>, coord);
<a name="l00172"></a>00172     <a class="code" href="classompl_1_1Grid.html" title="Representation of a simple grid.">Grid&lt;MotionSet&gt;::Cell</a>* cell = otherTree.<a class="code" href="structompl_1_1geometric_1_1SBL_1_1TreeData.html#a06d446c1f27927f0155ecaff80520d7e" title="The grid of motions corresponding to this tree.">grid</a>.<a class="code" href="classompl_1_1Grid.html#ae563fea4e6a46c741682b6dcbe93ce54" title="Get the cell at a specified coordinate.">getCell</a>(coord);
<a name="l00173"></a>00173 
<a name="l00174"></a>00174     <span class="keywordflow">if</span> (cell &amp;&amp; !cell-&gt;data.<a class="code" href="classompl_1_1Grid.html#af91ee958440919adc378ab2ae3b49fd8" title="Check if the grid is empty.">empty</a>())
<a name="l00175"></a>00175     {
<a name="l00176"></a>00176         <a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html" title="Representation of a motion.">Motion</a> *connectOther = cell-&gt;data[rng_.uniformInt(0, cell-&gt;data.<a class="code" href="classompl_1_1Grid.html#a94c2dd5667093608a10aa91a46f42dfa" title="Check the size of the grid.">size</a>() - 1)];
<a name="l00177"></a>00177 
<a name="l00178"></a>00178         <span class="keywordflow">if</span> (pdef_-&gt;getGoal()-&gt;isStartGoalPairValid(start ? motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#ab4c75449dee78c54accf15a27e45a138" title="The root of the tree this motion would get to, if we were to follow parent pointers.">root</a> : connectOther-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#ab4c75449dee78c54accf15a27e45a138" title="The root of the tree this motion would get to, if we were to follow parent pointers.">root</a>, start ? connectOther-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#ab4c75449dee78c54accf15a27e45a138" title="The root of the tree this motion would get to, if we were to follow parent pointers.">root</a> : motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#ab4c75449dee78c54accf15a27e45a138" title="The root of the tree this motion would get to, if we were to follow parent pointers.">root</a>))
<a name="l00179"></a>00179         {
<a name="l00180"></a>00180             <a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html" title="Representation of a motion.">Motion</a> *connect = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html" title="Representation of a motion.">Motion</a>(si_);
<a name="l00181"></a>00181 
<a name="l00182"></a>00182             si_-&gt;copyState(connect-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a1961e2628ac13bd2946f32a0df0e0644" title="The state this motion leads to.">state</a>, connectOther-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a1961e2628ac13bd2946f32a0df0e0644" title="The state this motion leads to.">state</a>);
<a name="l00183"></a>00183             connect-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a6909be2bcc8fc942027be974fc583035" title="The parent motion -- it contains the state this motion originates at.">parent</a> = motion;
<a name="l00184"></a>00184             connect-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#ab4c75449dee78c54accf15a27e45a138" title="The root of the tree this motion would get to, if we were to follow parent pointers.">root</a> = motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#ab4c75449dee78c54accf15a27e45a138" title="The root of the tree this motion would get to, if we were to follow parent pointers.">root</a>;
<a name="l00185"></a>00185             motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a7fb9efdcee594786f85fba6acd6a8fdd" title="The set of motions descending from the current motion.">children</a>.push_back(connect);
<a name="l00186"></a>00186             addMotion(tree, connect);
<a name="l00187"></a>00187 
<a name="l00188"></a>00188             <span class="keywordflow">if</span> (isPathValid(tree, connect) &amp;&amp; isPathValid(otherTree, connectOther))
<a name="l00189"></a>00189             {
<a name="l00190"></a>00190                 <span class="comment">/* extract the motions and put them in solution vector */</span>
<a name="l00191"></a>00191 
<a name="l00192"></a>00192                 std::vector&lt;Motion*&gt; mpath1;
<a name="l00193"></a>00193                 <span class="keywordflow">while</span> (motion != NULL)
<a name="l00194"></a>00194                 {
<a name="l00195"></a>00195                     mpath1.push_back(motion);
<a name="l00196"></a>00196                     motion = motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a6909be2bcc8fc942027be974fc583035" title="The parent motion -- it contains the state this motion originates at.">parent</a>;
<a name="l00197"></a>00197                 }
<a name="l00198"></a>00198 
<a name="l00199"></a>00199                 std::vector&lt;Motion*&gt; mpath2;
<a name="l00200"></a>00200                 <span class="keywordflow">while</span> (connectOther != NULL)
<a name="l00201"></a>00201                 {
<a name="l00202"></a>00202                     mpath2.push_back(connectOther);
<a name="l00203"></a>00203                     connectOther = connectOther-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a6909be2bcc8fc942027be974fc583035" title="The parent motion -- it contains the state this motion originates at.">parent</a>;
<a name="l00204"></a>00204                 }
<a name="l00205"></a>00205 
<a name="l00206"></a>00206                 <span class="keywordflow">if</span> (!start)
<a name="l00207"></a>00207                     mpath1.swap(mpath2);
<a name="l00208"></a>00208 
<a name="l00209"></a>00209                 <span class="keywordflow">for</span> (<span class="keywordtype">int</span> i = mpath1.size() - 1 ; i &gt;= 0 ; --i)
<a name="l00210"></a>00210                     solution.push_back(mpath1[i]);
<a name="l00211"></a>00211                 solution.insert(solution.end(), mpath2.begin(), mpath2.end());
<a name="l00212"></a>00212 
<a name="l00213"></a>00213                 <span class="keywordflow">return</span> <span class="keyword">true</span>;
<a name="l00214"></a>00214             }
<a name="l00215"></a>00215         }
<a name="l00216"></a>00216     }
<a name="l00217"></a>00217     <span class="keywordflow">return</span> <span class="keyword">false</span>;
<a name="l00218"></a>00218 }
<a name="l00219"></a>00219 
<a name="l00220"></a><a class="code" href="classompl_1_1geometric_1_1SBL.html#a5c290474f7aadefb7c5ed24bcab832be">00220</a> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1geometric_1_1SBL.html#a5c290474f7aadefb7c5ed24bcab832be" title="Since solutions are computed in a lazy fashion, once trees are connected, the solution found needs to...">ompl::geometric::SBL::isPathValid</a>(<a class="code" href="structompl_1_1geometric_1_1SBL_1_1TreeData.html" title="Representation of a search tree. Two instances will be used. One for start and one for goal...">TreeData</a> &amp;tree, <a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html" title="Representation of a motion.">Motion</a> *motion)
<a name="l00221"></a>00221 {
<a name="l00222"></a>00222     std::vector&lt;Motion*&gt; mpath;
<a name="l00223"></a>00223 
<a name="l00224"></a>00224     <span class="comment">/* construct the solution path */</span>
<a name="l00225"></a>00225     <span class="keywordflow">while</span> (motion != NULL)
<a name="l00226"></a>00226     {
<a name="l00227"></a>00227         mpath.push_back(motion);
<a name="l00228"></a>00228         motion = motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a6909be2bcc8fc942027be974fc583035" title="The parent motion -- it contains the state this motion originates at.">parent</a>;
<a name="l00229"></a>00229     }
<a name="l00230"></a>00230 
<a name="l00231"></a>00231     <span class="comment">/* check the path */</span>
<a name="l00232"></a>00232     <span class="keywordflow">for</span> (<span class="keywordtype">int</span> i = mpath.size() - 1 ; i &gt;= 0 ; --i)
<a name="l00233"></a>00233         <span class="keywordflow">if</span> (!mpath[i]-&gt;valid)
<a name="l00234"></a>00234         {
<a name="l00235"></a>00235             <span class="keywordflow">if</span> (si_-&gt;checkMotion(mpath[i]-&gt;parent-&gt;state, mpath[i]-&gt;state))
<a name="l00236"></a>00236                 mpath[i]-&gt;valid = <span class="keyword">true</span>;
<a name="l00237"></a>00237             <span class="keywordflow">else</span>
<a name="l00238"></a>00238             {
<a name="l00239"></a>00239                 removeMotion(tree, mpath[i]);
<a name="l00240"></a>00240                 <span class="keywordflow">return</span> <span class="keyword">false</span>;
<a name="l00241"></a>00241             }
<a name="l00242"></a>00242         }
<a name="l00243"></a>00243     <span class="keywordflow">return</span> <span class="keyword">true</span>;
<a name="l00244"></a>00244 }
<a name="l00245"></a>00245 
<a name="l00246"></a><a class="code" href="classompl_1_1geometric_1_1SBL.html#afb79a0fdc7fc54251d6ef246cdbf2a0c">00246</a> <a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html" title="Representation of a motion.">ompl::geometric::SBL::Motion</a>* <a class="code" href="classompl_1_1geometric_1_1SBL.html#afb79a0fdc7fc54251d6ef246cdbf2a0c" title="Select a motion from a tree.">ompl::geometric::SBL::selectMotion</a>(<a class="code" href="structompl_1_1geometric_1_1SBL_1_1TreeData.html" title="Representation of a search tree. Two instances will be used. One for start and one for goal...">TreeData</a> &amp;tree)
<a name="l00247"></a>00247 {
<a name="l00248"></a>00248     <span class="keywordtype">double</span> sum  = 0.0;
<a name="l00249"></a>00249     <a class="code" href="classompl_1_1Grid.html" title="Representation of a simple grid.">Grid&lt;MotionSet&gt;::Cell</a>* cell = NULL;
<a name="l00250"></a>00250     <span class="keywordtype">double</span> prob = rng_.uniform01() * (tree.<a class="code" href="structompl_1_1geometric_1_1SBL_1_1TreeData.html#a06d446c1f27927f0155ecaff80520d7e" title="The grid of motions corresponding to this tree.">grid</a>.<a class="code" href="classompl_1_1Grid.html#a94c2dd5667093608a10aa91a46f42dfa" title="Check the size of the grid.">size</a>() - 1);
<a name="l00251"></a>00251     <span class="keywordflow">for</span> (<a class="code" href="classompl_1_1Grid.html" title="Representation of a simple grid.">Grid&lt;MotionSet&gt;::iterator</a> it = tree.<a class="code" href="structompl_1_1geometric_1_1SBL_1_1TreeData.html#a06d446c1f27927f0155ecaff80520d7e" title="The grid of motions corresponding to this tree.">grid</a>.<a class="code" href="classompl_1_1Grid.html#ad74c5df97cf3d54a1a15eff55596973c" title="Return the begin() iterator for the grid.">begin</a>(); it != tree.<a class="code" href="structompl_1_1geometric_1_1SBL_1_1TreeData.html#a06d446c1f27927f0155ecaff80520d7e" title="The grid of motions corresponding to this tree.">grid</a>.<a class="code" href="classompl_1_1Grid.html#ac5d360c8fa02bd6ec58aa8cbbc450dd7" title="Return the end() iterator for the grid.">end</a>() ; ++it)
<a name="l00252"></a>00252     {
<a name="l00253"></a>00253         sum += (double)(tree.<a class="code" href="structompl_1_1geometric_1_1SBL_1_1TreeData.html#a5468bf9faf38d010765fda43bdfedbca" title="The number of motions (in total) from the tree.">size</a> - it-&gt;second-&gt;data.size()) / (<span class="keywordtype">double</span>)tree.<a class="code" href="structompl_1_1geometric_1_1SBL_1_1TreeData.html#a5468bf9faf38d010765fda43bdfedbca" title="The number of motions (in total) from the tree.">size</a>;
<a name="l00254"></a>00254         <span class="keywordflow">if</span> (prob &lt; sum)
<a name="l00255"></a>00255         {
<a name="l00256"></a>00256             cell = it-&gt;second;
<a name="l00257"></a>00257             <span class="keywordflow">break</span>;
<a name="l00258"></a>00258         }
<a name="l00259"></a>00259     }
<a name="l00260"></a>00260     <span class="keywordflow">if</span> (!cell &amp;&amp; tree.<a class="code" href="structompl_1_1geometric_1_1SBL_1_1TreeData.html#a06d446c1f27927f0155ecaff80520d7e" title="The grid of motions corresponding to this tree.">grid</a>.<a class="code" href="classompl_1_1Grid.html#a94c2dd5667093608a10aa91a46f42dfa" title="Check the size of the grid.">size</a>() &gt; 0)
<a name="l00261"></a>00261         cell = tree.<a class="code" href="structompl_1_1geometric_1_1SBL_1_1TreeData.html#a06d446c1f27927f0155ecaff80520d7e" title="The grid of motions corresponding to this tree.">grid</a>.<a class="code" href="classompl_1_1Grid.html#ad74c5df97cf3d54a1a15eff55596973c" title="Return the begin() iterator for the grid.">begin</a>()-&gt;second;
<a name="l00262"></a>00262     <span class="keywordflow">return</span> cell &amp;&amp; !cell-&gt;data.<a class="code" href="classompl_1_1Grid.html#af91ee958440919adc378ab2ae3b49fd8" title="Check if the grid is empty.">empty</a>() ? cell-&gt;data[rng_.uniformInt(0, cell-&gt;data.<a class="code" href="classompl_1_1Grid.html#a94c2dd5667093608a10aa91a46f42dfa" title="Check the size of the grid.">size</a>() - 1)] : NULL;
<a name="l00263"></a>00263 }
<a name="l00264"></a>00264 
<a name="l00265"></a><a class="code" href="classompl_1_1geometric_1_1SBL.html#a61d240f219227b2476df8d534289a200">00265</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1SBL.html#a61d240f219227b2476df8d534289a200" title="Remove a motion from a tree.">ompl::geometric::SBL::removeMotion</a>(<a class="code" href="structompl_1_1geometric_1_1SBL_1_1TreeData.html" title="Representation of a search tree. Two instances will be used. One for start and one for goal...">TreeData</a> &amp;tree, <a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html" title="Representation of a motion.">Motion</a> *motion)
<a name="l00266"></a>00266 {
<a name="l00267"></a>00267     <span class="comment">/* remove from grid */</span>
<a name="l00268"></a>00268 
<a name="l00269"></a>00269     <a class="code" href="classompl_1_1Grid.html" title="Representation of a simple grid.">Grid&lt;MotionSet&gt;::Coord</a> coord;
<a name="l00270"></a>00270     projectionEvaluator_-&gt;computeCoordinates(motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a1961e2628ac13bd2946f32a0df0e0644" title="The state this motion leads to.">state</a>, coord);
<a name="l00271"></a>00271     <a class="code" href="classompl_1_1Grid.html" title="Representation of a simple grid.">Grid&lt;MotionSet&gt;::Cell</a>* cell = tree.<a class="code" href="structompl_1_1geometric_1_1SBL_1_1TreeData.html#a06d446c1f27927f0155ecaff80520d7e" title="The grid of motions corresponding to this tree.">grid</a>.<a class="code" href="classompl_1_1Grid.html#ae563fea4e6a46c741682b6dcbe93ce54" title="Get the cell at a specified coordinate.">getCell</a>(coord);
<a name="l00272"></a>00272     <span class="keywordflow">if</span> (cell)
<a name="l00273"></a>00273     {
<a name="l00274"></a>00274         <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i &lt; cell-&gt;data.<a class="code" href="classompl_1_1Grid.html#a94c2dd5667093608a10aa91a46f42dfa" title="Check the size of the grid.">size</a>(); ++i)
<a name="l00275"></a>00275             <span class="keywordflow">if</span> (cell-&gt;data[i] == motion)
<a name="l00276"></a>00276             {
<a name="l00277"></a>00277                 cell-&gt;data.erase(cell-&gt;data.<a class="code" href="classompl_1_1Grid.html#ad74c5df97cf3d54a1a15eff55596973c" title="Return the begin() iterator for the grid.">begin</a>() + i);
<a name="l00278"></a>00278                 tree.<a class="code" href="structompl_1_1geometric_1_1SBL_1_1TreeData.html#a5468bf9faf38d010765fda43bdfedbca" title="The number of motions (in total) from the tree.">size</a>--;
<a name="l00279"></a>00279                 <span class="keywordflow">break</span>;
<a name="l00280"></a>00280             }
<a name="l00281"></a>00281         <span class="keywordflow">if</span> (cell-&gt;data.<a class="code" href="classompl_1_1Grid.html#af91ee958440919adc378ab2ae3b49fd8" title="Check if the grid is empty.">empty</a>())
<a name="l00282"></a>00282         {
<a name="l00283"></a>00283             tree.<a class="code" href="structompl_1_1geometric_1_1SBL_1_1TreeData.html#a06d446c1f27927f0155ecaff80520d7e" title="The grid of motions corresponding to this tree.">grid</a>.<a class="code" href="classompl_1_1Grid.html#a72386f9ffd43e98d25aa38b224541564">remove</a>(cell);
<a name="l00284"></a>00284             tree.<a class="code" href="structompl_1_1geometric_1_1SBL_1_1TreeData.html#a06d446c1f27927f0155ecaff80520d7e" title="The grid of motions corresponding to this tree.">grid</a>.<a class="code" href="classompl_1_1Grid.html#a5876a2ff7b1092fd00fc58fee9ad1829" title="Clear the memory occupied by a cell; do not call this function unless remove() was called first...">destroyCell</a>(cell);
<a name="l00285"></a>00285         }
<a name="l00286"></a>00286     }
<a name="l00287"></a>00287 
<a name="l00288"></a>00288     <span class="comment">/* remove self from parent list */</span>
<a name="l00289"></a>00289 
<a name="l00290"></a>00290     <span class="keywordflow">if</span> (motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a6909be2bcc8fc942027be974fc583035" title="The parent motion -- it contains the state this motion originates at.">parent</a>)
<a name="l00291"></a>00291     {
<a name="l00292"></a>00292         <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i &lt; motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a6909be2bcc8fc942027be974fc583035" title="The parent motion -- it contains the state this motion originates at.">parent</a>-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a7fb9efdcee594786f85fba6acd6a8fdd" title="The set of motions descending from the current motion.">children</a>.size() ; ++i)
<a name="l00293"></a>00293             <span class="keywordflow">if</span> (motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a6909be2bcc8fc942027be974fc583035" title="The parent motion -- it contains the state this motion originates at.">parent</a>-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a7fb9efdcee594786f85fba6acd6a8fdd" title="The set of motions descending from the current motion.">children</a>[i] == motion)
<a name="l00294"></a>00294             {
<a name="l00295"></a>00295                 motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a6909be2bcc8fc942027be974fc583035" title="The parent motion -- it contains the state this motion originates at.">parent</a>-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a7fb9efdcee594786f85fba6acd6a8fdd" title="The set of motions descending from the current motion.">children</a>.erase(motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a6909be2bcc8fc942027be974fc583035" title="The parent motion -- it contains the state this motion originates at.">parent</a>-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a7fb9efdcee594786f85fba6acd6a8fdd" title="The set of motions descending from the current motion.">children</a>.begin() + i);
<a name="l00296"></a>00296                 <span class="keywordflow">break</span>;
<a name="l00297"></a>00297             }
<a name="l00298"></a>00298     }
<a name="l00299"></a>00299 
<a name="l00300"></a>00300     <span class="comment">/* remove children */</span>
<a name="l00301"></a>00301     <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i &lt; motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a7fb9efdcee594786f85fba6acd6a8fdd" title="The set of motions descending from the current motion.">children</a>.size() ; ++i)
<a name="l00302"></a>00302     {
<a name="l00303"></a>00303         motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a7fb9efdcee594786f85fba6acd6a8fdd" title="The set of motions descending from the current motion.">children</a>[i]-&gt;parent = NULL;
<a name="l00304"></a>00304         removeMotion(tree, motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a7fb9efdcee594786f85fba6acd6a8fdd" title="The set of motions descending from the current motion.">children</a>[i]);
<a name="l00305"></a>00305     }
<a name="l00306"></a>00306 
<a name="l00307"></a>00307     <span class="keywordflow">if</span> (motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a1961e2628ac13bd2946f32a0df0e0644" title="The state this motion leads to.">state</a>)
<a name="l00308"></a>00308         si_-&gt;freeState(motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a1961e2628ac13bd2946f32a0df0e0644" title="The state this motion leads to.">state</a>);
<a name="l00309"></a>00309     <span class="keyword">delete</span> motion;
<a name="l00310"></a>00310 }
<a name="l00311"></a>00311 
<a name="l00312"></a><a class="code" href="classompl_1_1geometric_1_1SBL.html#aa7aaf57300e6a8474aade8c2b9899454">00312</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1SBL.html#aa7aaf57300e6a8474aade8c2b9899454" title="Add a motion to a tree.">ompl::geometric::SBL::addMotion</a>(<a class="code" href="structompl_1_1geometric_1_1SBL_1_1TreeData.html" title="Representation of a search tree. Two instances will be used. One for start and one for goal...">TreeData</a> &amp;tree, <a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html" title="Representation of a motion.">Motion</a> *motion)
<a name="l00313"></a>00313 {
<a name="l00314"></a>00314     <a class="code" href="classompl_1_1Grid.html" title="Representation of a simple grid.">Grid&lt;MotionSet&gt;::Coord</a> coord;
<a name="l00315"></a>00315     projectionEvaluator_-&gt;computeCoordinates(motion-&gt;<a class="code" href="classompl_1_1geometric_1_1SBL_1_1Motion.html#a1961e2628ac13bd2946f32a0df0e0644" title="The state this motion leads to.">state</a>, coord);
<a name="l00316"></a>00316     <a class="code" href="classompl_1_1Grid.html" title="Representation of a simple grid.">Grid&lt;MotionSet&gt;::Cell</a>* cell = tree.<a class="code" href="structompl_1_1geometric_1_1SBL_1_1TreeData.html#a06d446c1f27927f0155ecaff80520d7e" title="The grid of motions corresponding to this tree.">grid</a>.<a class="code" href="classompl_1_1Grid.html#ae563fea4e6a46c741682b6dcbe93ce54" title="Get the cell at a specified coordinate.">getCell</a>(coord);
<a name="l00317"></a>00317     <span class="keywordflow">if</span> (cell)
<a name="l00318"></a>00318         cell-&gt;data.push_back(motion);
<a name="l00319"></a>00319     <span class="keywordflow">else</span>
<a name="l00320"></a>00320     {
<a name="l00321"></a>00321         cell = tree.<a class="code" href="structompl_1_1geometric_1_1SBL_1_1TreeData.html#a06d446c1f27927f0155ecaff80520d7e" title="The grid of motions corresponding to this tree.">grid</a>.<a class="code" href="classompl_1_1Grid.html#ad105860f5ce20c533281104b95f3d402">createCell</a>(coord);
<a name="l00322"></a>00322         cell-&gt;data.push_back(motion);
<a name="l00323"></a>00323         tree.<a class="code" href="structompl_1_1geometric_1_1SBL_1_1TreeData.html#a06d446c1f27927f0155ecaff80520d7e" title="The grid of motions corresponding to this tree.">grid</a>.<a class="code" href="classompl_1_1Grid.html#ac72fa046a57332c7627126e8d84fb1dc" title="Add an instantiated cell to the grid.">add</a>(cell);
<a name="l00324"></a>00324     }
<a name="l00325"></a>00325     tree.<a class="code" href="structompl_1_1geometric_1_1SBL_1_1TreeData.html#a5468bf9faf38d010765fda43bdfedbca" title="The number of motions (in total) from the tree.">size</a>++;
<a name="l00326"></a>00326 }
<a name="l00327"></a>00327 
<a name="l00328"></a><a class="code" href="classompl_1_1geometric_1_1SBL.html#acac3c7d4b736c95d54c904c145a0c2e6">00328</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1SBL.html#acac3c7d4b736c95d54c904c145a0c2e6" title="Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...">ompl::geometric::SBL::clear</a>(<span class="keywordtype">void</span>)
<a name="l00329"></a>00329 {
<a name="l00330"></a>00330     Planner::clear();
<a name="l00331"></a>00331 
<a name="l00332"></a>00332     sampler_.reset();
<a name="l00333"></a>00333 
<a name="l00334"></a>00334     freeMemory();
<a name="l00335"></a>00335 
<a name="l00336"></a>00336     tStart_.grid.clear();
<a name="l00337"></a>00337     tStart_.size = 0;
<a name="l00338"></a>00338 
<a name="l00339"></a>00339     tGoal_.grid.clear();
<a name="l00340"></a>00340     tGoal_.size = 0;
<a name="l00341"></a>00341 }
<a name="l00342"></a>00342 
<a name="l00343"></a><a class="code" href="classompl_1_1geometric_1_1SBL.html#a5d8ac60361bd040a03d6fcdba7da29cd">00343</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1SBL.html#a5d8ac60361bd040a03d6fcdba7da29cd" title="Get information about the current run of the motion planner. Repeated calls to this function will upd...">ompl::geometric::SBL::getPlannerData</a>(<a class="code" href="classompl_1_1base_1_1PlannerData.html" title="Datatype holding data a planner can expose for debug purposes.">base::PlannerData</a> &amp;data)<span class="keyword"> const</span>
<a name="l00344"></a>00344 <span class="keyword"></span>{
<a name="l00345"></a>00345     Planner::getPlannerData(data);
<a name="l00346"></a>00346 
<a name="l00347"></a>00347     std::vector&lt;MotionSet&gt; motions;
<a name="l00348"></a>00348     tStart_.grid.getContent(motions);
<a name="l00349"></a>00349 
<a name="l00350"></a>00350     <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i &lt; motions.size() ; ++i)
<a name="l00351"></a>00351         <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> j = 0 ; j &lt; motions[i].size() ; ++j)
<a name="l00352"></a>00352         {
<a name="l00353"></a>00353             data.<a class="code" href="classompl_1_1base_1_1PlannerData.html#aa11d568e75a53a0fecddbecbc05ca429" title="Record an edge between two states. This function is called by planners to fill states, stateIndex and edges. If the same state/edge is seen multiple times, it is added only once.">recordEdge</a>(motions[i][j]-&gt;parent ? motions[i][j]-&gt;parent-&gt;state : NULL, motions[i][j]-&gt;state);
<a name="l00354"></a>00354             data.<a class="code" href="classompl_1_1base_1_1PlannerData.html#a8de56c12227187dbb8d2c81af916f146" title="Assign a tag to a state.">tagState</a>(motions[i][j]-&gt;state, 1);
<a name="l00355"></a>00355         }
<a name="l00356"></a>00356 
<a name="l00357"></a>00357 
<a name="l00358"></a>00358     motions.clear();
<a name="l00359"></a>00359     tGoal_.grid.getContent(motions);
<a name="l00360"></a>00360 
<a name="l00361"></a>00361     <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i &lt; motions.size() ; ++i)
<a name="l00362"></a>00362         <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> j = 0 ; j &lt; motions[i].size() ; ++j)
<a name="l00363"></a>00363         {
<a name="l00364"></a>00364             data.<a class="code" href="classompl_1_1base_1_1PlannerData.html#aa11d568e75a53a0fecddbecbc05ca429" title="Record an edge between two states. This function is called by planners to fill states, stateIndex and edges. If the same state/edge is seen multiple times, it is added only once.">recordEdge</a>(motions[i][j]-&gt;parent ? motions[i][j]-&gt;parent-&gt;state : NULL, motions[i][j]-&gt;state);
<a name="l00365"></a>00365             data.<a class="code" href="classompl_1_1base_1_1PlannerData.html#a8de56c12227187dbb8d2c81af916f146" title="Assign a tag to a state.">tagState</a>(motions[i][j]-&gt;state, 2);
<a name="l00366"></a>00366         }
<a name="l00367"></a>00367 
<a name="l00368"></a>00368 }
</pre></div></div>
</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:30 by&#160;<a href="http://www.doxygen.org/index.html">doxygen</a> 1.7.4</div>
</div>
</div>
</body>
</html>