<!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/contrib/rrt_star/src/BallTreeRRTstar.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"> </span>All</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(1)"><span class="SelectionMark"> </span>Classes</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(2)"><span class="SelectionMark"> </span>Namespaces</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(3)"><span class="SelectionMark"> </span>Functions</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(4)"><span class="SelectionMark"> </span>Variables</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(5)"><span class="SelectionMark"> </span>Typedefs</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(6)"><span class="SelectionMark"> </span>Enumerations</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(7)"><span class="SelectionMark"> </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_9f71015475b38a69aaae354435fa4512.html">contrib</a> </li> <li class="navelem"><a class="el" href="dir_dc31619b058474cd7b929e82901d6adb.html">rrt_star</a> </li> <li class="navelem"><a class="el" href="dir_d575ba698883e341b34e40d9826a2e18.html">src</a> </li> </ul> </div> </div> <div class="header"> <div class="headertitle"> <div class="title">BallTreeRRTstar.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) 2011, Rice University</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 Rice University 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">* "AS IS" 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">/* Authors: Alejandro Perez, Sertac Karaman, Ioan Sucan */</span> <a name="l00036"></a>00036 <a name="l00037"></a>00037 <span class="preprocessor">#include "ompl/contrib/rrt_star/BallTreeRRTstar.h"</span> <a name="l00038"></a>00038 <span class="preprocessor">#include "ompl/base/GoalSampleableRegion.h"</span> <a name="l00039"></a>00039 <span class="preprocessor">#include "ompl/datastructures/NearestNeighborsSqrtApprox.h"</span> <a name="l00040"></a>00040 <span class="preprocessor">#include "ompl/tools/config/SelfConfig.h"</span> <a name="l00041"></a>00041 <span class="preprocessor">#include <algorithm></span> <a name="l00042"></a>00042 <span class="preprocessor">#include <limits></span> <a name="l00043"></a>00043 <span class="preprocessor">#include <map></span> <a name="l00044"></a>00044 <a name="l00045"></a><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#afd5af5d5217dff1115820202d9c85ac3">00045</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#afd5af5d5217dff1115820202d9c85ac3" title="Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...">ompl::geometric::BallTreeRRTstar::setup</a>(<span class="keywordtype">void</span>) <a name="l00046"></a>00046 { <a name="l00047"></a>00047 <a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#afd5af5d5217dff1115820202d9c85ac3" title="Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...">Planner::setup</a>(); <a name="l00048"></a>00048 <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="l00049"></a>00049 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_1BallTreeRRTstar.html#a74f84ff8f56b4413a617bee1dc5ee68d" title="The maximum length of a motion to be added to a tree.">maxDistance_</a>); <a name="l00050"></a>00050 <a name="l00051"></a>00051 <a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a313137f73961f360e6eebaba79f21315" title="Maximum radius the planner uses to find near neighbors and rewire.">ballRadiusMax_</a> = <a class="code" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e" title="The space information for which planning is done.">si_</a>->getMaximumExtent(); <a name="l00052"></a>00052 <a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#ae031c5ecc5c5a557692862f41d325f11" title="Shrink rate of radius the planner uses to find near neighbors and rewire.">ballRadiusConst_</a> = <a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a74f84ff8f56b4413a617bee1dc5ee68d" title="The maximum length of a motion to be added to a tree.">maxDistance_</a> * sqrt(<a class="code" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e" title="The space information for which planning is done.">si_</a>->getStateSpace()->getDimension()); <a name="l00053"></a>00053 <a name="l00054"></a>00054 <a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#ace5c17f5eae277cbe6c9e2dc8f3fb1ed" title="Option to delay and reduce collision checking within iterations.">delayCC_</a> = <span class="keyword">true</span>; <a name="l00055"></a>00055 <a name="l00056"></a>00056 <span class="keywordflow">if</span> (!<a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#acc4f6c9bc0eab53494c14c1410c11484" title="A nearest-neighbors datastructure containing the tree of motions.">nn_</a>) <a name="l00057"></a>00057 <a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#acc4f6c9bc0eab53494c14c1410c11484" title="A nearest-neighbors datastructure containing the tree of motions.">nn_</a>.reset(<span class="keyword">new</span> <a class="code" href="classompl_1_1NearestNeighborsSqrtApprox.html" title="A nearest neighbors datastructure that uses linear search. The linear search is done over sqrt(n) ele...">NearestNeighborsSqrtApprox<Motion*></a>()); <a name="l00058"></a>00058 <a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#acc4f6c9bc0eab53494c14c1410c11484" title="A nearest-neighbors datastructure containing the tree of motions.">nn_</a>->setDistanceFunction(boost::bind(&<a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#ad23854a908038c8caf45c9ab8421acc1" title="Distance calculation considering volumes.">BallTreeRRTstar::distanceFunction</a>, <span class="keyword">this</span>, _1, _2)); <a name="l00059"></a>00059 } <a name="l00060"></a>00060 <a name="l00061"></a><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a450aea782c10383dc22e21cfcb72dcea">00061</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a450aea782c10383dc22e21cfcb72dcea" title="Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...">ompl::geometric::BallTreeRRTstar::clear</a>(<span class="keywordtype">void</span>) <a name="l00062"></a>00062 { <a name="l00063"></a>00063 Planner::clear(); <a name="l00064"></a>00064 sampler_.reset(); <a name="l00065"></a>00065 motions_.clear(); <a name="l00066"></a>00066 freeMemory(); <a name="l00067"></a>00067 <span class="keywordflow">if</span> (nn_) <a name="l00068"></a>00068 nn_->clear(); <a name="l00069"></a>00069 } <a name="l00070"></a>00070 <a name="l00071"></a><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#aca33b01960299c9fd1704e6cdaf06c06">00071</a> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#aca33b01960299c9fd1704e6cdaf06c06" title="Function that can solve the motion planning problem. This function can be called multiple times on th...">ompl::geometric::BallTreeRRTstar::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> &ptc) <a name="l00072"></a>00072 { <a name="l00073"></a>00073 checkValidity(); <a name="l00074"></a>00074 <a class="code" href="classompl_1_1base_1_1Goal.html" title="Abstract definition of goals. Will contain solutions, if found.">base::Goal</a> *goal = pdef_->getGoal().get(); <a name="l00075"></a>00075 <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_s = <span class="keyword">dynamic_cast<</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">></span>(goal); <a name="l00076"></a>00076 <a name="l00077"></a>00077 <span class="keywordflow">if</span> (!goal) <a name="l00078"></a>00078 { <a name="l00079"></a>00079 msg_.error(<span class="stringliteral">"Goal undefined"</span>); <a name="l00080"></a>00080 <span class="keywordflow">return</span> <span class="keyword">false</span>; <a name="l00081"></a>00081 } <a name="l00082"></a>00082 <a name="l00083"></a>00083 <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="l00084"></a>00084 { <a name="l00085"></a>00085 <a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html" title="Representation of a motion.">Motion</a> *motion = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html" title="Representation of a motion.">Motion</a>(si_, rO_); <a name="l00086"></a>00086 si_->copyState(motion-><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#a8d95ca2061c2d38e294a307c0bd86be1" title="The state contained by the motion.">state</a>, st); <a name="l00087"></a>00087 addMotion(motion); <a name="l00088"></a>00088 } <a name="l00089"></a>00089 <a name="l00090"></a>00090 <span class="keywordflow">if</span> (nn_->size() == 0) <a name="l00091"></a>00091 { <a name="l00092"></a>00092 msg_.error(<span class="stringliteral">"There are no valid initial states!"</span>); <a name="l00093"></a>00093 <span class="keywordflow">return</span> <span class="keyword">false</span>; <a name="l00094"></a>00094 } <a name="l00095"></a>00095 <a name="l00096"></a>00096 <span class="keywordflow">if</span> (!sampler_) <a name="l00097"></a>00097 sampler_ = si_->allocStateSampler(); <a name="l00098"></a>00098 <a name="l00099"></a>00099 msg_.inform(<span class="stringliteral">"Starting with %u states"</span>, nn_->size()); <a name="l00100"></a>00100 <a name="l00101"></a>00101 <a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html" title="Representation of a motion.">Motion</a> *solution = NULL; <a name="l00102"></a>00102 <a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html" title="Representation of a motion.">Motion</a> *approxsol = NULL; <a name="l00103"></a>00103 <span class="keywordtype">double</span> approxdif = std::numeric_limits<double>::infinity(); <a name="l00104"></a>00104 <span class="keywordtype">bool</span> approxsolved = <span class="keyword">false</span>; <a name="l00105"></a>00105 <a name="l00106"></a>00106 <a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html" title="Representation of a motion.">Motion</a> *rmotion = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html" title="Representation of a motion.">Motion</a>(si_, rO_); <a name="l00107"></a>00107 <a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html" title="Representation of a motion.">Motion</a> *toTrim = NULL; <a name="l00108"></a>00108 <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">base::State</a> *rstate = rmotion-><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#a8d95ca2061c2d38e294a307c0bd86be1" title="The state contained by the motion.">state</a>; <a name="l00109"></a>00109 <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">base::State</a> *xstate = si_->allocState(); <a name="l00110"></a>00110 <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">base::State</a> *tstate = si_->allocState(); <a name="l00111"></a>00111 std::vector<Motion*> solCheck; <a name="l00112"></a>00112 std::vector<Motion*> nbh; <a name="l00113"></a>00113 std::vector<double> dists; <a name="l00114"></a>00114 std::vector<int> valid; <a name="l00115"></a>00115 <span class="keywordtype">long</span> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> rewireTest = 0; <a name="l00116"></a>00116 <a name="l00117"></a>00117 std::pair<base::State*,double> lastValid(tstate, 0.0); <a name="l00118"></a>00118 <a name="l00119"></a>00119 <span class="keywordflow">while</span> (ptc() == <span class="keyword">false</span>) <a name="l00120"></a>00120 { <a name="l00121"></a>00121 <span class="keywordtype">bool</span> rejected = <span class="keyword">false</span>; <a name="l00122"></a>00122 <a name="l00123"></a>00123 <span class="comment">/* sample until a state not within any of the existing volumes is found */</span> <a name="l00124"></a>00124 <span class="keywordflow">do</span> <a name="l00125"></a>00125 { <a name="l00126"></a>00126 <span class="comment">/* sample random state (with goal biasing) */</span> <a name="l00127"></a>00127 <span class="keywordflow">if</span> (goal_s && rng_.uniform01() < goalBias_ && goal_s-><a class="code" href="classompl_1_1base_1_1GoalSampleableRegion.html#a60329b89ea7217a7550197e5866c28c7" title="Return true of maxSampleCount() > 0, since in this case samples can certainly be produced.">canSample</a>()) <a name="l00128"></a>00128 goal_s-><a class="code" href="classompl_1_1base_1_1GoalSampleableRegion.html#a11c9d2c4d9d5ddbeb8c30e531d1efc5f" title="Sample a state in the goal region.">sampleGoal</a>(rstate); <a name="l00129"></a>00129 <span class="keywordflow">else</span> <a name="l00130"></a>00130 sampler_->sampleUniform(rstate); <a name="l00131"></a>00131 <a name="l00132"></a>00132 <span class="comment">/* check to see if it is inside an existing volume */</span> <a name="l00133"></a>00133 <span class="keywordflow">if</span> (inVolume(rstate)) <a name="l00134"></a>00134 { <a name="l00135"></a>00135 rejected = <span class="keyword">true</span>; <a name="l00136"></a>00136 <a name="l00137"></a>00137 <span class="comment">/* see if the state is valid */</span> <a name="l00138"></a>00138 <span class="keywordflow">if</span>(!si_->isValid(rstate)) <a name="l00139"></a>00139 { <a name="l00140"></a>00140 <span class="comment">/* if it's not, reduce the size of the nearest volume to the distance</span> <a name="l00141"></a>00141 <span class="comment"> between its center and the rejected state */</span> <a name="l00142"></a>00142 toTrim = nn_->nearest(rmotion); <a name="l00143"></a>00143 <span class="keywordtype">double</span> newRad = si_->distance(toTrim-><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#a8d95ca2061c2d38e294a307c0bd86be1" title="The state contained by the motion.">state</a>, rstate); <a name="l00144"></a>00144 <span class="keywordflow">if</span> (newRad < toTrim->volRadius) <a name="l00145"></a>00145 toTrim-><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#a36a1c4c7f77b7c5c6ee14adc9f5a4b72" title="The radius of the volume associated to this motion.">volRadius</a> = newRad; <a name="l00146"></a>00146 } <a name="l00147"></a>00147 <a name="l00148"></a>00148 } <a name="l00149"></a>00149 <span class="keywordflow">else</span> <a name="l00150"></a>00150 <a name="l00151"></a>00151 rejected = <span class="keyword">false</span>; <a name="l00152"></a>00152 <a name="l00153"></a>00153 } <a name="l00154"></a>00154 <span class="keywordflow">while</span> (rejected); <a name="l00155"></a>00155 <a name="l00156"></a>00156 <span class="comment">/* find closest state in the tree */</span> <a name="l00157"></a>00157 <a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html" title="Representation of a motion.">Motion</a> *nmotion = nn_->nearest(rmotion); <a name="l00158"></a>00158 <a name="l00159"></a>00159 <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">base::State</a> *dstate = rstate; <a name="l00160"></a>00160 <a name="l00161"></a>00161 <span class="comment">/* find state to add */</span> <a name="l00162"></a>00162 <span class="keywordtype">double</span> d = si_->distance(nmotion-><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#a8d95ca2061c2d38e294a307c0bd86be1" title="The state contained by the motion.">state</a>, rstate); <a name="l00163"></a>00163 <span class="keywordflow">if</span> (d > maxDistance_) <a name="l00164"></a>00164 { <a name="l00165"></a>00165 si_->getStateSpace()->interpolate(nmotion-><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#a8d95ca2061c2d38e294a307c0bd86be1" title="The state contained by the motion.">state</a>, rstate, maxDistance_ / d, xstate); <a name="l00166"></a>00166 dstate = xstate; <a name="l00167"></a>00167 } <a name="l00168"></a>00168 <a name="l00169"></a>00169 <span class="keywordflow">if</span> (si_->checkMotion(nmotion-><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#a8d95ca2061c2d38e294a307c0bd86be1" title="The state contained by the motion.">state</a>, dstate, lastValid)) <a name="l00170"></a>00170 { <a name="l00171"></a>00171 <span class="comment">/* create a motion */</span> <a name="l00172"></a>00172 <span class="keywordtype">double</span> distN = si_->distance(dstate, nmotion-><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#a8d95ca2061c2d38e294a307c0bd86be1" title="The state contained by the motion.">state</a>); <a name="l00173"></a>00173 <a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html" title="Representation of a motion.">Motion</a> *motion = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html" title="Representation of a motion.">Motion</a>(si_, rO_); <a name="l00174"></a>00174 si_->copyState(motion-><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#a8d95ca2061c2d38e294a307c0bd86be1" title="The state contained by the motion.">state</a>, dstate); <a name="l00175"></a>00175 motion-><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#af3b35ea82a4ce4a771ae72e12c3d8298" title="The parent motion in the exploration tree.">parent</a> = nmotion; <a name="l00176"></a>00176 motion-><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#a589e3cb7a2a25c4f54dde560c31c379e" title="The cost of this motion.">cost</a> = nmotion-><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#a589e3cb7a2a25c4f54dde560c31c379e" title="The cost of this motion.">cost</a> + distN; <a name="l00177"></a>00177 <a name="l00178"></a>00178 <span class="comment">/* find nearby neighbors */</span> <a name="l00179"></a>00179 <span class="keywordtype">double</span> r = std::min(ballRadiusConst_ * (sqrt(log((<span class="keywordtype">double</span>)(1 + nn_->size())) / ((double)(nn_->size())))), <a name="l00180"></a>00180 ballRadiusMax_); <a name="l00181"></a>00181 <a name="l00182"></a>00182 nn_->nearestR(motion, r, nbh); <a name="l00183"></a>00183 rewireTest += nbh.size(); <a name="l00184"></a>00184 <a name="l00185"></a>00185 <span class="comment">// cache for distance computations</span> <a name="l00186"></a>00186 dists.resize(nbh.size()); <a name="l00187"></a>00187 <span class="comment">// cache for motion validity</span> <a name="l00188"></a>00188 valid.resize(nbh.size()); <a name="l00189"></a>00189 std::fill(valid.begin(), valid.end(), 0); <a name="l00190"></a>00190 <a name="l00191"></a>00191 <span class="keywordflow">if</span> (delayCC_) <a name="l00192"></a>00192 { <a name="l00193"></a>00193 <span class="comment">// calculate all costs and distances</span> <a name="l00194"></a>00194 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < nbh.size() ; ++i) <a name="l00195"></a>00195 <span class="keywordflow">if</span> (nbh[i] != nmotion) <a name="l00196"></a>00196 { <a name="l00197"></a>00197 <span class="keywordtype">double</span> c = nbh[i]->cost + si_->distance(nbh[i]->state, dstate); <a name="l00198"></a>00198 nbh[i]->cost = c; <a name="l00199"></a>00199 } <a name="l00200"></a>00200 <a name="l00201"></a>00201 <span class="comment">// sort the nodes</span> <a name="l00202"></a>00202 std::sort(nbh.begin(), nbh.end(), compareMotion); <a name="l00203"></a>00203 <a name="l00204"></a>00204 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < nbh.size() ; ++i) <a name="l00205"></a>00205 <span class="keywordflow">if</span> (nbh[i] != nmotion) <a name="l00206"></a>00206 { <a name="l00207"></a>00207 dists[i] = si_->distance(nbh[i]->state, dstate); <a name="l00208"></a>00208 nbh[i]->cost -= dists[i]; <a name="l00209"></a>00209 } <a name="l00210"></a>00210 <span class="comment">// collision check until a valid motion is found</span> <a name="l00211"></a>00211 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < nbh.size() ; ++i) <a name="l00212"></a>00212 <span class="keywordflow">if</span> (nbh[i] != nmotion) <a name="l00213"></a>00213 { <a name="l00214"></a>00214 <a name="l00215"></a>00215 dists[i] = si_->distance(nbh[i]->state, dstate); <a name="l00216"></a>00216 <span class="keywordtype">double</span> c = nbh[i]->cost + dists[i]; <a name="l00217"></a>00217 <span class="keywordflow">if</span> (c < motion->cost) <a name="l00218"></a>00218 { <a name="l00219"></a>00219 <span class="keywordflow">if</span> (si_->checkMotion(nbh[i]->state, dstate, lastValid)) <a name="l00220"></a>00220 { <a name="l00221"></a>00221 motion-><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#a589e3cb7a2a25c4f54dde560c31c379e" title="The cost of this motion.">cost</a> = c; <a name="l00222"></a>00222 motion-><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#af3b35ea82a4ce4a771ae72e12c3d8298" title="The parent motion in the exploration tree.">parent</a> = nbh[i]; <a name="l00223"></a>00223 valid[i] = 1; <a name="l00224"></a>00224 <span class="keywordflow">break</span>; <a name="l00225"></a>00225 } <a name="l00226"></a>00226 <span class="keywordflow">else</span> <a name="l00227"></a>00227 { <a name="l00228"></a>00228 valid[i] = -1; <a name="l00229"></a>00229 <span class="comment">/* if a collision is found, trim radius to distance from motion to last valid state */</span> <a name="l00230"></a>00230 <span class="keywordtype">double</span> nR = si_->distance(nbh[i]->state, lastValid.first); <a name="l00231"></a>00231 <span class="keywordflow">if</span> (nR < nbh[i]->volRadius) <a name="l00232"></a>00232 nbh[i]-><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#a36a1c4c7f77b7c5c6ee14adc9f5a4b72" title="The radius of the volume associated to this motion.">volRadius</a> = nR; <a name="l00233"></a>00233 } <a name="l00234"></a>00234 } <a name="l00235"></a>00235 } <a name="l00236"></a>00236 <span class="keywordflow">else</span> <a name="l00237"></a>00237 { <a name="l00238"></a>00238 valid[i] = 1; <a name="l00239"></a>00239 dists[i] = distN; <a name="l00240"></a>00240 <span class="keywordflow">break</span>; <a name="l00241"></a>00241 } <a name="l00242"></a>00242 <a name="l00243"></a>00243 } <a name="l00244"></a>00244 <span class="keywordflow">else</span>{ <a name="l00245"></a>00245 <span class="comment">/* find which one we connect the new state to*/</span> <a name="l00246"></a>00246 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < nbh.size() ; ++i) <a name="l00247"></a>00247 <span class="keywordflow">if</span> (nbh[i] != nmotion) <a name="l00248"></a>00248 { <a name="l00249"></a>00249 <a name="l00250"></a>00250 dists[i] = si_->distance(nbh[i]->state, dstate); <a name="l00251"></a>00251 <span class="keywordtype">double</span> c = nbh[i]->cost + dists[i]; <a name="l00252"></a>00252 <span class="keywordflow">if</span> (c < motion->cost) <a name="l00253"></a>00253 { <a name="l00254"></a>00254 <span class="keywordflow">if</span> (si_->checkMotion(nbh[i]->state, dstate, lastValid)) <a name="l00255"></a>00255 { <a name="l00256"></a>00256 motion-><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#a589e3cb7a2a25c4f54dde560c31c379e" title="The cost of this motion.">cost</a> = c; <a name="l00257"></a>00257 motion-><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#af3b35ea82a4ce4a771ae72e12c3d8298" title="The parent motion in the exploration tree.">parent</a> = nbh[i]; <a name="l00258"></a>00258 valid[i] = 1; <a name="l00259"></a>00259 } <a name="l00260"></a>00260 <span class="keywordflow">else</span> <a name="l00261"></a>00261 { <a name="l00262"></a>00262 valid[i] = -1; <a name="l00263"></a>00263 <span class="comment">/* if a collision is found, trim radius to distance from motion to last valid state */</span> <a name="l00264"></a>00264 <span class="keywordtype">double</span> newR = si_->distance(nbh[i]->state, lastValid.first); <a name="l00265"></a>00265 <span class="keywordflow">if</span> (newR < nbh[i]->volRadius) <a name="l00266"></a>00266 nbh[i]-><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#a36a1c4c7f77b7c5c6ee14adc9f5a4b72" title="The radius of the volume associated to this motion.">volRadius</a> = newR; <a name="l00267"></a>00267 <a name="l00268"></a>00268 } <a name="l00269"></a>00269 } <a name="l00270"></a>00270 } <a name="l00271"></a>00271 <span class="keywordflow">else</span> <a name="l00272"></a>00272 { <a name="l00273"></a>00273 valid[i] = 1; <a name="l00274"></a>00274 dists[i] = distN; <a name="l00275"></a>00275 } <a name="l00276"></a>00276 } <a name="l00277"></a>00277 <a name="l00278"></a>00278 <span class="comment">/* add motion to tree */</span> <a name="l00279"></a>00279 addMotion(motion); <a name="l00280"></a>00280 <a name="l00281"></a>00281 solCheck.resize(1); <a name="l00282"></a>00282 solCheck[0] = motion; <a name="l00283"></a>00283 <a name="l00284"></a>00284 <span class="comment">/* rewire tree if needed */</span> <a name="l00285"></a>00285 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < nbh.size() ; ++i) <a name="l00286"></a>00286 <span class="keywordflow">if</span> (nbh[i] != motion-><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#af3b35ea82a4ce4a771ae72e12c3d8298" title="The parent motion in the exploration tree.">parent</a>) <a name="l00287"></a>00287 { <a name="l00288"></a>00288 <span class="keywordtype">double</span> c = motion-><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#a589e3cb7a2a25c4f54dde560c31c379e" title="The cost of this motion.">cost</a> + dists[i]; <a name="l00289"></a>00289 <span class="keywordflow">if</span> (c < nbh[i]->cost) <a name="l00290"></a>00290 { <a name="l00291"></a>00291 <span class="keywordtype">bool</span> v = <span class="keyword">false</span>; <a name="l00292"></a>00292 <span class="keywordflow">if</span> (valid[i] == 0) <a name="l00293"></a>00293 { <a name="l00294"></a>00294 <span class="keywordflow">if</span>(!si_->checkMotion(nbh[i]->state, dstate, lastValid)) <a name="l00295"></a>00295 { <a name="l00296"></a>00296 <span class="comment">/* if a collision is found, trim radius to distance from motion to last valid state */</span> <a name="l00297"></a>00297 <span class="keywordtype">double</span> R = si_->distance(nbh[i]->state, lastValid.first); <a name="l00298"></a>00298 <span class="keywordflow">if</span> (R < nbh[i]->volRadius) <a name="l00299"></a>00299 nbh[i]->volRadius = R; <a name="l00300"></a>00300 } <a name="l00301"></a>00301 <span class="keywordflow">else</span> <a name="l00302"></a>00302 { <a name="l00303"></a>00303 v = <span class="keyword">true</span>; <a name="l00304"></a>00304 } <a name="l00305"></a>00305 } <a name="l00306"></a>00306 <span class="keywordflow">if</span> (valid[i] == 1) <a name="l00307"></a>00307 v = <span class="keyword">true</span>; <a name="l00308"></a>00308 <a name="l00309"></a>00309 <span class="keywordflow">if</span> (v) <a name="l00310"></a>00310 { <a name="l00311"></a>00311 nbh[i]->parent = motion; <a name="l00312"></a>00312 nbh[i]-><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#a589e3cb7a2a25c4f54dde560c31c379e" title="The cost of this motion.">cost</a> = c; <a name="l00313"></a>00313 solCheck.push_back(nbh[i]); <a name="l00314"></a>00314 } <a name="l00315"></a>00315 } <a name="l00316"></a>00316 } <a name="l00317"></a>00317 <a name="l00318"></a>00318 <span class="comment">/* check if we found a solution */</span> <a name="l00319"></a>00319 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < solCheck.size() ; ++i) <a name="l00320"></a>00320 { <a name="l00321"></a>00321 <span class="keywordtype">double</span> dist = 0.0; <a name="l00322"></a>00322 <span class="keywordtype">bool</span> solved = goal-><a class="code" href="classompl_1_1base_1_1Goal.html#a02ba4ba487714cd4e8f67c9d4164d0ec" title="Return true if the state satisfies the goal constraints.">isSatisfied</a>(solCheck[i]->state, &dist); <a name="l00323"></a>00323 <span class="keywordtype">bool</span> sufficientlyShort = solved ? goal-><a class="code" href="classompl_1_1base_1_1Goal.html#ab4beedc8edd881714081eb99b9b4ba34" title="Check if pathLength is smaller than the value returned by getMaximumPathLength()">isPathLengthSatisfied</a>(solCheck[i]->cost) : <span class="keyword">false</span>; <a name="l00324"></a>00324 <a name="l00325"></a>00325 <span class="keywordflow">if</span> (solved) <a name="l00326"></a>00326 { <a name="l00327"></a>00327 <span class="keywordflow">if</span> (sufficientlyShort) <a name="l00328"></a>00328 { <a name="l00329"></a>00329 solution = solCheck[i]; <a name="l00330"></a>00330 <span class="keywordflow">break</span>; <a name="l00331"></a>00331 } <a name="l00332"></a>00332 <span class="keywordflow">else</span> <a name="l00333"></a>00333 { <a name="l00334"></a>00334 <span class="keywordflow">if</span> (approxsolved) <a name="l00335"></a>00335 { <a name="l00336"></a>00336 <span class="keywordflow">if</span> (dist < approxdif) <a name="l00337"></a>00337 { <a name="l00338"></a>00338 approxdif = dist; <a name="l00339"></a>00339 approxsol = solCheck[i]; <a name="l00340"></a>00340 } <a name="l00341"></a>00341 } <a name="l00342"></a>00342 <span class="keywordflow">else</span> <a name="l00343"></a>00343 { <a name="l00344"></a>00344 approxsolved = <span class="keyword">true</span>; <a name="l00345"></a>00345 approxdif = dist; <a name="l00346"></a>00346 approxsol = solCheck[i]; <a name="l00347"></a>00347 } <a name="l00348"></a>00348 } <a name="l00349"></a>00349 } <a name="l00350"></a>00350 <span class="keywordflow">else</span> <a name="l00351"></a>00351 <span class="keywordflow">if</span> (!approxsolved && dist < approxdif) <a name="l00352"></a>00352 { <a name="l00353"></a>00353 approxdif = dist; <a name="l00354"></a>00354 approxsol = solCheck[i]; <a name="l00355"></a>00355 } <a name="l00356"></a>00356 } <a name="l00357"></a>00357 <a name="l00358"></a>00358 <span class="comment">/* terminate if a solution was found */</span> <a name="l00359"></a>00359 <span class="keywordflow">if</span> (solution != NULL) <a name="l00360"></a>00360 <span class="keywordflow">break</span>; <a name="l00361"></a>00361 } <a name="l00362"></a>00362 <span class="keywordflow">else</span> <a name="l00363"></a>00363 { <a name="l00364"></a>00364 <span class="comment">/* if a collision is found, trim radius to distance from motion to last valid state */</span> <a name="l00365"></a>00365 toTrim = nn_->nearest(nmotion); <a name="l00366"></a>00366 <span class="keywordtype">double</span> newRadius = si_->distance(toTrim-><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#a8d95ca2061c2d38e294a307c0bd86be1" title="The state contained by the motion.">state</a>, lastValid.first); <a name="l00367"></a>00367 <span class="keywordflow">if</span> (newRadius < toTrim->volRadius) <a name="l00368"></a>00368 toTrim-><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#a36a1c4c7f77b7c5c6ee14adc9f5a4b72" title="The radius of the volume associated to this motion.">volRadius</a> = newRadius; <a name="l00369"></a>00369 } <a name="l00370"></a>00370 } <a name="l00371"></a>00371 <a name="l00372"></a>00372 <span class="keywordtype">bool</span> approximate = <span class="keyword">false</span>; <a name="l00373"></a>00373 <span class="keywordflow">if</span> (solution == NULL) <a name="l00374"></a>00374 { <a name="l00375"></a>00375 solution = approxsol; <a name="l00376"></a>00376 approximate = <span class="keyword">true</span>; <a name="l00377"></a>00377 } <a name="l00378"></a>00378 <a name="l00379"></a>00379 <span class="keywordflow">if</span> (solution != NULL) <a name="l00380"></a>00380 { <a name="l00381"></a>00381 <span class="comment">/* construct the solution path */</span> <a name="l00382"></a>00382 std::vector<Motion*> mpath; <a name="l00383"></a>00383 <span class="keywordflow">while</span> (solution != NULL) <a name="l00384"></a>00384 { <a name="l00385"></a>00385 mpath.push_back(solution); <a name="l00386"></a>00386 solution = solution-><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#af3b35ea82a4ce4a771ae72e12c3d8298" title="The parent motion in the exploration tree.">parent</a>; <a name="l00387"></a>00387 } <a name="l00388"></a>00388 <a name="l00389"></a>00389 <span class="comment">/* set the solution path */</span> <a name="l00390"></a>00390 <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="l00391"></a>00391 <span class="keywordflow">for</span> (<span class="keywordtype">int</span> i = mpath.size() - 1 ; i >= 0 ; --i) <a name="l00392"></a>00392 path-><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_->cloneState(mpath[i]->state)); <a name="l00393"></a>00393 goal-><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>(approxdif); <a name="l00394"></a>00394 goal-><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), approximate); <a name="l00395"></a>00395 <a name="l00396"></a>00396 <span class="keywordflow">if</span> (approximate) <a name="l00397"></a>00397 msg_.warn(<span class="stringliteral">"Found approximate solution"</span>); <a name="l00398"></a>00398 } <a name="l00399"></a>00399 <a name="l00400"></a>00400 si_->freeState(xstate); <a name="l00401"></a>00401 <span class="keywordflow">if</span> (rmotion-><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#a8d95ca2061c2d38e294a307c0bd86be1" title="The state contained by the motion.">state</a>) <a name="l00402"></a>00402 si_->freeState(rmotion-><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar_1_1Motion.html#a8d95ca2061c2d38e294a307c0bd86be1" title="The state contained by the motion.">state</a>); <a name="l00403"></a>00403 <span class="keyword">delete</span> rmotion; <a name="l00404"></a>00404 <a name="l00405"></a>00405 msg_.inform(<span class="stringliteral">"Created %u states. Checked %lu rewire options."</span>, nn_->size(), rewireTest); <a name="l00406"></a>00406 <a name="l00407"></a>00407 <span class="keywordflow">return</span> goal-><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="l00408"></a>00408 } <a name="l00409"></a>00409 <a name="l00410"></a><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#ace1165ebcf8b4712422bc53a73ae5dec">00410</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#ace1165ebcf8b4712422bc53a73ae5dec" title="Free the memory allocated by this planner.">ompl::geometric::BallTreeRRTstar::freeMemory</a>(<span class="keywordtype">void</span>) <a name="l00411"></a>00411 { <a name="l00412"></a>00412 <span class="keywordflow">if</span> (nn_) <a name="l00413"></a>00413 { <a name="l00414"></a>00414 std::vector<Motion*> motions; <a name="l00415"></a>00415 nn_->list(motions); <a name="l00416"></a>00416 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < motions.size() ; ++i) <a name="l00417"></a>00417 { <a name="l00418"></a>00418 <span class="keywordflow">if</span> (motions[i]->state) <a name="l00419"></a>00419 si_->freeState(motions[i]->state); <a name="l00420"></a>00420 <span class="keyword">delete</span> motions[i]; <a name="l00421"></a>00421 } <a name="l00422"></a>00422 } <a name="l00423"></a>00423 } <a name="l00424"></a>00424 <a name="l00425"></a><a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a8ea2d6a703307a13272b52588acca8ef">00425</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BallTreeRRTstar.html#a8ea2d6a703307a13272b52588acca8ef" title="Get information about the current run of the motion planner. Repeated calls to this function will upd...">ompl::geometric::BallTreeRRTstar::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> &data)<span class="keyword"> const</span> <a name="l00426"></a>00426 <span class="keyword"></span>{ <a name="l00427"></a>00427 Planner::getPlannerData(data); <a name="l00428"></a>00428 <a name="l00429"></a>00429 std::vector<Motion*> motions; <a name="l00430"></a>00430 <span class="keywordflow">if</span> (nn_) <a name="l00431"></a>00431 nn_->list(motions); <a name="l00432"></a>00432 <a name="l00433"></a>00433 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < motions.size() ; ++i) <a name="l00434"></a>00434 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]->parent ? motions[i]->parent->state : NULL, motions[i]->state); <a name="l00435"></a>00435 } </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"> </span>All</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(1)"><span class="SelectionMark"> </span>Classes</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(2)"><span class="SelectionMark"> </span>Namespaces</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(3)"><span class="SelectionMark"> </span>Functions</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(4)"><span class="SelectionMark"> </span>Variables</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(5)"><span class="SelectionMark"> </span>Typedefs</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(6)"><span class="SelectionMark"> </span>Enumerations</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(7)"><span class="SelectionMark"> </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> • <a href="http://www.cs.rice.edu">Department of Computer Science</a> • <a href="http://www.rice.edu">Rice University</a><br> <div class="gray">Generated on Sun Oct 9 2011 23:04:40 by <a href="http://www.doxygen.org/index.html">doxygen</a> 1.7.4</div> </div> </div> </body> </html>