<!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: Geometric planning for a rigid body in 3D</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> <div class="header"> <div class="headertitle"> <div class="title">Geometric planning for a rigid body in 3D </div> </div> </div> <div class="contents"> <div class="textblock"><p>This tutorial shows how to plan for a rigid body in 3D. We show how to do this in two ways: <a class="el" href="geometricPlanningSE3.html#geometricSimpleSetup">with</a> and <a class="el" href="geometricPlanningSE3.html#withoutGeometricSimpleSetup">without</a> the <a class="el" href="classompl_1_1geometric_1_1SimpleSetup.html" title="Create the set of classes typically needed to solve a geometric problem.">ompl::geometric::SimpleSetup</a> class. The main difference is that in the latter case <a class="el" href="classompl_1_1base_1_1SpaceInformation.html" title="The base class for space information. This contains all the information about the space planning is d...">ompl::base::SpaceInformation</a> and <a class="el" href="classompl_1_1base_1_1ProblemDefinition.html" title="Definition of a problem to be solved. This includes the start state(s) for the system and a goal spec...">ompl::base::ProblemDefinition</a> need to be explicitly instantiated. Furthermore, the planner to be used must be explicitly instantiated as well. The recommended approach is using <a class="el" href="classompl_1_1geometric_1_1SimpleSetup.html" title="Create the set of classes typically needed to solve a geometric problem.">ompl::geometric::SimpleSetup</a> as this is less bug prone and does not limit the functionality of the code in any way. <br/> </p> <dl class="user"><dt><b></b></dt><dd>Setting up geometric planning for a rigid body in 3D requires the following steps:<ul> <li>identify the space we are planning in: SE(3)</li> <li>select a corresponding state space from the available ones, or implement one. For SE(3), the <a class="el" href="classompl_1_1base_1_1SE3StateSpace.html" title="A state space representing SE(3)">ompl::base::SE3StateSpace</a> is appropriate.</li> <li>since SE(3) contains an R<sup>3</sup> component, we need to define bounds.</li> <li>define the notion of state validity.</li> <li>define start states and a goal representation.</li> </ul> </dd></dl> <p>Once these steps are complete, the specification of the problem is conceptually done. The set of classes that allow the instantiation of this specification is shown below.</p> <h2><a class="anchor" id="geometricSimpleSetup"></a> Using the ompl::geometric::SimpleSetup class</h2> Assuming the following namespace definitions: <div class="fragment"><pre class="fragment"><span class="keyword">namespace </span>ob = ompl::base; <span class="keyword">namespace </span>og = ompl::geometric; </pre></div> And a state validity checking function defined like this: <div class="fragment"><pre class="fragment"><span class="keywordtype">bool</span> isStateValid(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">ob::State</a> *state) </pre></div> We first create an instance of the state space we are planning in. <div class="fragment"><pre class="fragment"><span class="keywordtype">void</span> planWithSimpleSetup(<span class="keywordtype">void</span>) { <span class="comment">// construct the state space we are planning in</span> <a class="code" href="classompl_1_1base_1_1StateSpacePtr.html" title="A boost shared pointer wrapper for ompl::base::StateSpace.">ob::StateSpacePtr</a> space(<span class="keyword">new</span> <a class="code" href="classompl_1_1base_1_1SE3StateSpace.html" title="A state space representing SE(3)">ob::SE3StateSpace</a>()); </pre></div> We then set the bounds for the R<sup>3</sup> component of this state space: <div class="fragment"><pre class="fragment"> <a class="code" href="classompl_1_1base_1_1RealVectorBounds.html" title="The lower and upper bounds for an Rn space.">ob::RealVectorBounds</a> bounds(3); bounds.setLow(-1); bounds.setHigh(1); space->as<<a class="code" href="classompl_1_1base_1_1SE3StateSpace.html" title="A state space representing SE(3)">ob::SE3StateSpace</a>>()->setBounds(bounds); </pre></div> Create an instance of <a class="el" href="classompl_1_1geometric_1_1SimpleSetup.html" title="Create the set of classes typically needed to solve a geometric problem.">ompl::geometric::SimpleSetup</a>. Instances of <a class="el" href="classompl_1_1base_1_1SpaceInformation.html" title="The base class for space information. This contains all the information about the space planning is d...">ompl::base::SpaceInformation</a>, and <a class="el" href="classompl_1_1base_1_1ProblemDefinition.html" title="Definition of a problem to be solved. This includes the start state(s) for the system and a goal spec...">ompl::base::ProblemDefinition</a> are created internally. <div class="fragment"><pre class="fragment"> <a class="code" href="classompl_1_1geometric_1_1SimpleSetup.html" title="Create the set of classes typically needed to solve a geometric problem.">og::SimpleSetup</a> ss(space); </pre></div> Set the state validity checker <div class="fragment"><pre class="fragment"> ss.setStateValidityChecker(boost::bind(&isStateValid, _1)); </pre></div> Create a random start state: <div class="fragment"><pre class="fragment"> <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ob::ScopedState<></a> start(space); start.random(); </pre></div> And a random goal state: <div class="fragment"><pre class="fragment"> <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ob::ScopedState<></a> goal(space); goal.random(); </pre></div> Set these states as start and goal for SimpleSetup. <div class="fragment"><pre class="fragment"> ss.setStartAndGoalStates(start, goal); </pre></div> We can now try to solve the problem. This will also trigger a call to <a class="el" href="classompl_1_1geometric_1_1SimpleSetup.html#af7196b38f02c10a5c2fc13261ce29781" title="This method will create the necessary classes for planning. The solve() method will call this functio...">ompl::geometric::SimpleSetup::setup()</a> and create a default instance of a planner, since we have not specified one. Furthermore, <a class="el" href="classompl_1_1base_1_1Planner.html#a948cef726b875317e53ea0f21af40efc" title="Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...">ompl::base::Planner::setup()</a> is called, which in turn calls <a class="el" href="classompl_1_1base_1_1SpaceInformation.html#ac39aa0c4b92e3ca5acfa75eeb56b080f" title="Perform additional setup tasks (run once, before use). If state validity checking resolution has not ...">ompl::base::SpaceInformation::setup()</a>. This chain of calls will lead to computation of runtime parameters such as the state validity checking resolution. This call returns a boolean flag indicating whether a solution has been found within the specified amount of time (in seconds). <div class="fragment"><pre class="fragment"> <span class="keywordtype">bool</span> solved = ss.solve(1.0); </pre></div> If a solution has been found, we can optionally simplify it and the display it <div class="fragment"><pre class="fragment"> <span class="keywordflow">if</span> (solved) { std::cout << <span class="stringliteral">"Found solution:"</span> << std::endl; <span class="comment">// print the path to screen</span> ss.simplifySolution(); ss.getSolutionPath().print(std::cout); } </pre></div> <br/> </p> <h2><a class="anchor" id="withoutGeometricSimpleSetup"></a> Without ompl::geometric::SimpleSetup</h2> Assuming the following namespace definitions: <div class="fragment"><pre class="fragment"><span class="keyword">namespace </span>ob = ompl::base; <span class="keyword">namespace </span>og = ompl::geometric; </pre></div> And a state validity checking function defined like this: <div class="fragment"><pre class="fragment"><span class="keywordtype">bool</span> isStateValid(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">ob::State</a> *state) </pre></div> We first create an instance of the state space we are planning in. <div class="fragment"><pre class="fragment"><span class="keywordtype">void</span> plan(<span class="keywordtype">void</span>) { <span class="comment">// construct the state space we are planning in</span> <a class="code" href="classompl_1_1base_1_1StateSpacePtr.html" title="A boost shared pointer wrapper for ompl::base::StateSpace.">ob::StateSpacePtr</a> space(<span class="keyword">new</span> <a class="code" href="classompl_1_1base_1_1SE3StateSpace.html" title="A state space representing SE(3)">ob::SE3StateSpace</a>()); </pre></div> We then set the bounds for the R<sup>3</sup> component of this state space: <div class="fragment"><pre class="fragment"> <a class="code" href="classompl_1_1base_1_1RealVectorBounds.html" title="The lower and upper bounds for an Rn space.">ob::RealVectorBounds</a> bounds(3); bounds.setLow(-1); bounds.setHigh(1); space->as<<a class="code" href="classompl_1_1base_1_1SE3StateSpace.html" title="A state space representing SE(3)">ob::SE3StateSpace</a>>()->setBounds(bounds); </pre></div> Create an instance of <a class="el" href="classompl_1_1base_1_1SpaceInformation.html" title="The base class for space information. This contains all the information about the space planning is d...">ompl::base::SpaceInformation</a> for the state space <div class="fragment"><pre class="fragment"> <a class="code" href="classompl_1_1base_1_1SpaceInformationPtr.html" title="A boost shared pointer wrapper for ompl::base::SpaceInformation.">ob::SpaceInformationPtr</a> si(<span class="keyword">new</span> <a class="code" href="classompl_1_1base_1_1SpaceInformation.html" title="The base class for space information. This contains all the information about the space planning is d...">ob::SpaceInformation</a>(space)); </pre></div> Set the state validity checker <div class="fragment"><pre class="fragment"> si-><a class="code" href="classompl_1_1base_1_1SpaceInformation.html#a0449ec0893e02aca2bdfc63323b624e5" title="Set the instance of the state validity checker to use. Parallel implementations of planners assume th...">setStateValidityChecker</a>(boost::bind(&isStateValid, _1)); </pre></div> Create a random start state: <div class="fragment"><pre class="fragment"> <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ob::ScopedState<></a> start(space); start.random(); </pre></div> And a random goal state: <div class="fragment"><pre class="fragment"> <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ob::ScopedState<></a> goal(space); goal.random(); </pre></div> Create an instance of <a class="el" href="classompl_1_1base_1_1ProblemDefinition.html" title="Definition of a problem to be solved. This includes the start state(s) for the system and a goal spec...">ompl::base::ProblemDefinition</a> <div class="fragment"><pre class="fragment"> <a class="code" href="classompl_1_1base_1_1ProblemDefinitionPtr.html" title="A boost shared pointer wrapper for ompl::base::ProblemDefinition.">ob::ProblemDefinitionPtr</a> pdef(<span class="keyword">new</span> <a class="code" href="classompl_1_1base_1_1ProblemDefinition.html" title="Definition of a problem to be solved. This includes the start state(s) for the system and a goal spec...">ob::ProblemDefinition</a>(si)); </pre></div> Set the start and goal states for the problem definition. <div class="fragment"><pre class="fragment"> pdef->setStartAndGoalStates(start, goal); </pre></div> Create an instance of a planner <div class="fragment"><pre class="fragment"> <a class="code" href="classompl_1_1base_1_1PlannerPtr.html" title="A boost shared pointer wrapper for ompl::base::Planner.">ob::PlannerPtr</a> planner(<span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1RRTConnect.html" title="RRT-Connect (RRTConnect)">og::RRTConnect</a>(si)); </pre></div> Tell the planner which problem we are interested in solving <div class="fragment"><pre class="fragment"> planner->setProblemDefinition(pdef); </pre></div> Make sure all the settings for the space and planner are in order. This will also lead to the runtime computation of the state validity checking resolution. <div class="fragment"><pre class="fragment"> planner->setup(); </pre></div> We can now try to solve the problem. This call returns a boolean flag indicating whether a solution has been found within the specified amount of time (in seconds). <div class="fragment"><pre class="fragment"> <span class="keywordtype">bool</span> solved = planner->solve(1.0); </pre></div> If a solution has been found, we display it. Simplification could be done, but we would need to create an instance of <a class="el" href="classompl_1_1geometric_1_1PathSimplifier.html" title="This class contains routines that attempt to simplify geometric paths.">ompl::geometric::PathSimplifier</a>. <div class="fragment"><pre class="fragment"> <span class="keywordflow">if</span> (solved) { <span class="comment">// get the goal representation from the problem definition (not the same as the goal state)</span> <span class="comment">// and inquire about the found path</span> <a class="code" href="classompl_1_1base_1_1PathPtr.html" title="A boost shared pointer wrapper for ompl::base::Path.">ob::PathPtr</a> path = pdef->getGoal()->getSolutionPath(); std::cout << <span class="stringliteral">"Found solution:"</span> << std::endl; <span class="comment">// print the path to screen</span> path->print(std::cout); } </pre></div> <br/> </p> </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:41 by <a href="http://www.doxygen.org/index.html">doxygen</a> 1.7.4</div> </div> </div> </body> </html>