<!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/rrt/src/pRRT.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_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_890a98498d27a04732c22f6c5c9a3258.html">rrt</a> </li> <li class="navelem"><a class="el" href="dir_dc712aed81dab10025bbf8e2d634c5d5.html">src</a> </li> </ul> </div> </div> <div class="header"> <div class="headertitle"> <div class="title">pRRT.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">* "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">/* Author: Ioan Sucan */</span> <a name="l00036"></a>00036 <a name="l00037"></a>00037 <span class="preprocessor">#include "ompl/geometric/planners/rrt/pRRT.h"</span> <a name="l00038"></a>00038 <span class="preprocessor">#include "ompl/datastructures/NearestNeighborsGNAT.h"</span> <a name="l00039"></a>00039 <span class="preprocessor">#include "ompl/base/GoalSampleableRegion.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 <boost/thread/thread.hpp></span> <a name="l00042"></a>00042 <span class="preprocessor">#include <limits></span> <a name="l00043"></a>00043 <a name="l00044"></a><a class="code" href="classompl_1_1geometric_1_1pRRT.html#aaee4c8111a36505ed11e9d8bf07580b6">00044</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1pRRT.html#aaee4c8111a36505ed11e9d8bf07580b6" title="Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...">ompl::geometric::pRRT::setup</a>(<span class="keywordtype">void</span>) <a name="l00045"></a>00045 { <a name="l00046"></a>00046 <a class="code" href="classompl_1_1geometric_1_1pRRT.html#aaee4c8111a36505ed11e9d8bf07580b6" title="Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...">Planner::setup</a>(); <a name="l00047"></a>00047 <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="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>(maxDistance_); <a name="l00049"></a>00049 <a name="l00050"></a>00050 <span class="keywordflow">if</span> (!nn_) <a name="l00051"></a>00051 nn_.reset(<span class="keyword">new</span> <a class="code" href="classompl_1_1NearestNeighborsGNAT.html" title="Geometric Near-neighbor Access Tree (GNAT), a data structure for nearest neighbor search...">NearestNeighborsGNAT<Motion*></a>()); <a name="l00052"></a>00052 nn_->setDistanceFunction(boost::bind(&pRRT::distanceFunction, <span class="keyword">this</span>, _1, _2)); <a name="l00053"></a>00053 } <a name="l00054"></a>00054 <a name="l00055"></a><a class="code" href="classompl_1_1geometric_1_1pRRT.html#aa98d9d3f5e5665dd057a2dfc02dba703">00055</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1pRRT.html#aa98d9d3f5e5665dd057a2dfc02dba703" title="Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...">ompl::geometric::pRRT::clear</a>(<span class="keywordtype">void</span>) <a name="l00056"></a>00056 { <a name="l00057"></a>00057 Planner::clear(); <a name="l00058"></a>00058 samplerArray_.clear(); <a name="l00059"></a>00059 freeMemory(); <a name="l00060"></a>00060 <span class="keywordflow">if</span> (nn_) <a name="l00061"></a>00061 nn_->clear(); <a name="l00062"></a>00062 } <a name="l00063"></a>00063 <a name="l00064"></a>00064 <span class="keywordtype">void</span> ompl::geometric::pRRT::freeMemory(<span class="keywordtype">void</span>) <a name="l00065"></a>00065 { <a name="l00066"></a>00066 <span class="keywordflow">if</span> (nn_) <a name="l00067"></a>00067 { <a name="l00068"></a>00068 std::vector<Motion*> motions; <a name="l00069"></a>00069 nn_->list(motions); <a name="l00070"></a>00070 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < motions.size() ; ++i) <a name="l00071"></a>00071 { <a name="l00072"></a>00072 <span class="keywordflow">if</span> (motions[i]->state) <a name="l00073"></a>00073 si_->freeState(motions[i]->state); <a name="l00074"></a>00074 <span class="keyword">delete</span> motions[i]; <a name="l00075"></a>00075 } <a name="l00076"></a>00076 } <a name="l00077"></a>00077 } <a name="l00078"></a>00078 <a name="l00079"></a>00079 <span class="keywordtype">void</span> ompl::geometric::pRRT::threadSolve(<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> tid, <span class="keyword">const</span> base::PlannerTerminationCondition &ptc, SolutionInfo *sol) <a name="l00080"></a>00080 { <a name="l00081"></a>00081 checkValidity(); <a name="l00082"></a>00082 base::Goal *goal = pdef_->getGoal().get(); <a name="l00083"></a>00083 base::GoalSampleableRegion *goal_s = <span class="keyword">dynamic_cast<</span>base::GoalSampleableRegion*<span class="keyword">></span>(goal); <a name="l00084"></a>00084 RNG rng; <a name="l00085"></a>00085 <a name="l00086"></a>00086 Motion *rmotion = <span class="keyword">new</span> Motion(si_); <a name="l00087"></a>00087 base::State *rstate = rmotion->state; <a name="l00088"></a>00088 base::State *xstate = si_->allocState(); <a name="l00089"></a>00089 <a name="l00090"></a>00090 <span class="keywordflow">while</span> (sol->solution == NULL && ptc() == <span class="keyword">false</span>) <a name="l00091"></a>00091 { <a name="l00092"></a>00092 <span class="comment">/* sample random state (with goal biasing) */</span> <a name="l00093"></a>00093 <span class="keywordflow">if</span> (goal_s && rng.uniform01() < goalBias_ && goal_s->canSample()) <a name="l00094"></a>00094 goal_s->sampleGoal(rstate); <a name="l00095"></a>00095 <span class="keywordflow">else</span> <a name="l00096"></a>00096 samplerArray_[tid]->sampleUniform(rstate); <a name="l00097"></a>00097 <a name="l00098"></a>00098 <span class="comment">/* find closest state in the tree */</span> <a name="l00099"></a>00099 nnLock_.lock(); <a name="l00100"></a>00100 Motion *nmotion = nn_->nearest(rmotion); <a name="l00101"></a>00101 nnLock_.unlock(); <a name="l00102"></a>00102 base::State *dstate = rstate; <a name="l00103"></a>00103 <a name="l00104"></a>00104 <span class="comment">/* find state to add */</span> <a name="l00105"></a>00105 <span class="keywordtype">double</span> d = si_->distance(nmotion->state, rstate); <a name="l00106"></a>00106 <span class="keywordflow">if</span> (d > maxDistance_) <a name="l00107"></a>00107 { <a name="l00108"></a>00108 si_->getStateSpace()->interpolate(nmotion->state, rstate, maxDistance_ / d, xstate); <a name="l00109"></a>00109 dstate = xstate; <a name="l00110"></a>00110 } <a name="l00111"></a>00111 <a name="l00112"></a>00112 <span class="keywordflow">if</span> (si_->checkMotion(nmotion->state, dstate)) <a name="l00113"></a>00113 { <a name="l00114"></a>00114 <span class="comment">/* create a motion */</span> <a name="l00115"></a>00115 Motion *motion = <span class="keyword">new</span> Motion(si_); <a name="l00116"></a>00116 si_->copyState(motion->state, dstate); <a name="l00117"></a>00117 motion->parent = nmotion; <a name="l00118"></a>00118 <a name="l00119"></a>00119 nnLock_.lock(); <a name="l00120"></a>00120 nn_->add(motion); <a name="l00121"></a>00121 nnLock_.unlock(); <a name="l00122"></a>00122 <a name="l00123"></a>00123 <span class="keywordtype">double</span> dist = 0.0; <a name="l00124"></a>00124 <span class="keywordtype">bool</span> solved = goal->isSatisfied(motion->state, &dist); <a name="l00125"></a>00125 <span class="keywordflow">if</span> (solved) <a name="l00126"></a>00126 { <a name="l00127"></a>00127 sol->lock.lock(); <a name="l00128"></a>00128 sol->approxdif = dist; <a name="l00129"></a>00129 sol->solution = motion; <a name="l00130"></a>00130 sol->lock.unlock(); <a name="l00131"></a>00131 <span class="keywordflow">break</span>; <a name="l00132"></a>00132 } <a name="l00133"></a>00133 <span class="keywordflow">if</span> (dist < sol->approxdif) <a name="l00134"></a>00134 { <a name="l00135"></a>00135 sol->lock.lock(); <a name="l00136"></a>00136 <span class="keywordflow">if</span> (dist < sol->approxdif) <a name="l00137"></a>00137 { <a name="l00138"></a>00138 sol->approxdif = dist; <a name="l00139"></a>00139 sol->approxsol = motion; <a name="l00140"></a>00140 } <a name="l00141"></a>00141 sol->lock.unlock(); <a name="l00142"></a>00142 } <a name="l00143"></a>00143 } <a name="l00144"></a>00144 } <a name="l00145"></a>00145 <a name="l00146"></a>00146 si_->freeState(xstate); <a name="l00147"></a>00147 <span class="keywordflow">if</span> (rmotion->state) <a name="l00148"></a>00148 si_->freeState(rmotion->state); <a name="l00149"></a>00149 <span class="keyword">delete</span> rmotion; <a name="l00150"></a>00150 } <a name="l00151"></a>00151 <a name="l00152"></a><a class="code" href="classompl_1_1geometric_1_1pRRT.html#a3c2e45ebc46e0456bc781223aa66c3c5">00152</a> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1geometric_1_1pRRT.html#a3c2e45ebc46e0456bc781223aa66c3c5" title="Function that can solve the motion planning problem. This function can be called multiple times on th...">ompl::geometric::pRRT::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="l00153"></a>00153 { <a name="l00154"></a>00154 <a class="code" href="classompl_1_1base_1_1GoalRegion.html" title="Definition of a goal region.">base::GoalRegion</a> *goal = <span class="keyword">dynamic_cast<</span><a class="code" href="classompl_1_1base_1_1GoalRegion.html" title="Definition of a goal region.">base::GoalRegion</a>*<span class="keyword">></span>(pdef_->getGoal().get()); <a name="l00155"></a>00155 <a name="l00156"></a>00156 <span class="keywordflow">if</span> (!goal) <a name="l00157"></a>00157 { <a name="l00158"></a>00158 msg_.error(<span class="stringliteral">"Goal undefined"</span>); <a name="l00159"></a>00159 <span class="keywordflow">return</span> <span class="keyword">false</span>; <a name="l00160"></a>00160 } <a name="l00161"></a>00161 <a name="l00162"></a>00162 samplerArray_.resize(threadCount_); <a name="l00163"></a>00163 <a name="l00164"></a>00164 <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="l00165"></a>00165 { <a name="l00166"></a>00166 <a class="code" href="classompl_1_1geometric_1_1pRRT_1_1Motion.html">Motion</a> *motion = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1pRRT_1_1Motion.html">Motion</a>(si_); <a name="l00167"></a>00167 si_->copyState(motion->state, st); <a name="l00168"></a>00168 nn_->add(motion); <a name="l00169"></a>00169 } <a name="l00170"></a>00170 <a name="l00171"></a>00171 <span class="keywordflow">if</span> (nn_->size() == 0) <a name="l00172"></a>00172 { <a name="l00173"></a>00173 msg_.error(<span class="stringliteral">"There are no valid initial states!"</span>); <a name="l00174"></a>00174 <span class="keywordflow">return</span> <span class="keyword">false</span>; <a name="l00175"></a>00175 } <a name="l00176"></a>00176 <a name="l00177"></a>00177 msg_.inform(<span class="stringliteral">"Starting with %u states"</span>, nn_->size()); <a name="l00178"></a>00178 <a name="l00179"></a>00179 <a class="code" href="structompl_1_1geometric_1_1pRRT_1_1SolutionInfo.html">SolutionInfo</a> sol; <a name="l00180"></a>00180 sol.solution = NULL; <a name="l00181"></a>00181 sol.approxsol = NULL; <a name="l00182"></a>00182 sol.approxdif = std::numeric_limits<double>::infinity(); <a name="l00183"></a>00183 <a name="l00184"></a>00184 std::vector<boost::thread*> th(threadCount_); <a name="l00185"></a>00185 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < threadCount_ ; ++i) <a name="l00186"></a>00186 th[i] = <span class="keyword">new</span> boost::thread(boost::bind(&pRRT::threadSolve, <span class="keyword">this</span>, i, ptc, &sol)); <a name="l00187"></a>00187 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < threadCount_ ; ++i) <a name="l00188"></a>00188 { <a name="l00189"></a>00189 th[i]->join(); <a name="l00190"></a>00190 <span class="keyword">delete</span> th[i]; <a name="l00191"></a>00191 } <a name="l00192"></a>00192 <a name="l00193"></a>00193 <span class="keywordtype">bool</span> approximate = <span class="keyword">false</span>; <a name="l00194"></a>00194 <span class="keywordflow">if</span> (sol.solution == NULL) <a name="l00195"></a>00195 { <a name="l00196"></a>00196 sol.solution = sol.approxsol; <a name="l00197"></a>00197 approximate = <span class="keyword">true</span>; <a name="l00198"></a>00198 } <a name="l00199"></a>00199 <a name="l00200"></a>00200 <span class="keywordflow">if</span> (sol.solution != NULL) <a name="l00201"></a>00201 { <a name="l00202"></a>00202 <span class="comment">/* construct the solution path */</span> <a name="l00203"></a>00203 std::vector<Motion*> mpath; <a name="l00204"></a>00204 <span class="keywordflow">while</span> (sol.solution != NULL) <a name="l00205"></a>00205 { <a name="l00206"></a>00206 mpath.push_back(sol.solution); <a name="l00207"></a>00207 sol.solution = sol.solution->parent; <a name="l00208"></a>00208 } <a name="l00209"></a>00209 <a name="l00210"></a>00210 <span class="comment">/* set the solution path */</span> <a name="l00211"></a>00211 <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="l00212"></a>00212 <span class="keywordflow">for</span> (<span class="keywordtype">int</span> i = mpath.size() - 1 ; i >= 0 ; --i) <a name="l00213"></a>00213 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="l00214"></a>00214 <a name="l00215"></a>00215 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>(sol.approxdif); <a name="l00216"></a>00216 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="l00217"></a>00217 <a name="l00218"></a>00218 <span class="keywordflow">if</span> (approximate) <a name="l00219"></a>00219 msg_.warn(<span class="stringliteral">"Found approximate solution"</span>); <a name="l00220"></a>00220 } <a name="l00221"></a>00221 <a name="l00222"></a>00222 msg_.inform(<span class="stringliteral">"Created %u states"</span>, nn_->size()); <a name="l00223"></a>00223 <a name="l00224"></a>00224 <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="l00225"></a>00225 } <a name="l00226"></a>00226 <a name="l00227"></a><a class="code" href="classompl_1_1geometric_1_1pRRT.html#afb65bde371fca3628ef9622ca32e0985">00227</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1pRRT.html#afb65bde371fca3628ef9622ca32e0985" title="Get information about the current run of the motion planner. Repeated calls to this function will upd...">ompl::geometric::pRRT::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="l00228"></a>00228 <span class="keyword"></span>{ <a name="l00229"></a>00229 Planner::getPlannerData(data); <a name="l00230"></a>00230 <a name="l00231"></a>00231 std::vector<Motion*> motions; <a name="l00232"></a>00232 <span class="keywordflow">if</span> (nn_) <a name="l00233"></a>00233 nn_->list(motions); <a name="l00234"></a>00234 <a name="l00235"></a>00235 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < motions.size() ; ++i) <a name="l00236"></a>00236 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="l00237"></a>00237 } <a name="l00238"></a>00238 <a name="l00239"></a><a class="code" href="classompl_1_1geometric_1_1pRRT.html#adfba9c3246fd29e4d72196c417cb1fda">00239</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1pRRT.html#adfba9c3246fd29e4d72196c417cb1fda" title="Set the number of threads the planner should use. Default is 2.">ompl::geometric::pRRT::setThreadCount</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> nthreads) <a name="l00240"></a>00240 { <a name="l00241"></a>00241 assert(nthreads > 0); <a name="l00242"></a>00242 threadCount_ = nthreads; <a name="l00243"></a>00243 } </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>