<!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/base/src/ProblemDefinition.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_40bc83a902349ad67ef9d1cb49964511.html">base</a> </li> <li class="navelem"><a class="el" href="dir_638c121d1114340bf3e84a5e9d67e9f2.html">src</a> </li> </ul> </div> </div> <div class="header"> <div class="headertitle"> <div class="title">ProblemDefinition.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) 2010, 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">/* Author: Ioan Sucan */</span> <a name="l00036"></a>00036 <a name="l00037"></a>00037 <span class="preprocessor">#include "ompl/base/ProblemDefinition.h"</span> <a name="l00038"></a>00038 <span class="preprocessor">#include "ompl/base/GoalState.h"</span> <a name="l00039"></a>00039 <span class="preprocessor">#include "ompl/base/GoalStates.h"</span> <a name="l00040"></a>00040 <span class="preprocessor">#include "ompl/control/SpaceInformation.h"</span> <a name="l00041"></a>00041 <span class="preprocessor">#include "ompl/control/PathControl.h"</span> <a name="l00042"></a>00042 <span class="preprocessor">#include <sstream></span> <a name="l00043"></a>00043 <a name="l00044"></a><a class="code" href="classompl_1_1base_1_1ProblemDefinition.html#a9ab5830fd9366be606349ea1885a3695">00044</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1base_1_1ProblemDefinition.html#a9ab5830fd9366be606349ea1885a3695" title="In the simplest case possible, we have a single starting state and a single goal state.">ompl::base::ProblemDefinition::setStartAndGoalStates</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *start, <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *goal, <span class="keyword">const</span> <span class="keywordtype">double</span> threshold) <a name="l00045"></a>00045 { <a name="l00046"></a>00046 <a class="code" href="classompl_1_1base_1_1ProblemDefinition.html#ac21b7750c81186c872485cc4231a9fd0" title="Clear all start states (memory is freed)">clearStartStates</a>(); <a name="l00047"></a>00047 <a class="code" href="classompl_1_1base_1_1ProblemDefinition.html#a3120682d036099f68fd26805fee0736d" title="Add a start state. The state is copied.">addStartState</a>(start); <a name="l00048"></a>00048 <a class="code" href="classompl_1_1base_1_1ProblemDefinition.html#a5cd271339a73f61bc1b13588a92a36d7" title="A simple form of setting the goal. This is called by setStartAndGoalStates(). A more general form is ...">setGoalState</a>(goal, threshold); <a name="l00049"></a>00049 } <a name="l00050"></a>00050 <a name="l00051"></a><a class="code" href="classompl_1_1base_1_1ProblemDefinition.html#a5cd271339a73f61bc1b13588a92a36d7">00051</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1base_1_1ProblemDefinition.html#a5cd271339a73f61bc1b13588a92a36d7" title="A simple form of setting the goal. This is called by setStartAndGoalStates(). A more general form is ...">ompl::base::ProblemDefinition::setGoalState</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *goal, <span class="keyword">const</span> <span class="keywordtype">double</span> threshold) <a name="l00052"></a>00052 { <a name="l00053"></a>00053 clearGoal(); <a name="l00054"></a>00054 <a class="code" href="classompl_1_1base_1_1GoalState.html" title="Definition of a goal state.">GoalState</a> *gs = <span class="keyword">new</span> <a class="code" href="classompl_1_1base_1_1GoalState.html" title="Definition of a goal state.">GoalState</a>(si_); <a name="l00055"></a>00055 gs-><a class="code" href="classompl_1_1base_1_1GoalState.html#a4ffb6cc48229964b4cc86066dda3e649" title="Set the goal state.">setState</a>(goal); <a name="l00056"></a>00056 gs-><a class="code" href="classompl_1_1base_1_1GoalRegion.html#a66faea81767a0772924082816b88e63f" title="Set the distance to the goal that is allowed for a state to be considered in the goal region...">setThreshold</a>(threshold); <a name="l00057"></a>00057 setGoal(<a class="code" href="classompl_1_1base_1_1GoalPtr.html" title="A boost shared pointer wrapper for ompl::base::Goal.">GoalPtr</a>(gs)); <a name="l00058"></a>00058 } <a name="l00059"></a>00059 <a name="l00060"></a><a class="code" href="classompl_1_1base_1_1ProblemDefinition.html#a8b292f3df6545bb90fbeff72e11f0b59">00060</a> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1base_1_1ProblemDefinition.html#a8b292f3df6545bb90fbeff72e11f0b59" title="Check whether a specified starting state is already included in the problem definition and optionally...">ompl::base::ProblemDefinition::hasStartState</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *state, <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> *startIndex) <a name="l00061"></a>00061 { <a name="l00062"></a>00062 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < startStates_.size() ; ++i) <a name="l00063"></a>00063 <span class="keywordflow">if</span> (si_->equalStates(state, startStates_[i])) <a name="l00064"></a>00064 { <a name="l00065"></a>00065 <span class="keywordflow">if</span> (startIndex) <a name="l00066"></a>00066 *startIndex = i; <a name="l00067"></a>00067 <span class="keywordflow">return</span> <span class="keyword">true</span>; <a name="l00068"></a>00068 } <a name="l00069"></a>00069 <span class="keywordflow">return</span> <span class="keyword">false</span>; <a name="l00070"></a>00070 } <a name="l00071"></a>00071 <a name="l00072"></a><a class="code" href="classompl_1_1base_1_1ProblemDefinition.html#a4afcbeee27af97ac5eefdc40ea8ecfbe">00072</a> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1base_1_1ProblemDefinition.html#a4afcbeee27af97ac5eefdc40ea8ecfbe" title="Helper function for fixInvalidInputStates(). Attempts to fix an individual state.">ompl::base::ProblemDefinition::fixInvalidInputState</a>(<a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *state, <span class="keywordtype">double</span> dist, <span class="keywordtype">bool</span> start, <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> attempts) <a name="l00073"></a>00073 { <a name="l00074"></a>00074 <span class="keywordtype">bool</span> result = <span class="keyword">false</span>; <a name="l00075"></a>00075 <a name="l00076"></a>00076 <span class="keywordtype">bool</span> b = si_->satisfiesBounds(state); <a name="l00077"></a>00077 <span class="keywordtype">bool</span> v = <span class="keyword">false</span>; <a name="l00078"></a>00078 <span class="keywordflow">if</span> (b) <a name="l00079"></a>00079 { <a name="l00080"></a>00080 v = si_->isValid(state); <a name="l00081"></a>00081 <span class="keywordflow">if</span> (!v) <a name="l00082"></a>00082 msg_.debug(<span class="stringliteral">"%s state is not valid"</span>, start ? <span class="stringliteral">"Start"</span> : <span class="stringliteral">"Goal"</span>); <a name="l00083"></a>00083 } <a name="l00084"></a>00084 <span class="keywordflow">else</span> <a name="l00085"></a>00085 msg_.debug(<span class="stringliteral">"%s state is not within space bounds"</span>, start ? <span class="stringliteral">"Start"</span> : <span class="stringliteral">"Goal"</span>); <a name="l00086"></a>00086 <a name="l00087"></a>00087 <span class="keywordflow">if</span> (!b || !v) <a name="l00088"></a>00088 { <a name="l00089"></a>00089 std::stringstream ss; <a name="l00090"></a>00090 si_->printState(state, ss); <a name="l00091"></a>00091 ss << <span class="stringliteral">" within distance "</span> << dist; <a name="l00092"></a>00092 msg_.debug(<span class="stringliteral">"Attempting to fix %s state %s"</span>, start ? <span class="stringliteral">"start"</span> : <span class="stringliteral">"goal"</span>, ss.str().c_str()); <a name="l00093"></a>00093 <a name="l00094"></a>00094 <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *temp = si_->allocState(); <a name="l00095"></a>00095 <span class="keywordflow">if</span> (si_->searchValidNearby(temp, state, dist, attempts)) <a name="l00096"></a>00096 { <a name="l00097"></a>00097 si_->copyState(state, temp); <a name="l00098"></a>00098 result = <span class="keyword">true</span>; <a name="l00099"></a>00099 } <a name="l00100"></a>00100 <span class="keywordflow">else</span> <a name="l00101"></a>00101 msg_.warn(<span class="stringliteral">"Unable to fix %s state"</span>, start ? <span class="stringliteral">"start"</span> : <span class="stringliteral">"goal"</span>); <a name="l00102"></a>00102 si_->freeState(temp); <a name="l00103"></a>00103 } <a name="l00104"></a>00104 <a name="l00105"></a>00105 <span class="keywordflow">return</span> result; <a name="l00106"></a>00106 } <a name="l00107"></a>00107 <a name="l00108"></a><a class="code" href="classompl_1_1base_1_1ProblemDefinition.html#a74aa8792df6065a84f1b602db53d108c">00108</a> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1base_1_1ProblemDefinition.html#a74aa8792df6065a84f1b602db53d108c" title="Many times the start or goal state will barely touch an obstacle. In this case, we may want to automa...">ompl::base::ProblemDefinition::fixInvalidInputStates</a>(<span class="keywordtype">double</span> distStart, <span class="keywordtype">double</span> distGoal, <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> attempts) <a name="l00109"></a>00109 { <a name="l00110"></a>00110 <span class="keywordtype">bool</span> result = <span class="keyword">true</span>; <a name="l00111"></a>00111 <a name="l00112"></a>00112 <span class="comment">// fix start states</span> <a name="l00113"></a>00113 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < startStates_.size() ; ++i) <a name="l00114"></a>00114 <span class="keywordflow">if</span> (!fixInvalidInputState(startStates_[i], distStart, <span class="keyword">true</span>, attempts)) <a name="l00115"></a>00115 result = <span class="keyword">false</span>; <a name="l00116"></a>00116 <a name="l00117"></a>00117 <span class="comment">// fix goal state</span> <a name="l00118"></a>00118 <a class="code" href="classompl_1_1base_1_1GoalState.html" title="Definition of a goal state.">GoalState</a> *goal = <span class="keyword">dynamic_cast<</span><a class="code" href="classompl_1_1base_1_1GoalState.html" title="Definition of a goal state.">GoalState</a>*<span class="keyword">></span>(goal_.get()); <a name="l00119"></a>00119 <span class="keywordflow">if</span> (goal) <a name="l00120"></a>00120 { <a name="l00121"></a>00121 <span class="keywordflow">if</span> (!fixInvalidInputState(goal-><a class="code" href="classompl_1_1base_1_1GoalState.html#ad35d1a357b23dae86eb5e34f0cc92670" title="The goal state.">state</a>, distGoal, <span class="keyword">false</span>, attempts)) <a name="l00122"></a>00122 result = <span class="keyword">false</span>; <a name="l00123"></a>00123 } <a name="l00124"></a>00124 <a name="l00125"></a>00125 <span class="comment">// fix goal state</span> <a name="l00126"></a>00126 <a class="code" href="classompl_1_1base_1_1GoalStates.html" title="Definition of a set of goal states.">GoalStates</a> *goals = <span class="keyword">dynamic_cast<</span><a class="code" href="classompl_1_1base_1_1GoalStates.html" title="Definition of a set of goal states.">GoalStates</a>*<span class="keyword">></span>(goal_.get()); <a name="l00127"></a>00127 <span class="keywordflow">if</span> (goals) <a name="l00128"></a>00128 { <a name="l00129"></a>00129 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < goals-><a class="code" href="classompl_1_1base_1_1GoalStates.html#a34ef4d90da89228d610ef169ec0c81e1" title="The goal states. Only ones that are valid are considered by the motion planner.">states</a>.size() ; ++i) <a name="l00130"></a>00130 <span class="keywordflow">if</span> (!fixInvalidInputState(goals-><a class="code" href="classompl_1_1base_1_1GoalStates.html#a34ef4d90da89228d610ef169ec0c81e1" title="The goal states. Only ones that are valid are considered by the motion planner.">states</a>[i], distGoal, <span class="keyword">false</span>, attempts)) <a name="l00131"></a>00131 result = <span class="keyword">false</span>; <a name="l00132"></a>00132 } <a name="l00133"></a>00133 <a name="l00134"></a>00134 <span class="keywordflow">return</span> result; <a name="l00135"></a>00135 } <a name="l00136"></a>00136 <a name="l00137"></a><a class="code" href="classompl_1_1base_1_1ProblemDefinition.html#a817035d12f2b66e0cb9bbf339b56921e">00137</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1base_1_1ProblemDefinition.html#a817035d12f2b66e0cb9bbf339b56921e" title="Get all the input states. This includes start states and states that are part of goal regions that ca...">ompl::base::ProblemDefinition::getInputStates</a>(std::vector<const State*> &states)<span class="keyword"> const</span> <a name="l00138"></a>00138 <span class="keyword"></span>{ <a name="l00139"></a>00139 states.clear(); <a name="l00140"></a>00140 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < startStates_.size() ; ++i) <a name="l00141"></a>00141 states.push_back(startStates_[i]); <a name="l00142"></a>00142 <a name="l00143"></a>00143 <a class="code" href="classompl_1_1base_1_1GoalState.html" title="Definition of a goal state.">GoalState</a> *goal = <span class="keyword">dynamic_cast<</span><a class="code" href="classompl_1_1base_1_1GoalState.html" title="Definition of a goal state.">GoalState</a>*<span class="keyword">></span>(goal_.get()); <a name="l00144"></a>00144 <span class="keywordflow">if</span> (goal) <a name="l00145"></a>00145 states.push_back(goal-><a class="code" href="classompl_1_1base_1_1GoalState.html#ad35d1a357b23dae86eb5e34f0cc92670" title="The goal state.">state</a>); <a name="l00146"></a>00146 <a name="l00147"></a>00147 <a class="code" href="classompl_1_1base_1_1GoalStates.html" title="Definition of a set of goal states.">GoalStates</a> *goals = <span class="keyword">dynamic_cast<</span><a class="code" href="classompl_1_1base_1_1GoalStates.html" title="Definition of a set of goal states.">GoalStates</a>*<span class="keyword">></span>(goal_.get()); <a name="l00148"></a>00148 <span class="keywordflow">if</span> (goals) <a name="l00149"></a>00149 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < goals-><a class="code" href="classompl_1_1base_1_1GoalStates.html#a34ef4d90da89228d610ef169ec0c81e1" title="The goal states. Only ones that are valid are considered by the motion planner.">states</a>.size() ; ++i) <a name="l00150"></a>00150 states.push_back(goals-><a class="code" href="classompl_1_1base_1_1GoalStates.html#a34ef4d90da89228d610ef169ec0c81e1" title="The goal states. Only ones that are valid are considered by the motion planner.">states</a>[i]); <a name="l00151"></a>00151 } <a name="l00152"></a>00152 <a name="l00153"></a><a class="code" href="classompl_1_1base_1_1ProblemDefinition.html#a45aac71e8031a0cda6e38efef737e5c3">00153</a> <a class="code" href="classompl_1_1base_1_1PathPtr.html" title="A boost shared pointer wrapper for ompl::base::Path.">ompl::base::PathPtr</a> <a class="code" href="classompl_1_1base_1_1ProblemDefinition.html#a45aac71e8031a0cda6e38efef737e5c3" title="Check if a straight line path is valid. If it is, return an instance of a path that represents the st...">ompl::base::ProblemDefinition::isStraightLinePathValid</a>(<span class="keywordtype">void</span>)<span class="keyword"> const</span> <a name="l00154"></a>00154 <span class="keyword"></span>{ <a name="l00155"></a>00155 <a class="code" href="classompl_1_1base_1_1PathPtr.html" title="A boost shared pointer wrapper for ompl::base::Path.">PathPtr</a> path; <a name="l00156"></a>00156 <span class="keywordflow">if</span> (<a class="code" href="classompl_1_1control_1_1SpaceInformationPtr.html" title="A boost shared pointer wrapper for ompl::control::SpaceInformation.">control::SpaceInformationPtr</a> sic = boost::dynamic_pointer_cast<control::SpaceInformation, SpaceInformation>(si_)) <a name="l00157"></a>00157 { <a name="l00158"></a>00158 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> startIndex; <a name="l00159"></a>00159 <span class="keywordflow">if</span> (isTrivial(&startIndex, NULL)) <a name="l00160"></a>00160 { <a name="l00161"></a>00161 <a class="code" href="classompl_1_1control_1_1PathControl.html" title="Definition of a control path.">control::PathControl</a> *pc = <span class="keyword">new</span> <a class="code" href="classompl_1_1control_1_1PathControl.html" title="Definition of a control path.">control::PathControl</a>(sic); <a name="l00162"></a>00162 pc-><a class="code" href="classompl_1_1control_1_1PathControl.html#a2bd25b55f0de06ecac55cabb4b90a606" title="The list of states that make up the path.">states</a>.push_back(sic->cloneState(startStates_[startIndex])); <a name="l00163"></a>00163 pc-><a class="code" href="classompl_1_1control_1_1PathControl.html#a2bd25b55f0de06ecac55cabb4b90a606" title="The list of states that make up the path.">states</a>.push_back(sic->cloneState(startStates_[startIndex])); <a name="l00164"></a>00164 pc-><a class="code" href="classompl_1_1control_1_1PathControl.html#a69d77e39906c91394470f9e988b4944a" title="The control applied at each state. This array contains one element less than the list of states...">controls</a>.push_back(sic->allocControl()); <a name="l00165"></a>00165 sic->nullControl(pc-><a class="code" href="classompl_1_1control_1_1PathControl.html#a69d77e39906c91394470f9e988b4944a" title="The control applied at each state. This array contains one element less than the list of states...">controls</a>.back()); <a name="l00166"></a>00166 pc-><a class="code" href="classompl_1_1control_1_1PathControl.html#a3a8b0e7b00684789eac7d51d65d81b49" title="The duration of the control applied at each state. This array contains one element less than the list...">controlDurations</a>.push_back(0); <a name="l00167"></a>00167 path.reset(pc); <a name="l00168"></a>00168 } <a name="l00169"></a>00169 <span class="keywordflow">else</span> <a name="l00170"></a>00170 { <a name="l00171"></a>00171 <a class="code" href="classompl_1_1control_1_1Control.html" title="Definition of an abstract control.">control::Control</a> *nc = sic->allocControl(); <a name="l00172"></a>00172 <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *result1 = sic->allocState(); <a name="l00173"></a>00173 <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *result2 = sic->allocState(); <a name="l00174"></a>00174 sic->nullControl(nc); <a name="l00175"></a>00175 <a name="l00176"></a>00176 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> k = 0 ; k < startStates_.size() && !path ; ++k) <a name="l00177"></a>00177 { <a name="l00178"></a>00178 <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *start = startStates_[k]; <a name="l00179"></a>00179 <span class="keywordflow">if</span> (start && si_->isValid(start) && si_->satisfiesBounds(start)) <a name="l00180"></a>00180 { <a name="l00181"></a>00181 sic->copyState(result1, start); <a name="l00182"></a>00182 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < sic->getMaxControlDuration() && !path ; ++i) <a name="l00183"></a>00183 <span class="keywordflow">if</span> (sic->propagateWhileValid(result1, nc, 1, result2)) <a name="l00184"></a>00184 { <a name="l00185"></a>00185 <span class="keywordflow">if</span> (goal_->isSatisfied(result2)) <a name="l00186"></a>00186 { <a name="l00187"></a>00187 <a class="code" href="classompl_1_1control_1_1PathControl.html" title="Definition of a control path.">control::PathControl</a> *pc = <span class="keyword">new</span> <a class="code" href="classompl_1_1control_1_1PathControl.html" title="Definition of a control path.">control::PathControl</a>(sic); <a name="l00188"></a>00188 pc-><a class="code" href="classompl_1_1control_1_1PathControl.html#a2bd25b55f0de06ecac55cabb4b90a606" title="The list of states that make up the path.">states</a>.push_back(sic->cloneState(start)); <a name="l00189"></a>00189 pc-><a class="code" href="classompl_1_1control_1_1PathControl.html#a2bd25b55f0de06ecac55cabb4b90a606" title="The list of states that make up the path.">states</a>.push_back(sic->cloneState(result2)); <a name="l00190"></a>00190 pc-><a class="code" href="classompl_1_1control_1_1PathControl.html#a69d77e39906c91394470f9e988b4944a" title="The control applied at each state. This array contains one element less than the list of states...">controls</a>.push_back(sic->cloneControl(nc)); <a name="l00191"></a>00191 pc-><a class="code" href="classompl_1_1control_1_1PathControl.html#a3a8b0e7b00684789eac7d51d65d81b49" title="The duration of the control applied at each state. This array contains one element less than the list...">controlDurations</a>.push_back(i + 1); <a name="l00192"></a>00192 path.reset(pc); <a name="l00193"></a>00193 <span class="keywordflow">break</span>; <a name="l00194"></a>00194 } <a name="l00195"></a>00195 std::swap(result1, result2); <a name="l00196"></a>00196 } <a name="l00197"></a>00197 } <a name="l00198"></a>00198 } <a name="l00199"></a>00199 sic->freeState(result1); <a name="l00200"></a>00200 sic->freeState(result2); <a name="l00201"></a>00201 sic->freeControl(nc); <a name="l00202"></a>00202 } <a name="l00203"></a>00203 } <a name="l00204"></a>00204 <span class="keywordflow">else</span> <a name="l00205"></a>00205 { <a name="l00206"></a>00206 std::vector<const State*> states; <a name="l00207"></a>00207 <a class="code" href="classompl_1_1base_1_1GoalState.html" title="Definition of a goal state.">GoalState</a> *goal = <span class="keyword">dynamic_cast<</span><a class="code" href="classompl_1_1base_1_1GoalState.html" title="Definition of a goal state.">GoalState</a>*<span class="keyword">></span>(goal_.get()); <a name="l00208"></a>00208 <span class="keywordflow">if</span> (goal) <a name="l00209"></a>00209 <span class="keywordflow">if</span> (si_->isValid(goal-><a class="code" href="classompl_1_1base_1_1GoalState.html#ad35d1a357b23dae86eb5e34f0cc92670" title="The goal state.">state</a>) && si_->satisfiesBounds(goal-><a class="code" href="classompl_1_1base_1_1GoalState.html#ad35d1a357b23dae86eb5e34f0cc92670" title="The goal state.">state</a>)) <a name="l00210"></a>00210 states.push_back(goal-><a class="code" href="classompl_1_1base_1_1GoalState.html#ad35d1a357b23dae86eb5e34f0cc92670" title="The goal state.">state</a>); <a name="l00211"></a>00211 <a class="code" href="classompl_1_1base_1_1GoalStates.html" title="Definition of a set of goal states.">GoalStates</a> *goals = <span class="keyword">dynamic_cast<</span><a class="code" href="classompl_1_1base_1_1GoalStates.html" title="Definition of a set of goal states.">GoalStates</a>*<span class="keyword">></span>(goal_.get()); <a name="l00212"></a>00212 <span class="keywordflow">if</span> (goals) <a name="l00213"></a>00213 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < goals-><a class="code" href="classompl_1_1base_1_1GoalStates.html#a34ef4d90da89228d610ef169ec0c81e1" title="The goal states. Only ones that are valid are considered by the motion planner.">states</a>.size() ; ++i) <a name="l00214"></a>00214 <span class="keywordflow">if</span> (si_->isValid(goals-><a class="code" href="classompl_1_1base_1_1GoalStates.html#a34ef4d90da89228d610ef169ec0c81e1" title="The goal states. Only ones that are valid are considered by the motion planner.">states</a>[i]) && si_->satisfiesBounds(goals-><a class="code" href="classompl_1_1base_1_1GoalStates.html#a34ef4d90da89228d610ef169ec0c81e1" title="The goal states. Only ones that are valid are considered by the motion planner.">states</a>[i])) <a name="l00215"></a>00215 states.push_back(goals-><a class="code" href="classompl_1_1base_1_1GoalStates.html#a34ef4d90da89228d610ef169ec0c81e1" title="The goal states. Only ones that are valid are considered by the motion planner.">states</a>[i]); <a name="l00216"></a>00216 <a name="l00217"></a>00217 <span class="keywordflow">if</span> (states.empty()) <a name="l00218"></a>00218 { <a name="l00219"></a>00219 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> startIndex; <a name="l00220"></a>00220 <span class="keywordflow">if</span> (isTrivial(&startIndex)) <a name="l00221"></a>00221 { <a name="l00222"></a>00222 <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html" title="Definition of a geometric path.">geometric::PathGeometric</a> *pg = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html" title="Definition of a geometric path.">geometric::PathGeometric</a>(si_); <a name="l00223"></a>00223 pg-><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(startStates_[startIndex])); <a name="l00224"></a>00224 pg-><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(startStates_[startIndex])); <a name="l00225"></a>00225 path.reset(pg); <a name="l00226"></a>00226 } <a name="l00227"></a>00227 } <a name="l00228"></a>00228 <span class="keywordflow">else</span> <a name="l00229"></a>00229 { <a name="l00230"></a>00230 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < startStates_.size() && !path ; ++i) <a name="l00231"></a>00231 { <a name="l00232"></a>00232 <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *start = startStates_[i]; <a name="l00233"></a>00233 <span class="keywordflow">if</span> (start && si_->isValid(start) && si_->satisfiesBounds(start)) <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> j = 0 ; j < states.size() && !path ; ++j) <a name="l00236"></a>00236 <span class="keywordflow">if</span> (si_->checkMotion(start, states[j])) <a name="l00237"></a>00237 { <a name="l00238"></a>00238 <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html" title="Definition of a geometric path.">geometric::PathGeometric</a> *pg = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html" title="Definition of a geometric path.">geometric::PathGeometric</a>(si_); <a name="l00239"></a>00239 pg-><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(start)); <a name="l00240"></a>00240 pg-><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(states[j])); <a name="l00241"></a>00241 path.reset(pg); <a name="l00242"></a>00242 <span class="keywordflow">break</span>; <a name="l00243"></a>00243 } <a name="l00244"></a>00244 } <a name="l00245"></a>00245 } <a name="l00246"></a>00246 } <a name="l00247"></a>00247 } <a name="l00248"></a>00248 <a name="l00249"></a>00249 <span class="keywordflow">return</span> path; <a name="l00250"></a>00250 } <a name="l00251"></a>00251 <a name="l00252"></a><a class="code" href="classompl_1_1base_1_1ProblemDefinition.html#ae8c6ae8979fb163fd01387c4a9f8fd2b">00252</a> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1base_1_1ProblemDefinition.html#ae8c6ae8979fb163fd01387c4a9f8fd2b" title="A problem is trivial if a given starting state already in the goal region, so we need no motion plann...">ompl::base::ProblemDefinition::isTrivial</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> *startIndex, <span class="keywordtype">double</span> *distance)<span class="keyword"> const</span> <a name="l00253"></a>00253 <span class="keyword"></span>{ <a name="l00254"></a>00254 <span class="keywordflow">if</span> (!goal_) <a name="l00255"></a>00255 { <a name="l00256"></a>00256 msg_.error(<span class="stringliteral">"Goal undefined"</span>); <a name="l00257"></a>00257 <span class="keywordflow">return</span> <span class="keyword">false</span>; <a name="l00258"></a>00258 } <a name="l00259"></a>00259 <a name="l00260"></a>00260 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < startStates_.size() ; ++i) <a name="l00261"></a>00261 { <a name="l00262"></a>00262 <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *start = startStates_[i]; <a name="l00263"></a>00263 <span class="keywordflow">if</span> (start && si_->isValid(start) && si_->satisfiesBounds(start)) <a name="l00264"></a>00264 { <a name="l00265"></a>00265 <span class="keywordtype">double</span> dist; <a name="l00266"></a>00266 <span class="keywordflow">if</span> (goal_->isSatisfied(start, &dist)) <a name="l00267"></a>00267 { <a name="l00268"></a>00268 <span class="keywordflow">if</span> (startIndex) <a name="l00269"></a>00269 *startIndex = i; <a name="l00270"></a>00270 <span class="keywordflow">if</span> (distance) <a name="l00271"></a>00271 *distance = dist; <a name="l00272"></a>00272 <span class="keywordflow">return</span> <span class="keyword">true</span>; <a name="l00273"></a>00273 } <a name="l00274"></a>00274 } <a name="l00275"></a>00275 <span class="keywordflow">else</span> <a name="l00276"></a>00276 { <a name="l00277"></a>00277 msg_.error(<span class="stringliteral">"Initial state is in collision!"</span>); <a name="l00278"></a>00278 } <a name="l00279"></a>00279 } <a name="l00280"></a>00280 <a name="l00281"></a>00281 <span class="keywordflow">return</span> <span class="keyword">false</span>; <a name="l00282"></a>00282 } <a name="l00283"></a>00283 <a name="l00284"></a><a class="code" href="classompl_1_1base_1_1ProblemDefinition.html#a76cd24bc1d239ffa674967c004c7df20">00284</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1base_1_1ProblemDefinition.html#a76cd24bc1d239ffa674967c004c7df20" title="Print information about the start and goal states.">ompl::base::ProblemDefinition::print</a>(std::ostream &out)<span class="keyword"> const</span> <a name="l00285"></a>00285 <span class="keyword"></span>{ <a name="l00286"></a>00286 out << <span class="stringliteral">"Start states:"</span> << std::endl; <a name="l00287"></a>00287 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < startStates_.size() ; ++i) <a name="l00288"></a>00288 si_->printState(startStates_[i], out); <a name="l00289"></a>00289 <span class="keywordflow">if</span> (goal_) <a name="l00290"></a>00290 goal_->print(out); <a name="l00291"></a>00291 <span class="keywordflow">else</span> <a name="l00292"></a>00292 out << <span class="stringliteral">"Goal = NULL"</span> << std::endl; <a name="l00293"></a>00293 } </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:39 by <a href="http://www.doxygen.org/index.html">doxygen</a> 1.7.4</div> </div> </div> </body> </html>