Sophie

Sophie

distrib > Fedora > 14 > x86_64 > media > updates > by-pkgid > e7618febbb9cbed15bb79e326774c050 > files > 503

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

<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta http-equiv="Content-Type" content="text/xhtml; charset=UTF-8"/>
<title>OMPL: ompl::base::ProblemDefinition Class Reference</title>
<meta name="author" content="Ioan A. Șucan, Mark Moll, Lydia E. Kavraki">
<link rel="stylesheet" href="../css/screen.css" type="text/css" media="screen, projection">
<link rel="stylesheet" href="../css/print.css" type="text/css" media="print">
<!--[if lt IE 7]>
<script type="text/javascript" src="../js/jquery/jquery.js"></script>
<script type="text/javascript" src="../js/jquery/jquery.dropdown.js"></script>
<![endif]-->
<script type="text/javaScript" src="search/search.js"></script>
<script type="text/javascript">
  var _gaq = _gaq || [];
  _gaq.push(['_setAccount', 'UA-9156598-2']);
  _gaq.push(['_trackPageview']);
  (function() {
    var ga = document.createElement('script'); ga.type = 'text/javascript'; ga.async = true;
    ga.src = ('https:' == document.location.protocol ? 'https://ssl' : 'http://www') + '.google-analytics.com/ga.js';
    var s = document.getElementsByTagName('script')[0]; s.parentNode.insertBefore(ga, s);
  })();
</script>
</head>
<body onload='searchBox.OnSelectItem(0);'>
<script type="text/javascript"><!--
var searchBox = new SearchBox("searchBox", "search",false,'Search API');
--></script>
<div class="navigation" id="top">
  <div class="tabs" id="ompltitle">
    <ul class="tablist">
      <li>The Open Motion Planning Library</li>
      <li id="searchli">
        <div id="MSearchBox" class="MSearchBoxInactive">
        <span class="left">
          <img id="MSearchSelect" src="search/mag_sel.png"
               onmouseover="return searchBox.OnSearchSelectShow()"
               onmouseout="return searchBox.OnSearchSelectHide()"
               alt=""/>
          <input type="text" id="MSearchField" value="Search API" accesskey="S"
               onfocus="searchBox.OnSearchFieldFocus(true)"
               onblur="searchBox.OnSearchFieldFocus(false)"
               onkeyup="searchBox.OnSearchFieldChange(event)"/>
          </span><span class="right">
            <a id="MSearchClose" href="javascript:searchBox.CloseResultsWindow()"><img id="MSearchCloseImg" border="0" src="search/close.png" alt=""/></a>
          </span>
        </div>
      </li>
    </ul>
  </div>

  <ul id="nav" class="dropdown">
    <li class="first"><a href="index.html">Home</a></li>
    <li><a href="download.html">Download</a></li>
    <li><a href="documentation.html">Documentation</a></li>
    <li><span class="dir">Code API</span>
      <ul>
        <li><a href="api_overview.html">API Overview</a></li>
        <li><a href="namespaces.html">Namespaces</a></li>
        <li><a href="annotated.html">Classes</a></li>
        <li><a href="files.html">Files</a></li>
        <li><a href="dirs.html">Directories</a></li>
      </ul>
    </li>
    <li><span class="dir">Community</span>
      <ul>
        <li><a href="developers.html">Developers</a></li>
        <li><a href="thirdparty.html">Contributions</a></li>
        <li><a href="education.html">Education</a></li>
        <li><a href="gallery.html">Gallery</a></li>
      </ul>
    </li>
    <li><span class="dir">About</span>
      <ul>
        <li><a href="license.html">License</a></li>
        <li><a href="citations.html">Citations</a></li>
        <li><a href="acknowledgements.html">Acknowledgments</a></li>
        <li><a href="contact.html">Contact Us</a></li>
      </ul>
    </li>
  </ul>
</div>

<!--- window showing the filter options -->
<div id="MSearchSelectWindow"
  onmouseover="return searchBox.OnSearchSelectShow()"
  onmouseout="return searchBox.OnSearchSelectHide()"
  onkeydown="return searchBox.OnSearchSelectKey(event)">
<a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(0)"><span class="SelectionMark">&#160;</span>All</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(1)"><span class="SelectionMark">&#160;</span>Classes</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(2)"><span class="SelectionMark">&#160;</span>Namespaces</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(3)"><span class="SelectionMark">&#160;</span>Functions</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(4)"><span class="SelectionMark">&#160;</span>Variables</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(5)"><span class="SelectionMark">&#160;</span>Typedefs</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(6)"><span class="SelectionMark">&#160;</span>Enumerations</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(7)"><span class="SelectionMark">&#160;</span>Enumerator</a></div>

<!-- iframe showing the search results (closed by default) -->
<div id="MSearchResultsWindow">
  <iframe src="" frameborder="0"name="MSearchResults" id="MSearchResults"></iframe>
</div>

<div class="container">
  <div class="span-22 push-2 first last">
  <div>
<!-- Generated by Doxygen 1.7.4 -->
<script type="text/javascript"><!--
var searchBox = new SearchBox("searchBox", "search",false,'Search');
--></script>
  <div id="nav-path" class="navpath">
    <ul>
      <li class="navelem"><a class="el" href="namespaceompl.html">ompl</a>      </li>
      <li class="navelem"><a class="el" href="namespaceompl_1_1base.html">base</a>      </li>
      <li class="navelem"><a class="el" href="classompl_1_1base_1_1ProblemDefinition.html">ProblemDefinition</a>      </li>
    </ul>
  </div>
</div>
<div class="header">
  <div class="summary">
<a href="#pub-methods">Public Member Functions</a> &#124;
<a href="#pro-methods">Protected Member Functions</a> &#124;
<a href="#pro-attribs">Protected Attributes</a>  </div>
  <div class="headertitle">
<div class="title">ompl::base::ProblemDefinition Class Reference</div>  </div>
</div>
<div class="contents">
<!-- doxytag: class="ompl::base::ProblemDefinition" -->
<p>Definition of a problem to be solved. This includes the start state(s) for the system and a goal specification.  
 <a href="classompl_1_1base_1_1ProblemDefinition.html#details">More...</a></p>

<p><code>#include &lt;<a class="el" href="ProblemDefinition_8h_source.html">ProblemDefinition.h</a>&gt;</code></p>

<p><a href="classompl_1_1base_1_1ProblemDefinition-members.html">List of all members.</a></p>
<table class="memberdecls">
<tr><td colspan="2"><h2><a name="pub-methods"></a>
Public Member Functions</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a1626717b23766adb3e901bc2ff746744"></a><!-- doxytag: member="ompl::base::ProblemDefinition::ProblemDefinition" ref="a1626717b23766adb3e901bc2ff746744" args="(const SpaceInformationPtr &amp;si)" -->
&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#a1626717b23766adb3e901bc2ff746744">ProblemDefinition</a> (const <a class="el" href="classompl_1_1base_1_1SpaceInformationPtr.html">SpaceInformationPtr</a> &amp;si)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Create a problem definition given the <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...">SpaceInformation</a> it is part of. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a3120682d036099f68fd26805fee0736d"></a><!-- doxytag: member="ompl::base::ProblemDefinition::addStartState" ref="a3120682d036099f68fd26805fee0736d" args="(const State *state)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#a3120682d036099f68fd26805fee0736d">addStartState</a> (const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *state)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Add a start state. The state is copied. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#a874c33b1adab325a2ebf489fa04b8099">addStartState</a> (const <a class="el" href="classompl_1_1base_1_1ScopedState.html">ScopedState</a>&lt;&gt; &amp;state)</td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a8b292f3df6545bb90fbeff72e11f0b59"></a><!-- doxytag: member="ompl::base::ProblemDefinition::hasStartState" ref="a8b292f3df6545bb90fbeff72e11f0b59" args="(const State *state, unsigned int *startIndex=NULL)" -->
bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#a8b292f3df6545bb90fbeff72e11f0b59">hasStartState</a> (const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *state, unsigned int *startIndex=NULL)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Check whether a specified starting state is already included in the problem definition and optionally return the index of that starting state. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ac21b7750c81186c872485cc4231a9fd0"></a><!-- doxytag: member="ompl::base::ProblemDefinition::clearStartStates" ref="ac21b7750c81186c872485cc4231a9fd0" args="(void)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#ac21b7750c81186c872485cc4231a9fd0">clearStartStates</a> (void)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Clear all start states (memory is freed) <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a403e32d54b512e5610435a7443608923"></a><!-- doxytag: member="ompl::base::ProblemDefinition::getStartStateCount" ref="a403e32d54b512e5610435a7443608923" args="(void) const " -->
unsigned int&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#a403e32d54b512e5610435a7443608923">getStartStateCount</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Returns the number of start states. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="aaf141b46b6b36418bc115fcb5e8afff3"></a><!-- doxytag: member="ompl::base::ProblemDefinition::getStartState" ref="aaf141b46b6b36418bc115fcb5e8afff3" args="(unsigned int index) const " -->
const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#aaf141b46b6b36418bc115fcb5e8afff3">getStartState</a> (unsigned int index) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Returns a specific start state. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="classompl_1_1base_1_1State.html">State</a> *&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#ad9fb68d7aab6f613645cf02fa6995c52">getStartState</a> (unsigned int index)</td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a039bef3abd7e8319e4ea2e4cda752ff6"></a><!-- doxytag: member="ompl::base::ProblemDefinition::setGoal" ref="a039bef3abd7e8319e4ea2e4cda752ff6" args="(const GoalPtr &amp;goal)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#a039bef3abd7e8319e4ea2e4cda752ff6">setGoal</a> (const <a class="el" href="classompl_1_1base_1_1GoalPtr.html">GoalPtr</a> &amp;goal)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Set the goal. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a5de8ae94efc42f4b8055292e7cd2e980"></a><!-- doxytag: member="ompl::base::ProblemDefinition::clearGoal" ref="a5de8ae94efc42f4b8055292e7cd2e980" args="(void)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#a5de8ae94efc42f4b8055292e7cd2e980">clearGoal</a> (void)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Clear the goal. Memory is freed. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ac499610c18458d89bbe727127d420b52"></a><!-- doxytag: member="ompl::base::ProblemDefinition::getGoal" ref="ac499610c18458d89bbe727127d420b52" args="(void) const " -->
const <a class="el" href="classompl_1_1base_1_1GoalPtr.html">GoalPtr</a> &amp;&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#ac499610c18458d89bbe727127d420b52">getGoal</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Return the current goal. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a817035d12f2b66e0cb9bbf339b56921e"></a><!-- doxytag: member="ompl::base::ProblemDefinition::getInputStates" ref="a817035d12f2b66e0cb9bbf339b56921e" args="(std::vector&lt; const State * &gt; &amp;states) const " -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#a817035d12f2b66e0cb9bbf339b56921e">getInputStates</a> (std::vector&lt; const <a class="el" href="classompl_1_1base_1_1State.html">State</a> * &gt; &amp;states) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Get all the input states. This includes start states and states that are part of goal regions that can be casted as <a class="el" href="classompl_1_1base_1_1GoalState.html" title="Definition of a goal state.">ompl::base::GoalState</a> or <a class="el" href="classompl_1_1base_1_1GoalStates.html" title="Definition of a set of goal states.">ompl::base::GoalStates</a>. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#a9ab5830fd9366be606349ea1885a3695">setStartAndGoalStates</a> (const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *start, const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *goal, const double threshold=std::numeric_limits&lt; double &gt;::epsilon())</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">In the simplest case possible, we have a single starting state and a single goal state.  <a href="#a9ab5830fd9366be606349ea1885a3695"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a5cd271339a73f61bc1b13588a92a36d7"></a><!-- doxytag: member="ompl::base::ProblemDefinition::setGoalState" ref="a5cd271339a73f61bc1b13588a92a36d7" args="(const State *goal, const double threshold=std::numeric_limits&lt; double &gt;::epsilon())" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#a5cd271339a73f61bc1b13588a92a36d7">setGoalState</a> (const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *goal, const double threshold=std::numeric_limits&lt; double &gt;::epsilon())</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">A simple form of setting the goal. This is called by <a class="el" 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.">setStartAndGoalStates()</a>. A more general form is <a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#a039bef3abd7e8319e4ea2e4cda752ff6" title="Set the goal.">setGoal()</a> <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#a5ada7160decb7894ac566615eb22633a">setStartAndGoalStates</a> (const <a class="el" href="classompl_1_1base_1_1ScopedState.html">ScopedState</a>&lt;&gt; &amp;start, const <a class="el" href="classompl_1_1base_1_1ScopedState.html">ScopedState</a>&lt;&gt; &amp;goal, const double threshold=std::numeric_limits&lt; double &gt;::epsilon())</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#a935f86078c4e65dd397db736c02b3c81">setGoalState</a> (const <a class="el" href="classompl_1_1base_1_1ScopedState.html">ScopedState</a>&lt;&gt; &amp;goal, const double threshold=std::numeric_limits&lt; double &gt;::epsilon())</td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ae8c6ae8979fb163fd01387c4a9f8fd2b"></a><!-- doxytag: member="ompl::base::ProblemDefinition::isTrivial" ref="ae8c6ae8979fb163fd01387c4a9f8fd2b" args="(unsigned int *startIndex=NULL, double *distance=NULL) const " -->
bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#ae8c6ae8979fb163fd01387c4a9f8fd2b">isTrivial</a> (unsigned int *startIndex=NULL, double *distance=NULL) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">A problem is trivial if a given starting state already in the goal region, so we need no motion planning. startID will be set to the index of the starting state that satisfies the goal. The distance to the goal can optionally be returned as well. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="classompl_1_1base_1_1PathPtr.html">PathPtr</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#a45aac71e8031a0cda6e38efef737e5c3">isStraightLinePathValid</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Check if a straight line path is valid. If it is, return an instance of a path that represents the straight line.  <a href="#a45aac71e8031a0cda6e38efef737e5c3"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a74aa8792df6065a84f1b602db53d108c"></a><!-- doxytag: member="ompl::base::ProblemDefinition::fixInvalidInputStates" ref="a74aa8792df6065a84f1b602db53d108c" args="(double distStart, double distGoal, unsigned int attempts)" -->
bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#a74aa8792df6065a84f1b602db53d108c">fixInvalidInputStates</a> (double distStart, double distGoal, unsigned int attempts)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Many times the start or goal state will barely touch an obstacle. In this case, we may want to automatically find a nearby state that is valid so motion planning can be performed. This function enables this behaviour. The allowed distance for both start and goal states is specified. The number of attempts is also specified. Returns true if all states are valid after completion. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a76cd24bc1d239ffa674967c004c7df20"></a><!-- doxytag: member="ompl::base::ProblemDefinition::print" ref="a76cd24bc1d239ffa674967c004c7df20" args="(std::ostream &amp;out=std::cout) const " -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#a76cd24bc1d239ffa674967c004c7df20">print</a> (std::ostream &amp;out=std::cout) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Print information about the start and goal states. <br/></td></tr>
<tr><td colspan="2"><h2><a name="pro-methods"></a>
Protected Member Functions</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a4afcbeee27af97ac5eefdc40ea8ecfbe"></a><!-- doxytag: member="ompl::base::ProblemDefinition::fixInvalidInputState" ref="a4afcbeee27af97ac5eefdc40ea8ecfbe" args="(State *state, double dist, bool start, unsigned int attempts)" -->
bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#a4afcbeee27af97ac5eefdc40ea8ecfbe">fixInvalidInputState</a> (<a class="el" href="classompl_1_1base_1_1State.html">State</a> *state, double dist, bool start, unsigned int attempts)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Helper function for <a class="el" 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...">fixInvalidInputStates()</a>. Attempts to fix an individual state. <br/></td></tr>
<tr><td colspan="2"><h2><a name="pro-attribs"></a>
Protected Attributes</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ac24e830b5fedc3642f3b3c4194d0decb"></a><!-- doxytag: member="ompl::base::ProblemDefinition::si_" ref="ac24e830b5fedc3642f3b3c4194d0decb" args="" -->
<a class="el" href="classompl_1_1base_1_1SpaceInformationPtr.html">SpaceInformationPtr</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#ac24e830b5fedc3642f3b3c4194d0decb">si_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The space information this problem definition is for. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ab545e2929804683e9841c27d492dae82"></a><!-- doxytag: member="ompl::base::ProblemDefinition::startStates_" ref="ab545e2929804683e9841c27d492dae82" args="" -->
std::vector&lt; <a class="el" href="classompl_1_1base_1_1State.html">State</a> * &gt;&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#ab545e2929804683e9841c27d492dae82">startStates_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The set of start states. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a3bdc61f288bbf3f1dece9a275cd2c113"></a><!-- doxytag: member="ompl::base::ProblemDefinition::goal_" ref="a3bdc61f288bbf3f1dece9a275cd2c113" args="" -->
<a class="el" href="classompl_1_1base_1_1GoalPtr.html">GoalPtr</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#a3bdc61f288bbf3f1dece9a275cd2c113">goal_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The goal representation. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a524008c227869a4feb3b562bcfe97147"></a><!-- doxytag: member="ompl::base::ProblemDefinition::msg_" ref="a524008c227869a4feb3b562bcfe97147" args="" -->
<a class="el" href="classompl_1_1msg_1_1Interface.html">msg::Interface</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#a524008c227869a4feb3b562bcfe97147">msg_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Interface for console output. <br/></td></tr>
</table>
<hr/><a name="details" id="details"></a><h2>Detailed Description</h2>
<div class="textblock"><p>Definition of a problem to be solved. This includes the start state(s) for the system and a goal specification. </p>

<p>Definition at line <a class="el" href="ProblemDefinition_8h_source.html#l00067">67</a> of file <a class="el" href="ProblemDefinition_8h_source.html">ProblemDefinition.h</a>.</p>
</div><hr/><h2>Member Function Documentation</h2>
<a class="anchor" id="a874c33b1adab325a2ebf489fa04b8099"></a><!-- doxytag: member="ompl::base::ProblemDefinition::addStartState" ref="a874c33b1adab325a2ebf489fa04b8099" args="(const ScopedState&lt;&gt; &amp;state)" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">void ompl::base::ProblemDefinition::addStartState </td>
          <td>(</td>
          <td class="paramtype">const <a class="el" href="classompl_1_1base_1_1ScopedState.html">ScopedState</a>&lt;&gt; &amp;&#160;</td>
          <td class="paramname"><em>state</em></td><td>)</td>
          <td><code> [inline]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">
<p>Add a start state. The state is copied. </p>
 
<p>Definition at line <a class="el" href="ProblemDefinition_8h_source.html#l00088">88</a> of file <a class="el" href="ProblemDefinition_8h_source.html">ProblemDefinition.h</a>.</p>

</div>
</div>
<a class="anchor" id="ad9fb68d7aab6f613645cf02fa6995c52"></a><!-- doxytag: member="ompl::base::ProblemDefinition::getStartState" ref="ad9fb68d7aab6f613645cf02fa6995c52" args="(unsigned int index)" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname"><a class="el" href="classompl_1_1base_1_1State.html">State</a>* ompl::base::ProblemDefinition::getStartState </td>
          <td>(</td>
          <td class="paramtype">unsigned int&#160;</td>
          <td class="paramname"><em>index</em></td><td>)</td>
          <td><code> [inline]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">
<p>Returns a specific start state. </p>
 
<p>Definition at line <a class="el" href="ProblemDefinition_8h_source.html#l00119">119</a> of file <a class="el" href="ProblemDefinition_8h_source.html">ProblemDefinition.h</a>.</p>

</div>
</div>
<a class="anchor" id="a45aac71e8031a0cda6e38efef737e5c3"></a><!-- doxytag: member="ompl::base::ProblemDefinition::isStraightLinePathValid" ref="a45aac71e8031a0cda6e38efef737e5c3" args="(void) const " -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname"><a class="el" href="classompl_1_1base_1_1PathPtr.html">ompl::base::PathPtr</a> ompl::base::ProblemDefinition::isStraightLinePathValid </td>
          <td>(</td>
          <td class="paramtype">void&#160;</td>
          <td class="paramname"></td><td>)</td>
          <td> const</td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Check if a straight line path is valid. If it is, return an instance of a path that represents the straight line. </p>
<dl class="note"><dt><b>Note:</b></dt><dd>When planning under geometric constraints, this works only if the goal region can be sampled. If the goal region cannot be sampled, this call is equivalent to calling <a class="el" 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...">isTrivial()</a></dd>
<dd>
When planning under differential constraints, the system is propagated forward in time using the null control. </dd></dl>

<p>Definition at line <a class="el" href="ProblemDefinition_8cpp_source.html#l00153">153</a> of file <a class="el" href="ProblemDefinition_8cpp_source.html">ProblemDefinition.cpp</a>.</p>

</div>
</div>
<a class="anchor" id="a935f86078c4e65dd397db736c02b3c81"></a><!-- doxytag: member="ompl::base::ProblemDefinition::setGoalState" ref="a935f86078c4e65dd397db736c02b3c81" args="(const ScopedState&lt;&gt; &amp;goal, const double threshold=std::numeric_limits&lt; double &gt;::epsilon())" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">void ompl::base::ProblemDefinition::setGoalState </td>
          <td>(</td>
          <td class="paramtype">const <a class="el" href="classompl_1_1base_1_1ScopedState.html">ScopedState</a>&lt;&gt; &amp;&#160;</td>
          <td class="paramname"><em>goal</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">const double&#160;</td>
          <td class="paramname"><em>threshold</em> = <code>std::numeric_limits&lt;double&gt;::epsilon()</code>&#160;</td>
        </tr>
        <tr>
          <td></td>
          <td>)</td>
          <td></td><td><code> [inline]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">
<p>A simple form of setting the goal. This is called by <a class="el" 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.">setStartAndGoalStates()</a>. A more general form is <a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#a039bef3abd7e8319e4ea2e4cda752ff6" title="Set the goal.">setGoal()</a> </p>
 
<p>Definition at line <a class="el" href="ProblemDefinition_8h_source.html#l00167">167</a> of file <a class="el" href="ProblemDefinition_8h_source.html">ProblemDefinition.h</a>.</p>

</div>
</div>
<a class="anchor" id="a9ab5830fd9366be606349ea1885a3695"></a><!-- doxytag: member="ompl::base::ProblemDefinition::setStartAndGoalStates" ref="a9ab5830fd9366be606349ea1885a3695" args="(const State *start, const State *goal, const double threshold=std::numeric_limits&lt; double &gt;::epsilon())" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">void ompl::base::ProblemDefinition::setStartAndGoalStates </td>
          <td>(</td>
          <td class="paramtype">const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *&#160;</td>
          <td class="paramname"><em>start</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *&#160;</td>
          <td class="paramname"><em>goal</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">const double&#160;</td>
          <td class="paramname"><em>threshold</em> = <code>std::numeric_limits&lt;double&gt;::epsilon()</code>&#160;</td>
        </tr>
        <tr>
          <td></td>
          <td>)</td>
          <td></td><td></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>In the simplest case possible, we have a single starting state and a single goal state. </p>
<p>This function simply configures the problem definition using these states (performs the needed calls to <a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#a3120682d036099f68fd26805fee0736d" title="Add a start state. The state is copied.">addStartState()</a>, creates an instance of <a class="el" href="classompl_1_1base_1_1GoalState.html" title="Definition of a goal state.">ompl::base::GoalState</a> and calls <a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#a039bef3abd7e8319e4ea2e4cda752ff6" title="Set the goal.">setGoal()</a> on it. </p>

<p>Definition at line <a class="el" href="ProblemDefinition_8cpp_source.html#l00044">44</a> of file <a class="el" href="ProblemDefinition_8cpp_source.html">ProblemDefinition.cpp</a>.</p>

</div>
</div>
<a class="anchor" id="a5ada7160decb7894ac566615eb22633a"></a><!-- doxytag: member="ompl::base::ProblemDefinition::setStartAndGoalStates" ref="a5ada7160decb7894ac566615eb22633a" args="(const ScopedState&lt;&gt; &amp;start, const ScopedState&lt;&gt; &amp;goal, const double threshold=std::numeric_limits&lt; double &gt;::epsilon())" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">void ompl::base::ProblemDefinition::setStartAndGoalStates </td>
          <td>(</td>
          <td class="paramtype">const <a class="el" href="classompl_1_1base_1_1ScopedState.html">ScopedState</a>&lt;&gt; &amp;&#160;</td>
          <td class="paramname"><em>start</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">const <a class="el" href="classompl_1_1base_1_1ScopedState.html">ScopedState</a>&lt;&gt; &amp;&#160;</td>
          <td class="paramname"><em>goal</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">const double&#160;</td>
          <td class="paramname"><em>threshold</em> = <code>std::numeric_limits&lt;double&gt;::epsilon()</code>&#160;</td>
        </tr>
        <tr>
          <td></td>
          <td>)</td>
          <td></td><td><code> [inline]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">
<p>In the simplest case possible, we have a single starting state and a single goal state. </p>
<p>This function simply configures the problem definition using these states (performs the needed calls to <a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#a3120682d036099f68fd26805fee0736d" title="Add a start state. The state is copied.">addStartState()</a>, creates an instance of <a class="el" href="classompl_1_1base_1_1GoalState.html" title="Definition of a goal state.">ompl::base::GoalState</a> and calls <a class="el" href="classompl_1_1base_1_1ProblemDefinition.html#a039bef3abd7e8319e4ea2e4cda752ff6" title="Set the goal.">setGoal()</a> on it. </p>
 
<p>Definition at line <a class="el" href="ProblemDefinition_8h_source.html#l00161">161</a> of file <a class="el" href="ProblemDefinition_8h_source.html">ProblemDefinition.h</a>.</p>

</div>
</div>
<hr/>The documentation for this class was generated from the following files:<ul>
<li>src/ompl/base/<a class="el" href="ProblemDefinition_8h_source.html">ProblemDefinition.h</a></li>
<li>src/ompl/base/src/<a class="el" href="ProblemDefinition_8cpp_source.html">ProblemDefinition.cpp</a></li>
</ul>
</div>
<!-- window showing the filter options -->
<div id="MSearchSelectWindow"
     onmouseover="return searchBox.OnSearchSelectShow()"
     onmouseout="return searchBox.OnSearchSelectHide()"
     onkeydown="return searchBox.OnSearchSelectKey(event)">
<a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(0)"><span class="SelectionMark">&#160;</span>All</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(1)"><span class="SelectionMark">&#160;</span>Classes</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(2)"><span class="SelectionMark">&#160;</span>Namespaces</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(3)"><span class="SelectionMark">&#160;</span>Functions</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(4)"><span class="SelectionMark">&#160;</span>Variables</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(5)"><span class="SelectionMark">&#160;</span>Typedefs</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(6)"><span class="SelectionMark">&#160;</span>Enumerations</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(7)"><span class="SelectionMark">&#160;</span>Enumerator</a></div>

<!-- iframe showing the search results (closed by default) -->
<div id="MSearchResultsWindow">
<iframe src="javascript:void(0)" frameborder="0" 
        name="MSearchResults" id="MSearchResults">
</iframe>
</div>

</div>

<div class="footer span-22 push-2 last">
  <a href="http://www.kavrakilab.org">Physical and Biological Computing Group</a> &bull;
  <a href="http://www.cs.rice.edu">Department of Computer Science</a> &bull;
  <a href="http://www.rice.edu">Rice University</a><br>
  <div class="gray">Generated on Sun Oct 9 2011 23:04:42 by&#160;<a href="http://www.doxygen.org/index.html">doxygen</a> 1.7.4</div>
</div>
</div>
</body>
</html>