<!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::GoalStates 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"> </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="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_1GoalStates.html">GoalStates</a> </li> </ul> </div> </div> <div class="header"> <div class="summary"> <a href="#pub-methods">Public Member Functions</a> | <a href="#pub-attribs">Public Attributes</a> </div> <div class="headertitle"> <div class="title">ompl::base::GoalStates Class Reference</div> </div> </div> <div class="contents"> <!-- doxytag: class="ompl::base::GoalStates" --><!-- doxytag: inherits="ompl::base::GoalSampleableRegion" --> <p>Definition of a set of goal states. <a href="classompl_1_1base_1_1GoalStates.html#details">More...</a></p> <p><code>#include <<a class="el" href="GoalStates_8h_source.html">GoalStates.h</a>></code></p> <div class="dynheader"> Inheritance diagram for ompl::base::GoalStates:</div> <div class="dyncontent"> <div class="center"><img src="classompl_1_1base_1_1GoalStates__inherit__graph.png" border="0" usemap="#ompl_1_1base_1_1GoalStates_inherit__map" alt="Inheritance graph"/></div> <map name="ompl_1_1base_1_1GoalStates_inherit__map" id="ompl_1_1base_1_1GoalStates_inherit__map"> <area shape="rect" id="node9" 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-safe manner." alt="" coords="20,315,220,344"/><area shape="rect" id="node2" href="classompl_1_1base_1_1GoalSampleableRegion.html" title="Abstract definition of a goal region that can be sampled." alt="" coords="5,160,235,189"/><area shape="rect" id="node4" href="classompl_1_1base_1_1GoalRegion.html" title="Definition of a goal region." alt="" coords="39,83,201,112"/><area shape="rect" id="node6" href="classompl_1_1base_1_1Goal.html" title="Abstract definition of goals. Will contain solutions, if found." alt="" coords="60,5,180,35"/></map> <center><span class="legend">[<a href="graph_legend.html">legend</a>]</span></center></div> <p><a href="classompl_1_1base_1_1GoalStates-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="ac1431173837a911a7b4b32d7e7f86dbc"></a><!-- doxytag: member="ompl::base::GoalStates::GoalStates" ref="ac1431173837a911a7b4b32d7e7f86dbc" args="(const SpaceInformationPtr &si)" -->  </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalStates.html#ac1431173837a911a7b4b32d7e7f86dbc">GoalStates</a> (const <a class="el" href="classompl_1_1base_1_1SpaceInformationPtr.html">SpaceInformationPtr</a> &si)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Create a goal representation that is in fact a set of states. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a0acc6095d25d837940f21e76bb9793ea"></a><!-- doxytag: member="ompl::base::GoalStates::sampleGoal" ref="a0acc6095d25d837940f21e76bb9793ea" args="(State *st) const " --> virtual void </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalStates.html#a0acc6095d25d837940f21e76bb9793ea">sampleGoal</a> (<a class="el" href="classompl_1_1base_1_1State.html">State</a> *st) const </td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Sample a state in the goal region. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a6c4f7e4a9b7648db8bde7ffe8ee8e7dc"></a><!-- doxytag: member="ompl::base::GoalStates::maxSampleCount" ref="a6c4f7e4a9b7648db8bde7ffe8ee8e7dc" args="(void) const " --> virtual unsigned int </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalStates.html#a6c4f7e4a9b7648db8bde7ffe8ee8e7dc">maxSampleCount</a> (void) const </td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Return the maximum number of samples that can be asked for before repeating. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a7f630ce514a5b222e9c27232d3de6a10"></a><!-- doxytag: member="ompl::base::GoalStates::distanceGoal" ref="a7f630ce514a5b222e9c27232d3de6a10" args="(const State *st) const " --> virtual double </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalStates.html#a7f630ce514a5b222e9c27232d3de6a10">distanceGoal</a> (const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *st) const </td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Compute the distance to the goal (heuristic). This function is the one used in computing the distance to the goal in a call to <a class="el" href="classompl_1_1base_1_1GoalRegion.html#a63180f3c2e53eb6feedae905cb858f39" title="Equivalent to calling isSatisfied(const State *, double *) with a NULL second argument.">isSatisfied()</a> <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a0186d82ecb85de07b3f256c7643bfce8"></a><!-- doxytag: member="ompl::base::GoalStates::print" ref="a0186d82ecb85de07b3f256c7643bfce8" args="(std::ostream &out=std::cout) const " --> virtual void </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalStates.html#a0186d82ecb85de07b3f256c7643bfce8">print</a> (std::ostream &out=std::cout) const </td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Print information about the goal data structure to a stream. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a6cf378a86fd25680dfaa5b2446598d55"></a><!-- doxytag: member="ompl::base::GoalStates::addState" ref="a6cf378a86fd25680dfaa5b2446598d55" args="(const State *st)" --> virtual void </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalStates.html#a6cf378a86fd25680dfaa5b2446598d55">addState</a> (const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *st)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Add a goal state. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="af43dd0177bdc390dc3d98aab04003238"></a><!-- doxytag: member="ompl::base::GoalStates::addState" ref="af43dd0177bdc390dc3d98aab04003238" args="(const ScopedState<> &st)" --> void </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalStates.html#af43dd0177bdc390dc3d98aab04003238">addState</a> (const <a class="el" href="classompl_1_1base_1_1ScopedState.html">ScopedState</a><> &st)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Add a goal state (calls the previous definition of <a class="el" href="classompl_1_1base_1_1GoalStates.html#a6cf378a86fd25680dfaa5b2446598d55" title="Add a goal state.">addState()</a>) <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a215641afe30c50665e5e7bde6894e65e"></a><!-- doxytag: member="ompl::base::GoalStates::clear" ref="a215641afe30c50665e5e7bde6894e65e" args="(void)" --> virtual void </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalStates.html#a215641afe30c50665e5e7bde6894e65e">clear</a> (void)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Clear all goal states. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a67213111771fbf1e76df453dc9c40599"></a><!-- doxytag: member="ompl::base::GoalStates::hasStates" ref="a67213111771fbf1e76df453dc9c40599" args="(void) const " --> bool </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalStates.html#a67213111771fbf1e76df453dc9c40599">hasStates</a> (void) const </td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Check if there are any states in this goal region. <br/></td></tr> <tr><td colspan="2"><h2><a name="pub-attribs"></a> Public Attributes</h2></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a34ef4d90da89228d610ef169ec0c81e1"></a><!-- doxytag: member="ompl::base::GoalStates::states" ref="a34ef4d90da89228d610ef169ec0c81e1" args="" --> std::vector< <a class="el" href="classompl_1_1base_1_1State.html">State</a> * > </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1GoalStates.html#a34ef4d90da89228d610ef169ec0c81e1">states</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">The goal states. Only ones that are valid are considered by the motion planner. <br/></td></tr> </table> <hr/><a name="details" id="details"></a><h2>Detailed Description</h2> <div class="textblock"><p>Definition of a set of goal states. </p> <p>Definition at line <a class="el" href="GoalStates_8h_source.html#l00050">50</a> of file <a class="el" href="GoalStates_8h_source.html">GoalStates.h</a>.</p> </div><hr/>The documentation for this class was generated from the following files:<ul> <li>src/ompl/base/<a class="el" href="GoalStates_8h_source.html">GoalStates.h</a></li> <li>src/ompl/base/src/<a class="el" href="GoalStates_8cpp_source.html">GoalStates.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"> </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:42 by <a href="http://www.doxygen.org/index.html">doxygen</a> 1.7.4</div> </div> </div> </body> </html>