Sophie

Sophie

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

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::DiscreteStateSpace 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_1DiscreteStateSpace.html">DiscreteStateSpace</a>      </li>
    </ul>
  </div>
</div>
<div class="header">
  <div class="summary">
<a href="#nested-classes">Classes</a> &#124;
<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::DiscreteStateSpace Class Reference</div>  </div>
</div>
<div class="contents">
<!-- doxytag: class="ompl::base::DiscreteStateSpace" --><!-- doxytag: inherits="ompl::base::StateSpace" -->
<p>A space representing discrete states; i.e. there are a small number of discrete states the system can be in. States are represented as integers [lowerBound, upperBound], where lowerBound and upperBound are inclusive. States do not wrap around; i.e. the distance between state lowerBound and state upperBound is upperBound-lowerBound, NOT 1.  
 <a href="classompl_1_1base_1_1DiscreteStateSpace.html#details">More...</a></p>

<p><code>#include &lt;<a class="el" href="DiscreteStateSpace_8h_source.html">DiscreteStateSpace.h</a>&gt;</code></p>
<div class="dynheader">
Inheritance diagram for ompl::base::DiscreteStateSpace:</div>
<div class="dyncontent">
<div class="center"><img src="classompl_1_1base_1_1DiscreteStateSpace__inherit__graph.png" border="0" usemap="#ompl_1_1base_1_1DiscreteStateSpace_inherit__map" alt="Inheritance graph"/></div>
<map name="ompl_1_1base_1_1DiscreteStateSpace_inherit__map" id="ompl_1_1base_1_1DiscreteStateSpace_inherit__map">
<area shape="rect" id="node2" href="classompl_1_1base_1_1StateSpace.html" title="Representation of a space in which planning can be performed. Topology specific sampling, interpolation and distance are defined." alt="" coords="29,5,192,35"/></map>
<center><span class="legend">[<a href="graph_legend.html">legend</a>]</span></center></div>

<p><a href="classompl_1_1base_1_1DiscreteStateSpace-members.html">List of all members.</a></p>
<table class="memberdecls">
<tr><td colspan="2"><h2><a name="nested-classes"></a>
Classes</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">class &#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1DiscreteStateSpace_1_1StateType.html">StateType</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The definition of a discrete state.  <a href="classompl_1_1base_1_1DiscreteStateSpace_1_1StateType.html#details">More...</a><br/></td></tr>
<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="a3d3b1f110e2717437d5e20ce33185346"></a><!-- doxytag: member="ompl::base::DiscreteStateSpace::DiscreteStateSpace" ref="a3d3b1f110e2717437d5e20ce33185346" args="(int lowerBound, int upperBound)" -->
&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1DiscreteStateSpace.html#a3d3b1f110e2717437d5e20ce33185346">DiscreteStateSpace</a> (int lowerBound, int upperBound)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Construct a discrete space in wich states can take values in the set [<em>lowerBound</em>, <em>upperBound</em>]. <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_1DiscreteStateSpace.html#afd90bfa97ae9cc027272b52cd7966fec">isDiscrete</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Check if the set of states is discrete.  <a href="#afd90bfa97ae9cc027272b52cd7966fec"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="abae3e927d29b6322fc3bd2e586e41707"></a><!-- doxytag: member="ompl::base::DiscreteStateSpace::getDimension" ref="abae3e927d29b6322fc3bd2e586e41707" args="(void) const " -->
virtual unsigned int&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1DiscreteStateSpace.html#abae3e927d29b6322fc3bd2e586e41707">getDimension</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Get the dimension of the space (not the dimension of the surrounding ambient space) <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">virtual double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1DiscreteStateSpace.html#a4e162fbfbcb0b9a46a3a3c3e802c7c49">getMaximumExtent</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Get the maximum value a call to <a class="el" href="classompl_1_1base_1_1DiscreteStateSpace.html#ab2324393c8a76c6ff127213b4dc1c90e" title="Computes distance to between two states. This function satisfies the properties of a metric and its r...">distance()</a> can return (or an upper bound). For unbounded state spaces, this function can return infinity.  <a href="#a4e162fbfbcb0b9a46a3a3c3e802c7c49"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a1246bbbe424c3c82d4661d8c409b87da"></a><!-- doxytag: member="ompl::base::DiscreteStateSpace::enforceBounds" ref="a1246bbbe424c3c82d4661d8c409b87da" args="(State *state) const " -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1DiscreteStateSpace.html#a1246bbbe424c3c82d4661d8c409b87da">enforceBounds</a> (<a class="el" href="classompl_1_1base_1_1State.html">State</a> *state) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Bring the state within the bounds of the state space. For unbounded spaces this function can be a no-op. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a269c5ff29309beaaec16e130ad6d6a84"></a><!-- doxytag: member="ompl::base::DiscreteStateSpace::satisfiesBounds" ref="a269c5ff29309beaaec16e130ad6d6a84" args="(const State *state) const " -->
virtual bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1DiscreteStateSpace.html#a269c5ff29309beaaec16e130ad6d6a84">satisfiesBounds</a> (const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *state) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Check if a state is inside the bounding box. For unbounded spaces this function can always return true. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a6ce8e181f39cff7ccab6ac5ae2f9cafd"></a><!-- doxytag: member="ompl::base::DiscreteStateSpace::copyState" ref="a6ce8e181f39cff7ccab6ac5ae2f9cafd" args="(State *destination, const State *source) const " -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1DiscreteStateSpace.html#a6ce8e181f39cff7ccab6ac5ae2f9cafd">copyState</a> (<a class="el" href="classompl_1_1base_1_1State.html">State</a> *destination, const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *source) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Copy a state to another. The memory of source and destination should NOT overlap. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ab2324393c8a76c6ff127213b4dc1c90e"></a><!-- doxytag: member="ompl::base::DiscreteStateSpace::distance" ref="ab2324393c8a76c6ff127213b4dc1c90e" args="(const State *state1, const State *state2) const " -->
virtual double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1DiscreteStateSpace.html#ab2324393c8a76c6ff127213b4dc1c90e">distance</a> (const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *state1, const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *state2) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Computes distance to between two states. This function satisfies the properties of a metric and its return value will always be between 0 and <a class="el" href="classompl_1_1base_1_1DiscreteStateSpace.html#a4e162fbfbcb0b9a46a3a3c3e802c7c49" title="Get the maximum value a call to distance() can return (or an upper bound). For unbounded state spaces...">getMaximumExtent()</a> <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ade2b260d8e816d5086cb104e6148d54f"></a><!-- doxytag: member="ompl::base::DiscreteStateSpace::equalStates" ref="ade2b260d8e816d5086cb104e6148d54f" args="(const State *state1, const State *state2) const " -->
virtual bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1DiscreteStateSpace.html#ade2b260d8e816d5086cb104e6148d54f">equalStates</a> (const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *state1, const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *state2) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Checks whether two states are equal. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a17bdd2b4bf0e0cea9fc9ffe2bc9d12e3"></a><!-- doxytag: member="ompl::base::DiscreteStateSpace::interpolate" ref="a17bdd2b4bf0e0cea9fc9ffe2bc9d12e3" args="(const State *from, const State *to, const double t, State *state) const " -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1DiscreteStateSpace.html#a17bdd2b4bf0e0cea9fc9ffe2bc9d12e3">interpolate</a> (const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *from, const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *to, const double t, <a class="el" href="classompl_1_1base_1_1State.html">State</a> *state) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Computes the state that lies at time <em>t</em> in [0, 1] on the segment that connects <em>from</em> state to <em>to</em> state. The memory location of <em>state</em> is not required to be different from the memory of either <em>from</em> or <em>to</em>. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="aae72454699008b487594ccd4c1c21881"></a><!-- doxytag: member="ompl::base::DiscreteStateSpace::allocStateSampler" ref="aae72454699008b487594ccd4c1c21881" args="(void) const " -->
virtual <a class="el" href="classompl_1_1base_1_1StateSamplerPtr.html">StateSamplerPtr</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1DiscreteStateSpace.html#aae72454699008b487594ccd4c1c21881">allocStateSampler</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Allocate an instance of a uniform state sampler for this space. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a56336d7a88e4e79046eef462b734ee2d"></a><!-- doxytag: member="ompl::base::DiscreteStateSpace::allocState" ref="a56336d7a88e4e79046eef462b734ee2d" args="(void) const " -->
virtual <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_1DiscreteStateSpace.html#a56336d7a88e4e79046eef462b734ee2d">allocState</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Allocate a state that can store a point in the described space. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a4f318a56d5804c88f47605646882c471"></a><!-- doxytag: member="ompl::base::DiscreteStateSpace::freeState" ref="a4f318a56d5804c88f47605646882c471" args="(State *state) const " -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1DiscreteStateSpace.html#a4f318a56d5804c88f47605646882c471">freeState</a> (<a class="el" href="classompl_1_1base_1_1State.html">State</a> *state) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Free the memory of the allocated state. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ae659ee971f00c53002fc73384db0aaa6"></a><!-- doxytag: member="ompl::base::DiscreteStateSpace::printState" ref="ae659ee971f00c53002fc73384db0aaa6" args="(const State *state, std::ostream &amp;out) const " -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1DiscreteStateSpace.html#ae659ee971f00c53002fc73384db0aaa6">printState</a> (const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *state, std::ostream &amp;out) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Print a state to a stream. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="acafc4e5db93a4ff66a8a1c5461f84229"></a><!-- doxytag: member="ompl::base::DiscreteStateSpace::printSettings" ref="acafc4e5db93a4ff66a8a1c5461f84229" args="(std::ostream &amp;out) const " -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1DiscreteStateSpace.html#acafc4e5db93a4ff66a8a1c5461f84229">printSettings</a> (std::ostream &amp;out) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Print the settings for this state space to a stream. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a24d08db42cb5a2cdfaff8dfad158adf9"></a><!-- doxytag: member="ompl::base::DiscreteStateSpace::registerProjections" ref="a24d08db42cb5a2cdfaff8dfad158adf9" args="(void)" -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1DiscreteStateSpace.html#a24d08db42cb5a2cdfaff8dfad158adf9">registerProjections</a> (void)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Register the projections for this state space. Usually, this is at least the default projection. These are implicit projections, set by the implementation of the state space. This is called by <a class="el" href="classompl_1_1base_1_1DiscreteStateSpace.html#a6646ed652da596db8e5ea58e656e275f" title="Perform final setup steps. This function is automatically called by the SpaceInformation. If any default projections are to be registered, this call will set them. It is safe to call this function multiple times.">setup()</a>. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a1aa48da9c8ac9ecfc85d3f6c3f281627"></a><!-- doxytag: member="ompl::base::DiscreteStateSpace::getStateCount" ref="a1aa48da9c8ac9ecfc85d3f6c3f281627" args="(void) const " -->
unsigned int&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1DiscreteStateSpace.html#a1aa48da9c8ac9ecfc85d3f6c3f281627">getStateCount</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Returns the number of states possible. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a96a783ee5642564f8852d853302e61f5"></a><!-- doxytag: member="ompl::base::DiscreteStateSpace::getLowerBound" ref="a96a783ee5642564f8852d853302e61f5" args="(void) const " -->
int&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1DiscreteStateSpace.html#a96a783ee5642564f8852d853302e61f5">getLowerBound</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Returns the lowest possible state. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a87a4b712736a14720bff98d4f484b21c"></a><!-- doxytag: member="ompl::base::DiscreteStateSpace::getUpperBound" ref="a87a4b712736a14720bff98d4f484b21c" args="(void) const " -->
int&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1DiscreteStateSpace.html#a87a4b712736a14720bff98d4f484b21c">getUpperBound</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Returns the highest possible state. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a998e66139b0ecb28fbc2743ada6e9af5"></a><!-- doxytag: member="ompl::base::DiscreteStateSpace::setBounds" ref="a998e66139b0ecb28fbc2743ada6e9af5" args="(int lowerBound, int upperBound)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1DiscreteStateSpace.html#a998e66139b0ecb28fbc2743ada6e9af5">setBounds</a> (int lowerBound, int upperBound)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Set the bounds for the states in this space (the states will be in the set [<em>lowerBound</em>, <em>upperBound</em>]. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a6646ed652da596db8e5ea58e656e275f"></a><!-- doxytag: member="ompl::base::DiscreteStateSpace::setup" ref="a6646ed652da596db8e5ea58e656e275f" args="(void)" -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1DiscreteStateSpace.html#a6646ed652da596db8e5ea58e656e275f">setup</a> (void)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Perform final setup steps. This function is automatically called by 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>. If any default projections are to be registered, this call will set them. It is safe to call this function multiple times. <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="a7174ff602c03b57979137dcca4b65e82"></a><!-- doxytag: member="ompl::base::DiscreteStateSpace::lowerBound_" ref="a7174ff602c03b57979137dcca4b65e82" args="" -->
int&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1DiscreteStateSpace.html#a7174ff602c03b57979137dcca4b65e82">lowerBound_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The lowest integer state. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a6ef735722c1289bf0a3fda7a6f6c2dd7"></a><!-- doxytag: member="ompl::base::DiscreteStateSpace::upperBound_" ref="a6ef735722c1289bf0a3fda7a6f6c2dd7" args="" -->
int&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1DiscreteStateSpace.html#a6ef735722c1289bf0a3fda7a6f6c2dd7">upperBound_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The highest integer state. <br/></td></tr>
</table>
<hr/><a name="details" id="details"></a><h2>Detailed Description</h2>
<div class="textblock"><p>A space representing discrete states; i.e. there are a small number of discrete states the system can be in. States are represented as integers [lowerBound, upperBound], where lowerBound and upperBound are inclusive. States do not wrap around; i.e. the distance between state lowerBound and state upperBound is upperBound-lowerBound, NOT 1. </p>

<p>Definition at line <a class="el" href="DiscreteStateSpace_8h_source.html#l00068">68</a> of file <a class="el" href="DiscreteStateSpace_8h_source.html">DiscreteStateSpace.h</a>.</p>
</div><hr/><h2>Member Function Documentation</h2>
<a class="anchor" id="a4e162fbfbcb0b9a46a3a3c3e802c7c49"></a><!-- doxytag: member="ompl::base::DiscreteStateSpace::getMaximumExtent" ref="a4e162fbfbcb0b9a46a3a3c3e802c7c49" args="(void) const " -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">double ompl::base::DiscreteStateSpace::getMaximumExtent </td>
          <td>(</td>
          <td class="paramtype">void&#160;</td>
          <td class="paramname"></td><td>)</td>
          <td> const<code> [virtual]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Get the maximum value a call to <a class="el" href="classompl_1_1base_1_1DiscreteStateSpace.html#ab2324393c8a76c6ff127213b4dc1c90e" title="Computes distance to between two states. This function satisfies the properties of a metric and its r...">distance()</a> can return (or an upper bound). For unbounded state spaces, this function can return infinity. </p>
<dl class="note"><dt><b>Note:</b></dt><dd>Tight upper bounds are preferred because the value of the extent is used in the automatic computation of parameters for planning. If the bounds are less tight, the automatically computed parameters will be less useful. </dd></dl>

<p>Implements <a class="el" href="classompl_1_1base_1_1StateSpace.html#a46ed7d102b6a65a2e2a03e70c7464a37">ompl::base::StateSpace</a>.</p>

<p>Definition at line <a class="el" href="DiscreteStateSpace_8cpp_source.html#l00075">75</a> of file <a class="el" href="DiscreteStateSpace_8cpp_source.html">DiscreteStateSpace.cpp</a>.</p>

</div>
</div>
<a class="anchor" id="afd90bfa97ae9cc027272b52cd7966fec"></a><!-- doxytag: member="ompl::base::DiscreteStateSpace::isDiscrete" ref="afd90bfa97ae9cc027272b52cd7966fec" args="(void) const " -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">bool ompl::base::DiscreteStateSpace::isDiscrete </td>
          <td>(</td>
          <td class="paramtype">void&#160;</td>
          <td class="paramname"></td><td>)</td>
          <td> const<code> [virtual]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Check if the set of states is discrete. </p>
<dl class="note"><dt><b>Note:</b></dt><dd>In fact, because of limited numerical precision, the representation of all spaces is discrete; this function returns true if the corresponding mathematical object is a discrete one. </dd></dl>

<p>Reimplemented from <a class="el" href="classompl_1_1base_1_1StateSpace.html#a0ba7529960eb53ab38ce532236277baf">ompl::base::StateSpace</a>.</p>

<p>Definition at line <a class="el" href="DiscreteStateSpace_8cpp_source.html#l00065">65</a> of file <a class="el" href="DiscreteStateSpace_8cpp_source.html">DiscreteStateSpace.cpp</a>.</p>

</div>
</div>
<hr/>The documentation for this class was generated from the following files:<ul>
<li>src/ompl/base/spaces/<a class="el" href="DiscreteStateSpace_8h_source.html">DiscreteStateSpace.h</a></li>
<li>src/ompl/base/spaces/src/<a class="el" href="DiscreteStateSpace_8cpp_source.html">DiscreteStateSpace.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>