Sophie

Sophie

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

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::RealVectorStateSpace 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_1RealVectorStateSpace.html">RealVectorStateSpace</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::RealVectorStateSpace Class Reference</div>  </div>
</div>
<div class="contents">
<!-- doxytag: class="ompl::base::RealVectorStateSpace" --><!-- doxytag: inherits="ompl::base::StateSpace" -->
<p>A state space representing R<sup>n</sup>. The distance function is the L2 norm.  
 <a href="classompl_1_1base_1_1RealVectorStateSpace.html#details">More...</a></p>

<p><code>#include &lt;<a class="el" href="RealVectorStateSpace_8h_source.html">RealVectorStateSpace.h</a>&gt;</code></p>
<div class="dynheader">
Inheritance diagram for ompl::base::RealVectorStateSpace:</div>
<div class="dyncontent">
<div class="center"><img src="classompl_1_1base_1_1RealVectorStateSpace__inherit__graph.png" border="0" usemap="#ompl_1_1base_1_1RealVectorStateSpace_inherit__map" alt="Inheritance graph"/></div>
<map name="ompl_1_1base_1_1RealVectorStateSpace_inherit__map" id="ompl_1_1base_1_1RealVectorStateSpace_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="37,5,200,35"/></map>
<center><span class="legend">[<a href="graph_legend.html">legend</a>]</span></center></div>

<p><a href="classompl_1_1base_1_1RealVectorStateSpace-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_1RealVectorStateSpace_1_1StateType.html">StateType</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The definition of a state in R<sup>n</sup>  <a href="classompl_1_1base_1_1RealVectorStateSpace_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="a345793d578ff70b4de5fb5c3a8e0a93c"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::RealVectorStateSpace" ref="a345793d578ff70b4de5fb5c3a8e0a93c" args="(unsigned int dim=0)" -->
&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1RealVectorStateSpace.html#a345793d578ff70b4de5fb5c3a8e0a93c">RealVectorStateSpace</a> (unsigned int dim=0)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Constructor. The dimension of of the space needs to be specified. A space representing R<sup>dim</sup> will be instantiated. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a2893436790633b216ed31123b3cf1634"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::addDimension" ref="a2893436790633b216ed31123b3cf1634" args="(double minBound=0.0, double maxBound=0.0)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1RealVectorStateSpace.html#a2893436790633b216ed31123b3cf1634">addDimension</a> (double minBound=0.0, double maxBound=0.0)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Increase the dimensionality of the state space by 1. Optionally, bounds can be specified for this added dimension. <a class="el" href="classompl_1_1base_1_1RealVectorStateSpace.html#a9b72767f319e1744a9860649dcb4950a" 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> will need to be called after adding dimensions. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a03b7187e42e78e2874db062dc88a1bd0"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::addDimension" ref="a03b7187e42e78e2874db062dc88a1bd0" args="(const std::string &amp;name, double minBound=0.0, double maxBound=0.0)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1RealVectorStateSpace.html#a03b7187e42e78e2874db062dc88a1bd0">addDimension</a> (const std::string &amp;name, double minBound=0.0, double maxBound=0.0)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Increase the dimensionality of the state space by 1 and specify the name of this dimension. Optionally, bounds can be specified for this added dimension. <a class="el" href="classompl_1_1base_1_1RealVectorStateSpace.html#a9b72767f319e1744a9860649dcb4950a" 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> will need to be called after adding dimensions. This function is a wrapper for the previous definition of <a class="el" href="classompl_1_1base_1_1RealVectorStateSpace.html#a2893436790633b216ed31123b3cf1634" title="Increase the dimensionality of the state space by 1. Optionally, bounds can be specified for this add...">addDimension()</a>. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ab53c0ef2a517e34f4c387785dd3f8956"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::setBounds" ref="ab53c0ef2a517e34f4c387785dd3f8956" args="(const RealVectorBounds &amp;bounds)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1RealVectorStateSpace.html#ab53c0ef2a517e34f4c387785dd3f8956">setBounds</a> (const <a class="el" href="classompl_1_1base_1_1RealVectorBounds.html">RealVectorBounds</a> &amp;bounds)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Set the bounds of this state space. This defines the range of the space in which sampling is performed. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a592f658c4d3c546d96342146d18b5d13"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::setBounds" ref="a592f658c4d3c546d96342146d18b5d13" args="(double low, double high)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1RealVectorStateSpace.html#a592f658c4d3c546d96342146d18b5d13">setBounds</a> (double low, double high)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Set the bounds of this state space. The bounds for each dimension will be the same: [<em>low</em>, <em>high</em>]. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="aaa05e27e5e613958c89be71f3a2bd6a8"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::getBounds" ref="aaa05e27e5e613958c89be71f3a2bd6a8" args="(void) const " -->
const <a class="el" href="classompl_1_1base_1_1RealVectorBounds.html">RealVectorBounds</a> &amp;&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1RealVectorStateSpace.html#aaa05e27e5e613958c89be71f3a2bd6a8">getBounds</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Get the bounds for this state space. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a415bba6e6653b33fdd531871e0199cb8"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::getDimension" ref="a415bba6e6653b33fdd531871e0199cb8" args="(void) const " -->
virtual unsigned int&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1RealVectorStateSpace.html#a415bba6e6653b33fdd531871e0199cb8">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"><a class="anchor" id="ae5112c5d1bfbe7d69094b71ead4f84ca"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::getDimensionName" ref="ae5112c5d1bfbe7d69094b71ead4f84ca" args="(unsigned int index) const " -->
const std::string &amp;&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1RealVectorStateSpace.html#ae5112c5d1bfbe7d69094b71ead4f84ca">getDimensionName</a> (unsigned int index) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Each dimension can optionally have a name associated to it. If it does, this function returns that name. Return empty string otherwise. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a3b43a37b02d3164f55581c4cda94fa00"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::getDimensionIndex" ref="a3b43a37b02d3164f55581c4cda94fa00" args="(const std::string &amp;name) const " -->
int&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1RealVectorStateSpace.html#a3b43a37b02d3164f55581c4cda94fa00">getDimensionIndex</a> (const std::string &amp;name) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Get the index of a specific dimension, by name. Return -1 if name is not found. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a2d387a4a02fafea56315ddd449703847"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::setDimensionName" ref="a2d387a4a02fafea56315ddd449703847" args="(unsigned int index, const std::string &amp;name)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1RealVectorStateSpace.html#a2d387a4a02fafea56315ddd449703847">setDimensionName</a> (unsigned int index, const std::string &amp;name)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Set the name of a dimension. <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_1RealVectorStateSpace.html#af5a3758aabe1a915a64c99d7c93d692e">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_1RealVectorStateSpace.html#ae9dba965480f0b4771455c79aae8a195" 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="#af5a3758aabe1a915a64c99d7c93d692e"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ae473cc4d0feaefb5e568578cd927d9b9"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::enforceBounds" ref="ae473cc4d0feaefb5e568578cd927d9b9" args="(State *state) const " -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1RealVectorStateSpace.html#ae473cc4d0feaefb5e568578cd927d9b9">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="a8ea04b460df8e8cb638ced218fef71e0"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::satisfiesBounds" ref="a8ea04b460df8e8cb638ced218fef71e0" args="(const State *state) const " -->
virtual bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1RealVectorStateSpace.html#a8ea04b460df8e8cb638ced218fef71e0">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="a2304bbddd850d5b10eaa70142547b67d"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::copyState" ref="a2304bbddd850d5b10eaa70142547b67d" args="(State *destination, const State *source) const " -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1RealVectorStateSpace.html#a2304bbddd850d5b10eaa70142547b67d">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="ae9dba965480f0b4771455c79aae8a195"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::distance" ref="ae9dba965480f0b4771455c79aae8a195" 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_1RealVectorStateSpace.html#ae9dba965480f0b4771455c79aae8a195">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_1RealVectorStateSpace.html#af5a3758aabe1a915a64c99d7c93d692e" 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="a7de4ee53afed57ec78012c764758274e"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::equalStates" ref="a7de4ee53afed57ec78012c764758274e" 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_1RealVectorStateSpace.html#a7de4ee53afed57ec78012c764758274e">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="a5135607e2fedf624b07d5546f8fec2c5"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::interpolate" ref="a5135607e2fedf624b07d5546f8fec2c5" 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_1RealVectorStateSpace.html#a5135607e2fedf624b07d5546f8fec2c5">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="a741fcd3240ca1a34c80f0ea9f141e2e8"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::allocStateSampler" ref="a741fcd3240ca1a34c80f0ea9f141e2e8" 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_1RealVectorStateSpace.html#a741fcd3240ca1a34c80f0ea9f141e2e8">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="a9d460e47e6636871542bdc4f4bc017e3"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::allocState" ref="a9d460e47e6636871542bdc4f4bc017e3" 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_1RealVectorStateSpace.html#a9d460e47e6636871542bdc4f4bc017e3">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="af2ed57519f3da6e87cd96d3c300336cb"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::freeState" ref="af2ed57519f3da6e87cd96d3c300336cb" args="(State *state) const " -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1RealVectorStateSpace.html#af2ed57519f3da6e87cd96d3c300336cb">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">virtual double *&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1RealVectorStateSpace.html#aa263419b2d378049b3315286413d5a2f">getValueAddressAtIndex</a> (<a class="el" href="classompl_1_1base_1_1State.html">State</a> *state, const unsigned int index) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Many states contain a number of double values. This function provides a means to get the memory address of a double value from state <em>state</em> located at position <em>index</em>. The first double value is returned for <em>index</em> = 0. If <em>index</em> is too large (does not point to any double values in the state), the return value is NULL.  <a href="#aa263419b2d378049b3315286413d5a2f"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a2a3d613e6aef0a811f89bfae0ac3f181"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::printState" ref="a2a3d613e6aef0a811f89bfae0ac3f181" 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_1RealVectorStateSpace.html#a2a3d613e6aef0a811f89bfae0ac3f181">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="a7297b3664373e5dbe9dea943f9a49bc4"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::printSettings" ref="a7297b3664373e5dbe9dea943f9a49bc4" args="(std::ostream &amp;out) const " -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1RealVectorStateSpace.html#a7297b3664373e5dbe9dea943f9a49bc4">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="ae9578af74fb1deb62f2ac655e26bd89b"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::registerProjections" ref="ae9578af74fb1deb62f2ac655e26bd89b" args="(void)" -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1RealVectorStateSpace.html#ae9578af74fb1deb62f2ac655e26bd89b">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_1RealVectorStateSpace.html#a9b72767f319e1744a9860649dcb4950a" 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="a9b72767f319e1744a9860649dcb4950a"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::setup" ref="a9b72767f319e1744a9860649dcb4950a" args="(void)" -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1RealVectorStateSpace.html#a9b72767f319e1744a9860649dcb4950a">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="a1d187d416ce5c4d0bc101912e6e7ae7f"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::dimension_" ref="a1d187d416ce5c4d0bc101912e6e7ae7f" args="" -->
unsigned int&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1RealVectorStateSpace.html#a1d187d416ce5c4d0bc101912e6e7ae7f">dimension_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The dimension of the space. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a09ec78ff21dcbec292a4694da8f8ab92"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::bounds_" ref="a09ec78ff21dcbec292a4694da8f8ab92" args="" -->
<a class="el" href="classompl_1_1base_1_1RealVectorBounds.html">RealVectorBounds</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1RealVectorStateSpace.html#a09ec78ff21dcbec292a4694da8f8ab92">bounds_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The bounds of the space (used for sampling) <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a58d503f751e68f0ae946b48b526444f4"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::dimensionNames_" ref="a58d503f751e68f0ae946b48b526444f4" args="" -->
std::vector&lt; std::string &gt;&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1RealVectorStateSpace.html#a58d503f751e68f0ae946b48b526444f4">dimensionNames_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Optional names for individual dimensions. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="abc8aaf3fdd92ce6d9006c1095deeb705"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::dimensionIndex_" ref="abc8aaf3fdd92ce6d9006c1095deeb705" args="" -->
std::map&lt; std::string, <br class="typebreak"/>
unsigned int &gt;&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1RealVectorStateSpace.html#abc8aaf3fdd92ce6d9006c1095deeb705">dimensionIndex_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Map from names to index values for dimensions. <br/></td></tr>
</table>
<hr/><a name="details" id="details"></a><h2>Detailed Description</h2>
<div class="textblock"><p>A state space representing R<sup>n</sup>. The distance function is the L2 norm. </p>

<p>Definition at line <a class="el" href="RealVectorStateSpace_8h_source.html#l00067">67</a> of file <a class="el" href="RealVectorStateSpace_8h_source.html">RealVectorStateSpace.h</a>.</p>
</div><hr/><h2>Member Function Documentation</h2>
<a class="anchor" id="af5a3758aabe1a915a64c99d7c93d692e"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::getMaximumExtent" ref="af5a3758aabe1a915a64c99d7c93d692e" args="(void) const " -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">double ompl::base::RealVectorStateSpace::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_1RealVectorStateSpace.html#ae9dba965480f0b4771455c79aae8a195" 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="RealVectorStateSpace_8cpp_source.html#l00171">171</a> of file <a class="el" href="RealVectorStateSpace_8cpp_source.html">RealVectorStateSpace.cpp</a>.</p>

</div>
</div>
<a class="anchor" id="aa263419b2d378049b3315286413d5a2f"></a><!-- doxytag: member="ompl::base::RealVectorStateSpace::getValueAddressAtIndex" ref="aa263419b2d378049b3315286413d5a2f" args="(State *state, const unsigned int index) const " -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">double * ompl::base::RealVectorStateSpace::getValueAddressAtIndex </td>
          <td>(</td>
          <td class="paramtype"><a class="el" href="classompl_1_1base_1_1State.html">State</a> *&#160;</td>
          <td class="paramname"><em>state</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">const unsigned int&#160;</td>
          <td class="paramname"><em>index</em>&#160;</td>
        </tr>
        <tr>
          <td></td>
          <td>)</td>
          <td></td><td> const<code> [virtual]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Many states contain a number of double values. This function provides a means to get the memory address of a double value from state <em>state</em> located at position <em>index</em>. The first double value is returned for <em>index</em> = 0. If <em>index</em> is too large (does not point to any double values in the state), the return value is NULL. </p>
<dl class="note"><dt><b>Note:</b></dt><dd>This function does <b>not</b> map a state to an array of doubles. There may be components of a state that do not correspond to double values and they are 'invisible' to this function. Furthermore, this function is slow and is not intended for use in the implementation of planners. </dd></dl>

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

<p>Definition at line <a class="el" href="RealVectorStateSpace_8cpp_source.html#l00266">266</a> of file <a class="el" href="RealVectorStateSpace_8cpp_source.html">RealVectorStateSpace.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="RealVectorStateSpace_8h_source.html">RealVectorStateSpace.h</a></li>
<li>src/ompl/base/spaces/src/<a class="el" href="RealVectorStateSpace_8cpp_source.html">RealVectorStateSpace.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>