Sophie

Sophie

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

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::Goal 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_1Goal.html">Goal</a>      </li>
    </ul>
  </div>
</div>
<div class="header">
  <div class="summary">
<a href="#pub-methods">Public Member Functions</a> &#124;
<a href="#pro-attribs">Protected Attributes</a>  </div>
  <div class="headertitle">
<div class="title">ompl::base::Goal Class Reference</div>  </div>
</div>
<div class="contents">
<!-- doxytag: class="ompl::base::Goal" -->
<p>Abstract definition of goals. Will contain solutions, if found.  
 <a href="classompl_1_1base_1_1Goal.html#details">More...</a></p>

<p><code>#include &lt;<a class="el" href="Goal_8h_source.html">Goal.h</a>&gt;</code></p>
<div class="dynheader">
Inheritance diagram for ompl::base::Goal:</div>
<div class="dyncontent">
<div class="center"><img src="classompl_1_1base_1_1Goal__inherit__graph.png" border="0" usemap="#ompl_1_1base_1_1Goal_inherit__map" alt="Inheritance graph"/></div>
<map name="ompl_1_1base_1_1Goal_inherit__map" id="ompl_1_1base_1_1Goal_inherit__map">
<area shape="rect" id="node3" href="classompl_1_1base_1_1GoalRegion.html" title="Definition of a goal region." alt="" coords="89,83,252,112"/><area shape="rect" id="node5" href="classompl_1_1base_1_1GoalSampleableRegion.html" title="Abstract definition of a goal region that can be sampled." alt="" coords="56,160,285,189"/><area shape="rect" id="node7" href="classompl_1_1base_1_1GoalState.html" title="Definition of a goal state." alt="" coords="5,237,157,267"/><area shape="rect" id="node9" href="classompl_1_1base_1_1GoalStates.html" title="Definition of a set of goal states." alt="" coords="181,237,339,267"/><area shape="rect" id="node11" href="classompl_1_1base_1_1GoalLazySamples.html" title="Definition of a goal region that can be sampled, but the sampling process can be slow. This class allows sampling the happen in a separate thread, and the number of goals may increase, as the planner is running, in a thread&#45;safe manner." alt="" coords="160,315,360,344"/></map>
<center><span class="legend">[<a href="graph_legend.html">legend</a>]</span></center></div>

<p><a href="classompl_1_1base_1_1Goal-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="aa32a9dcc9c62ab906eb89e3b6c4e04c7"></a><!-- doxytag: member="ompl::base::Goal::Goal" ref="aa32a9dcc9c62ab906eb89e3b6c4e04c7" args="(const SpaceInformationPtr &amp;si)" -->
&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1Goal.html#aa32a9dcc9c62ab906eb89e3b6c4e04c7">Goal</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">Constructor. The goal must always know the space information it is part of. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a0b3c267935f7a201823afee5e8da7b92"></a><!-- doxytag: member="ompl::base::Goal::~Goal" ref="a0b3c267935f7a201823afee5e8da7b92" args="(void)" -->
virtual&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1Goal.html#a0b3c267935f7a201823afee5e8da7b92">~Goal</a> (void)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Destructor. Clears the solution as well. <br/></td></tr>
<tr><td class="memTemplParams" colspan="2">template&lt;class T &gt; </td></tr>
<tr><td class="memTemplItemLeft" align="right" valign="top">T *&#160;</td><td class="memTemplItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1Goal.html#aea2db492c83aac0eb3720b2b2a9710c3">as</a> (void)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Cast this instance to a desired type.  <a href="#aea2db492c83aac0eb3720b2b2a9710c3"></a><br/></td></tr>
<tr><td class="memTemplParams" colspan="2">template&lt;class T &gt; </td></tr>
<tr><td class="memTemplItemLeft" align="right" valign="top">const T *&#160;</td><td class="memTemplItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1Goal.html#a48f856096f8ee2e05de11df986ad2d9f">as</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Cast this instance to a desired type.  <a href="#a48f856096f8ee2e05de11df986ad2d9f"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a04a7feefcb8700902b12805d434a8f4b"></a><!-- doxytag: member="ompl::base::Goal::getType" ref="a04a7feefcb8700902b12805d434a8f4b" args="(void) const " -->
<a class="el" href="namespaceompl_1_1base.html#a1620a159019faf720c550eeca5723f55">GoalType</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1Goal.html#a04a7feefcb8700902b12805d434a8f4b">getType</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Return the goal type. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a72d63bac8cbeb4110fdfe93172c92209"></a><!-- doxytag: member="ompl::base::Goal::hasType" ref="a72d63bac8cbeb4110fdfe93172c92209" args="(GoalType type) const " -->
bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1Goal.html#a72d63bac8cbeb4110fdfe93172c92209">hasType</a> (<a class="el" href="namespaceompl_1_1base.html#a1620a159019faf720c550eeca5723f55">GoalType</a> type) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Check if this goal can be cast to a particular goal type. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ad8106bac6c0180b7ea430fe4312305fc"></a><!-- doxytag: member="ompl::base::Goal::getSpaceInformation" ref="ad8106bac6c0180b7ea430fe4312305fc" args="(void) const " -->
const <a class="el" href="classompl_1_1base_1_1SpaceInformationPtr.html">SpaceInformationPtr</a> &amp;&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1Goal.html#ad8106bac6c0180b7ea430fe4312305fc">getSpaceInformation</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Get the space information this goal is for. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a02ba4ba487714cd4e8f67c9d4164d0ec"></a><!-- doxytag: member="ompl::base::Goal::isSatisfied" ref="a02ba4ba487714cd4e8f67c9d4164d0ec" args="(const State *st) const =0" -->
virtual bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1Goal.html#a02ba4ba487714cd4e8f67c9d4164d0ec">isSatisfied</a> (const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *st) const =0</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Return true if the state satisfies the goal constraints. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">virtual bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1Goal.html#aa3a78aa896a1a7778e40c02f4e1d3d1d">isSatisfied</a> (const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *st, double *distance) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Return true if the state satisfies the goal constraints and compute the distance between the state given as argument and the goal (even if the goal is not satisfied). This distance can be an approximation. It can even be set to a constant, if such a computation is not possible.  <a href="#aa3a78aa896a1a7778e40c02f4e1d3d1d"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1Goal.html#afc90703a426c2f44d2ced607df4f0aa6">isSatisfied</a> (const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *st, double pathLength, double *distance) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Return true if the state satisfies the goal constraints and the path length is less than the desired maximum length. This call also computes the distance between the state given as argument and the goal.  <a href="#afc90703a426c2f44d2ced607df4f0aa6"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a5d5285908b7e09d61577279f35e47175"></a><!-- doxytag: member="ompl::base::Goal::isStartGoalPairValid" ref="a5d5285908b7e09d61577279f35e47175" args="(const State *, const State *) const " -->
virtual bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1Goal.html#a5d5285908b7e09d61577279f35e47175">isStartGoalPairValid</a> (const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *, const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Since there can be multiple starting states (and multiple goal states) it is possible certain pairs are not to be allowed. By default we however assume all such pairs are allowed. Note: if this function returns true, <a class="el" href="classompl_1_1base_1_1Goal.html#a02ba4ba487714cd4e8f67c9d4164d0ec" title="Return true if the state satisfies the goal constraints.">isSatisfied()</a> need not be called. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a9a6e44d33f848108d0beeb1cf7a6c1ad"></a><!-- doxytag: member="ompl::base::Goal::isAchieved" ref="a9a6e44d33f848108d0beeb1cf7a6c1ad" args="(void) const " -->
bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1Goal.html#a9a6e44d33f848108d0beeb1cf7a6c1ad">isAchieved</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Returns true if a solution path has been found (could be approximate) <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a033696b98580c4be0694a878ef1e7bbb"></a><!-- doxytag: member="ompl::base::Goal::getMaximumPathLength" ref="a033696b98580c4be0694a878ef1e7bbb" args="(void) const " -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1Goal.html#a033696b98580c4be0694a878ef1e7bbb">getMaximumPathLength</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Get the maximum length allowed for a solution path. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a19445b2688918bf9e402f3f9472a63df"></a><!-- doxytag: member="ompl::base::Goal::setMaximumPathLength" ref="a19445b2688918bf9e402f3f9472a63df" args="(double maximumPathLength)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1Goal.html#a19445b2688918bf9e402f3f9472a63df">setMaximumPathLength</a> (double maximumPathLength)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Set the maximum length allowed for a solution path. This value is checked only in the version of <a class="el" href="classompl_1_1base_1_1Goal.html#a02ba4ba487714cd4e8f67c9d4164d0ec" title="Return true if the state satisfies the goal constraints.">isSatisfied()</a> that takes the path length as argument or by <a class="el" href="classompl_1_1base_1_1Goal.html#ab4beedc8edd881714081eb99b9b4ba34" title="Check if pathLength is smaller than the value returned by getMaximumPathLength()">isPathLengthSatisfied()</a>. The default maximal path length is infinity. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ab4beedc8edd881714081eb99b9b4ba34"></a><!-- doxytag: member="ompl::base::Goal::isPathLengthSatisfied" ref="ab4beedc8edd881714081eb99b9b4ba34" args="(double pathLength) const " -->
bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1Goal.html#ab4beedc8edd881714081eb99b9b4ba34">isPathLengthSatisfied</a> (double pathLength) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Check if <em>pathLength</em> is smaller than the value returned by <a class="el" href="classompl_1_1base_1_1Goal.html#a033696b98580c4be0694a878ef1e7bbb" title="Get the maximum length allowed for a solution path.">getMaximumPathLength()</a> <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">const <a class="el" href="classompl_1_1base_1_1PathPtr.html">PathPtr</a> &amp;&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1Goal.html#ab15b334d24d37e52d21b76ef18eb9058">getSolutionPath</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Return the found solution path.  <a href="#ab15b334d24d37e52d21b76ef18eb9058"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ade528c0fefb9094abc1a2d1518a5f860"></a><!-- doxytag: member="ompl::base::Goal::setSolutionPath" ref="ade528c0fefb9094abc1a2d1518a5f860" args="(const PathPtr &amp;path, bool approximate=false)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1Goal.html#ade528c0fefb9094abc1a2d1518a5f860">setSolutionPath</a> (const <a class="el" href="classompl_1_1base_1_1PathPtr.html">PathPtr</a> &amp;path, bool approximate=false)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Update the solution path. If a previous solution path exists, it is deleted. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a56e614a15d3ddf7ce34b77ab1c4ea886"></a><!-- doxytag: member="ompl::base::Goal::clearSolutionPath" ref="a56e614a15d3ddf7ce34b77ab1c4ea886" args="(void)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1Goal.html#a56e614a15d3ddf7ce34b77ab1c4ea886">clearSolutionPath</a> (void)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Forget the solution path. Memory is freed. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a5e982753bd3b279d244ea52acbcb8f19"></a><!-- doxytag: member="ompl::base::Goal::getDifference" ref="a5e982753bd3b279d244ea52acbcb8f19" args="(void) const " -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1Goal.html#a5e982753bd3b279d244ea52acbcb8f19">getDifference</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">If a difference between the desired solution and the solution found is computed by the planner, this functions returns it. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="afbfc02ebac97049ebdd28d040ce44c37"></a><!-- doxytag: member="ompl::base::Goal::setDifference" ref="afbfc02ebac97049ebdd28d040ce44c37" args="(double difference)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1Goal.html#afbfc02ebac97049ebdd28d040ce44c37">setDifference</a> (double difference)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Set the difference between the found solution path and the desired solution path. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a318d3b926915a1dc2cb2dcb9732ca3f4"></a><!-- doxytag: member="ompl::base::Goal::isApproximate" ref="a318d3b926915a1dc2cb2dcb9732ca3f4" args="(void) const " -->
bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1Goal.html#a318d3b926915a1dc2cb2dcb9732ca3f4">isApproximate</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Return true if the found solution is approximate (does not actually reach the desired goal, but hopefully is closer to it) <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a8a8a736012591d8b46138f09bd35bead"></a><!-- doxytag: member="ompl::base::Goal::print" ref="a8a8a736012591d8b46138f09bd35bead" args="(std::ostream &amp;out=std::cout) const " -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1Goal.html#a8a8a736012591d8b46138f09bd35bead">print</a> (std::ostream &amp;out=std::cout) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Print information about the goal. <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="af5e22736c4d1335c4edf92d8c76eaa02"></a><!-- doxytag: member="ompl::base::Goal::type_" ref="af5e22736c4d1335c4edf92d8c76eaa02" args="" -->
<a class="el" href="namespaceompl_1_1base.html#a1620a159019faf720c550eeca5723f55">GoalType</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1Goal.html#af5e22736c4d1335c4edf92d8c76eaa02">type_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight"><a class="el" href="classompl_1_1base_1_1Goal.html" title="Abstract definition of goals. Will contain solutions, if found.">Goal</a> type. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a2568592d1968413e2759564c4f6511b0"></a><!-- doxytag: member="ompl::base::Goal::si_" ref="a2568592d1968413e2759564c4f6511b0" 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_1Goal.html#a2568592d1968413e2759564c4f6511b0">si_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The space information for this goal. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a307993d7ed51565d703143143c0a60bb"></a><!-- doxytag: member="ompl::base::Goal::maximumPathLength_" ref="a307993d7ed51565d703143143c0a60bb" args="" -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1Goal.html#a307993d7ed51565d703143143c0a60bb">maximumPathLength_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The maximum length allowed for the solution path. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="adadfb1776c3b6a5bc02dfd4d925b0a77"></a><!-- doxytag: member="ompl::base::Goal::path_" ref="adadfb1776c3b6a5bc02dfd4d925b0a77" args="" -->
<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_1Goal.html#adadfb1776c3b6a5bc02dfd4d925b0a77">path_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Solution path, if found. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="afae6a0a48dcc5083a8144da2d3d2c807"></a><!-- doxytag: member="ompl::base::Goal::difference_" ref="afae6a0a48dcc5083a8144da2d3d2c807" args="" -->
double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1Goal.html#afae6a0a48dcc5083a8144da2d3d2c807">difference_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The achieved difference between the found solution and the desired goal. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ac0635a0086076403e3f8d4960754f18b"></a><!-- doxytag: member="ompl::base::Goal::approximate_" ref="ac0635a0086076403e3f8d4960754f18b" args="" -->
bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1Goal.html#ac0635a0086076403e3f8d4960754f18b">approximate_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">True if goal was not achieved, but an approximate solution was found. <br/></td></tr>
</table>
<hr/><a name="details" id="details"></a><h2>Detailed Description</h2>
<div class="textblock"><p>Abstract definition of goals. Will contain solutions, if found. </p>

<p>Definition at line <a class="el" href="Goal_8h_source.html#l00061">61</a> of file <a class="el" href="Goal_8h_source.html">Goal.h</a>.</p>
</div><hr/><h2>Member Function Documentation</h2>
<a class="anchor" id="aea2db492c83aac0eb3720b2b2a9710c3"></a><!-- doxytag: member="ompl::base::Goal::as" ref="aea2db492c83aac0eb3720b2b2a9710c3" args="(void)" -->
<div class="memitem">
<div class="memproto">
<div class="memtemplate">
template&lt;class T &gt; </div>
      <table class="memname">
        <tr>
          <td class="memname">T* ompl::base::Goal::as </td>
          <td>(</td>
          <td class="paramtype">void&#160;</td>
          <td class="paramname"></td><td>)</td>
          <td><code> [inline]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Cast this instance to a desired type. </p>

<p><p>Make sure the type we are casting to is indeed a goal </p>
</p>

<p>Definition at line <a class="el" href="Goal_8h_source.html#l00075">75</a> of file <a class="el" href="Goal_8h_source.html">Goal.h</a>.</p>

</div>
</div>
<a class="anchor" id="a48f856096f8ee2e05de11df986ad2d9f"></a><!-- doxytag: member="ompl::base::Goal::as" ref="a48f856096f8ee2e05de11df986ad2d9f" args="(void) const " -->
<div class="memitem">
<div class="memproto">
<div class="memtemplate">
template&lt;class T &gt; </div>
      <table class="memname">
        <tr>
          <td class="memname">const T* ompl::base::Goal::as </td>
          <td>(</td>
          <td class="paramtype">void&#160;</td>
          <td class="paramname"></td><td>)</td>
          <td> const<code> [inline]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Cast this instance to a desired type. </p>

<p><p>Make sure the type we are casting to is indeed a goal </p>
</p>

<p>Definition at line <a class="el" href="Goal_8h_source.html#l00085">85</a> of file <a class="el" href="Goal_8h_source.html">Goal.h</a>.</p>

</div>
</div>
<a class="anchor" id="ab15b334d24d37e52d21b76ef18eb9058"></a><!-- doxytag: member="ompl::base::Goal::getSolutionPath" ref="ab15b334d24d37e52d21b76ef18eb9058" args="(void) const " -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">const <a class="el" href="classompl_1_1base_1_1PathPtr.html">PathPtr</a>&amp; ompl::base::Goal::getSolutionPath </td>
          <td>(</td>
          <td class="paramtype">void&#160;</td>
          <td class="paramname"></td><td>)</td>
          <td> const<code> [inline]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Return the found solution path. </p>
<p>This will need to be casted into the specialization computed by the planner </p>

<p>Definition at line <a class="el" href="Goal_8h_source.html#l00182">182</a> of file <a class="el" href="Goal_8h_source.html">Goal.h</a>.</p>

</div>
</div>
<a class="anchor" id="afc90703a426c2f44d2ced607df4f0aa6"></a><!-- doxytag: member="ompl::base::Goal::isSatisfied" ref="afc90703a426c2f44d2ced607df4f0aa6" args="(const State *st, double pathLength, double *distance) const " -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">bool ompl::base::Goal::isSatisfied </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>st</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">double&#160;</td>
          <td class="paramname"><em>pathLength</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">double *&#160;</td>
          <td class="paramname"><em>distance</em>&#160;</td>
        </tr>
        <tr>
          <td></td>
          <td>)</td>
          <td></td><td> const</td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Return true if the state satisfies the goal constraints and the path length is less than the desired maximum length. This call also computes the distance between the state given as argument and the goal. </p>
<dl><dt><b>Parameters:</b></dt><dd>
  <table class="params">
    <tr><td class="paramname">st</td><td>the state to check for validity </td></tr>
    <tr><td class="paramname">pathLength</td><td>the length of the path that leads to <em>st</em> </td></tr>
    <tr><td class="paramname">distance</td><td>location at which distance to goal will be stored </td></tr>
  </table>
  </dd>
</dl>

<p>Definition at line <a class="el" href="Goal_8cpp_source.html#l00053">53</a> of file <a class="el" href="Goal_8cpp_source.html">Goal.cpp</a>.</p>

</div>
</div>
<a class="anchor" id="aa3a78aa896a1a7778e40c02f4e1d3d1d"></a><!-- doxytag: member="ompl::base::Goal::isSatisfied" ref="aa3a78aa896a1a7778e40c02f4e1d3d1d" args="(const State *st, double *distance) const " -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">bool ompl::base::Goal::isSatisfied </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>st</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">double *&#160;</td>
          <td class="paramname"><em>distance</em>&#160;</td>
        </tr>
        <tr>
          <td></td>
          <td>)</td>
          <td></td><td> const<code> [virtual]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Return true if the state satisfies the goal constraints and compute the distance between the state given as argument and the goal (even if the goal is not satisfied). This distance can be an approximation. It can even be set to a constant, if such a computation is not possible. </p>
<dl><dt><b>Parameters:</b></dt><dd>
  <table class="params">
    <tr><td class="paramname">st</td><td>the state to check for validity </td></tr>
    <tr><td class="paramname">distance</td><td>location at which distance to goal will be stored </td></tr>
  </table>
  </dd>
</dl>
<dl class="note"><dt><b>Note:</b></dt><dd>The default implementation sets the distance to a constant. </dd>
<dd>
If this function returns true, <a class="el" href="classompl_1_1base_1_1Goal.html#a5d5285908b7e09d61577279f35e47175" title="Since there can be multiple starting states (and multiple goal states) it is possible certain pairs a...">isStartGoalPairValid()</a> need not be called. </dd></dl>

<p>Reimplemented in <a class="el" href="classompl_1_1base_1_1GoalRegion.html#a7d6ee3fbc03fe16a55da3b4b4c07dbca">ompl::base::GoalRegion</a>.</p>

<p>Definition at line <a class="el" href="Goal_8cpp_source.html#l00046">46</a> of file <a class="el" href="Goal_8cpp_source.html">Goal.cpp</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="Goal_8h_source.html">Goal.h</a></li>
<li>src/ompl/base/src/<a class="el" href="Goal_8cpp_source.html">Goal.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:41 by&#160;<a href="http://www.doxygen.org/index.html">doxygen</a> 1.7.4</div>
</div>
</div>
</body>
</html>