Sophie

Sophie

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

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::control::ODEStateSpace 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_1control.html">control</a>      </li>
      <li class="navelem"><a class="el" href="classompl_1_1control_1_1ODEStateSpace.html">ODEStateSpace</a>      </li>
    </ul>
  </div>
</div>
<div class="header">
  <div class="summary">
<a href="#nested-classes">Classes</a> &#124;
<a href="#pub-types">Public Types</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::control::ODEStateSpace Class Reference</div>  </div>
</div>
<div class="contents">
<!-- doxytag: class="ompl::control::ODEStateSpace" --><!-- doxytag: inherits="ompl::base::CompoundStateSpace" -->
<p>State space representing ODE states.  
 <a href="classompl_1_1control_1_1ODEStateSpace.html#details">More...</a></p>

<p><code>#include &lt;<a class="el" href="ODEStateSpace_8h_source.html">ODEStateSpace.h</a>&gt;</code></p>
<div class="dynheader">
Inheritance diagram for ompl::control::ODEStateSpace:</div>
<div class="dyncontent">
<div class="center"><img src="classompl_1_1control_1_1ODEStateSpace__inherit__graph.png" border="0" usemap="#ompl_1_1control_1_1ODEStateSpace_inherit__map" alt="Inheritance graph"/></div>
<map name="ompl_1_1control_1_1ODEStateSpace_inherit__map" id="ompl_1_1control_1_1ODEStateSpace_inherit__map">
<area shape="rect" id="node2" href="classompl_1_1base_1_1CompoundStateSpace.html" title="A space to allow the composition of state spaces." alt="" coords="5,83,229,112"/><area shape="rect" id="node4" 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="36,5,199,35"/></map>
<center><span class="legend">[<a href="graph_legend.html">legend</a>]</span></center></div>

<p><a href="classompl_1_1control_1_1ODEStateSpace-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_1control_1_1ODEStateSpace_1_1StateType.html">StateType</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">ODE State. This is a compound state that allows accessing the properties of the bodies the state space is constructed for.  <a href="classompl_1_1control_1_1ODEStateSpace_1_1StateType.html#details">More...</a><br/></td></tr>
<tr><td colspan="2"><h2><a name="pub-types"></a>
Public Types</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">enum &#160;</td><td class="memItemRight" valign="bottom">{ <a class="el" href="classompl_1_1control_1_1ODEStateSpace.html#ab075415388f31633522d44a5418029fdaed833e9de7ff11ae0e1913a2c23222f4">STATE_COLLISION_KNOWN_BIT</a> =  0, 
<a class="el" href="classompl_1_1control_1_1ODEStateSpace.html#ab075415388f31633522d44a5418029fdaa73ce13533ae4274372087653cc91c99">STATE_COLLISION_VALUE_BIT</a> =  1, 
<a class="el" href="classompl_1_1control_1_1ODEStateSpace.html#ab075415388f31633522d44a5418029fda10f9959c7abdf3c6c80c7e0190a0c7fb">STATE_VALIDITY_KNOWN_BIT</a> =  2, 
<a class="el" href="classompl_1_1control_1_1ODEStateSpace.html#ab075415388f31633522d44a5418029fda2b1ca7a8e59afc00ad7aa945589d4607">STATE_VALIDITY_VALUE_BIT</a> =  3
 }</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">&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1control_1_1ODEStateSpace.html#ac895b311341b2fbc01fc140a5d0d654d">ODEStateSpace</a> (const <a class="el" href="classompl_1_1control_1_1ODEEnvironmentPtr.html">ODEEnvironmentPtr</a> &amp;env, double positionWeight=1.0, double linVelWeight=0.5, double angVelWeight=0.5, double orientationWeight=1.0)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Construct a state space representing ODE states.  <a href="#ac895b311341b2fbc01fc140a5d0d654d"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a05f2d0feca87376bfede048f0709232f"></a><!-- doxytag: member="ompl::control::ODEStateSpace::getEnvironment" ref="a05f2d0feca87376bfede048f0709232f" args="(void) const " -->
const <a class="el" href="classompl_1_1control_1_1ODEEnvironmentPtr.html">ODEEnvironmentPtr</a> &amp;&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1control_1_1ODEStateSpace.html#a05f2d0feca87376bfede048f0709232f">getEnvironment</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Get the ODE environment this state space corresponds to. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a2abdf341c56bb3dfcb77f710757bd115"></a><!-- doxytag: member="ompl::control::ODEStateSpace::getNrBodies" ref="a2abdf341c56bb3dfcb77f710757bd115" args="(void) const " -->
unsigned int&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1control_1_1ODEStateSpace.html#a2abdf341c56bb3dfcb77f710757bd115">getNrBodies</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Get the number of bodies state is maintained for. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="aa920d89178817da99722e0fb733e72de"></a><!-- doxytag: member="ompl::control::ODEStateSpace::setDefaultBounds" ref="aa920d89178817da99722e0fb733e72de" args="(void)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1control_1_1ODEStateSpace.html#aa920d89178817da99722e0fb733e72de">setDefaultBounds</a> (void)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">By default, the volume bounds enclosing the geometry of the environment are computed to include all objects in the spaces collision checking is performed (env.collisionSpaces_). The linear and angular velocity bounds are set as -1 to 1 for each dimension. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a572348387ab7d3176a4a1063e6b3009e"></a><!-- doxytag: member="ompl::control::ODEStateSpace::setVolumeBounds" ref="a572348387ab7d3176a4a1063e6b3009e" args="(const base::RealVectorBounds &amp;bounds)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1control_1_1ODEStateSpace.html#a572348387ab7d3176a4a1063e6b3009e">setVolumeBounds</a> (const <a class="el" href="classompl_1_1base_1_1RealVectorBounds.html">base::RealVectorBounds</a> &amp;bounds)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Set the bounds for each of the position subspaces. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a0d779b1d59544cf4bfb90de4def851a5"></a><!-- doxytag: member="ompl::control::ODEStateSpace::setLinearVelocityBounds" ref="a0d779b1d59544cf4bfb90de4def851a5" args="(const base::RealVectorBounds &amp;bounds)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1control_1_1ODEStateSpace.html#a0d779b1d59544cf4bfb90de4def851a5">setLinearVelocityBounds</a> (const <a class="el" href="classompl_1_1base_1_1RealVectorBounds.html">base::RealVectorBounds</a> &amp;bounds)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Set the bounds for each of the linear velocity subspaces. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="aa7390b20c14d2e09f803b46d2fa9aeed"></a><!-- doxytag: member="ompl::control::ODEStateSpace::setAngularVelocityBounds" ref="aa7390b20c14d2e09f803b46d2fa9aeed" args="(const base::RealVectorBounds &amp;bounds)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1control_1_1ODEStateSpace.html#aa7390b20c14d2e09f803b46d2fa9aeed">setAngularVelocityBounds</a> (const <a class="el" href="classompl_1_1base_1_1RealVectorBounds.html">base::RealVectorBounds</a> &amp;bounds)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Set the bounds for each of the angular velocity subspaces. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a17b12710391410fc3fd0cc6e3eca9f1f"></a><!-- doxytag: member="ompl::control::ODEStateSpace::readState" ref="a17b12710391410fc3fd0cc6e3eca9f1f" args="(base::State *state) const " -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1control_1_1ODEStateSpace.html#a17b12710391410fc3fd0cc6e3eca9f1f">readState</a> (<a class="el" href="classompl_1_1base_1_1State.html">base::State</a> *state) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Read the parameters of the ODE bodies and store them in <em>state</em>. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a7cebbdb127b722b783fab82f1873d71d"></a><!-- doxytag: member="ompl::control::ODEStateSpace::writeState" ref="a7cebbdb127b722b783fab82f1873d71d" args="(const base::State *state) const " -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1control_1_1ODEStateSpace.html#a7cebbdb127b722b783fab82f1873d71d">writeState</a> (const <a class="el" href="classompl_1_1base_1_1State.html">base::State</a> *state) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Set the parameters of the ODE bodies to be the ones read from <em>state</em>. The code will technically work if this function is called from multiple threads simultaneously, but the results are unpredictable. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a5b061f3f0cfeb29a70ac6aaa9f2add11"></a><!-- doxytag: member="ompl::control::ODEStateSpace::satisfiesBoundsExceptRotation" ref="a5b061f3f0cfeb29a70ac6aaa9f2add11" args="(const StateType *state) const " -->
bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1control_1_1ODEStateSpace.html#a5b061f3f0cfeb29a70ac6aaa9f2add11">satisfiesBoundsExceptRotation</a> (const <a class="el" href="classompl_1_1control_1_1ODEStateSpace_1_1StateType.html">StateType</a> *state) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">This is a convenience function provided for optimization purposes. It checks whether a state satisfies its bounds. Typically, in the process of simulation the rotations remain valid (very slightly out of bounds), so there is no point in updating or checking them. This function checks all other bounds (position, linear and agular velocities) <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a6a322bef2a5ca80db337ecd977235be9"></a><!-- doxytag: member="ompl::control::ODEStateSpace::allocState" ref="a6a322bef2a5ca80db337ecd977235be9" args="(void) const " -->
virtual <a class="el" href="classompl_1_1base_1_1State.html">base::State</a> *&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1control_1_1ODEStateSpace.html#a6a322bef2a5ca80db337ecd977235be9">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="a22e049b3b64c43fc4dc5bf8020c0bbd2"></a><!-- doxytag: member="ompl::control::ODEStateSpace::freeState" ref="a22e049b3b64c43fc4dc5bf8020c0bbd2" args="(base::State *state) const " -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1control_1_1ODEStateSpace.html#a22e049b3b64c43fc4dc5bf8020c0bbd2">freeState</a> (<a class="el" href="classompl_1_1base_1_1State.html">base::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="a74b7cd10a3e11b62f5e3d6c0bda79d92"></a><!-- doxytag: member="ompl::control::ODEStateSpace::copyState" ref="a74b7cd10a3e11b62f5e3d6c0bda79d92" args="(base::State *destination, const base::State *source) const " -->
virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1control_1_1ODEStateSpace.html#a74b7cd10a3e11b62f5e3d6c0bda79d92">copyState</a> (<a class="el" href="classompl_1_1base_1_1State.html">base::State</a> *destination, const <a class="el" href="classompl_1_1base_1_1State.html">base::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="a1f158dfa526d5573dda8dd31851ba0cf"></a><!-- doxytag: member="ompl::control::ODEStateSpace::evaluateCollision" ref="a1f158dfa526d5573dda8dd31851ba0cf" args="(const base::State *source) const " -->
virtual bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1control_1_1ODEStateSpace.html#a1f158dfa526d5573dda8dd31851ba0cf">evaluateCollision</a> (const <a class="el" href="classompl_1_1base_1_1State.html">base::State</a> *source) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Fill the <a class="el" href="classompl_1_1control_1_1ODEStateSpace.html#ab075415388f31633522d44a5418029fdaa73ce13533ae4274372087653cc91c99" title="Index of bit in StateType::collision indicating whether a state is in collision or not...">ODEStateSpace::STATE_COLLISION_VALUE_BIT</a> of <a class="el" href="classompl_1_1control_1_1ODEStateSpace_1_1StateType.html#a1ba5dfafa14052fd4a9ee317cddcd596" title="Flag containing information about state validity.">StateType::collision</a> member of a state, if unspecified. Return the value value of that bit. <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="a14bed6203a14e8dfdb10f8a7ede817da"></a><!-- doxytag: member="ompl::control::ODEStateSpace::env_" ref="a14bed6203a14e8dfdb10f8a7ede817da" args="" -->
<a class="el" href="classompl_1_1control_1_1ODEEnvironmentPtr.html">ODEEnvironmentPtr</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1control_1_1ODEStateSpace.html#a14bed6203a14e8dfdb10f8a7ede817da">env_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Representation of the ODE parameters OMPL needs to plan. <br/></td></tr>
</table>
<hr/><a name="details" id="details"></a><h2>Detailed Description</h2>
<div class="textblock"><p>State space representing ODE states. </p>

<p>Definition at line <a class="el" href="ODEStateSpace_8h_source.html#l00051">51</a> of file <a class="el" href="ODEStateSpace_8h_source.html">ODEStateSpace.h</a>.</p>
</div><hr/><h2>Member Enumeration Documentation</h2>
<a class="anchor" id="ab075415388f31633522d44a5418029fd"></a><!-- doxytag: member="ompl::control::ODEStateSpace::@0" ref="ab075415388f31633522d44a5418029fd" args="" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">anonymous enum</td>
        </tr>
      </table>
</div>
<div class="memdoc">
<dl><dt><b>Enumerator: </b></dt><dd><table border="0" cellspacing="2" cellpadding="0">
<tr><td valign="top"><em><a class="anchor" id="ab075415388f31633522d44a5418029fdaed833e9de7ff11ae0e1913a2c23222f4"></a><!-- doxytag: member="STATE_COLLISION_KNOWN_BIT" ref="ab075415388f31633522d44a5418029fdaed833e9de7ff11ae0e1913a2c23222f4" args="" -->STATE_COLLISION_KNOWN_BIT</em>&nbsp;</td><td>
<p>Index of bit in <a class="el" href="classompl_1_1control_1_1ODEStateSpace_1_1StateType.html#a1ba5dfafa14052fd4a9ee317cddcd596" title="Flag containing information about state validity.">StateType::collision</a> indicating whether it is known if a state is in collision or not. Initially this is 0. The value of this bit is updated by <a class="el" href="classompl_1_1control_1_1ODEStateSpace.html#a1f158dfa526d5573dda8dd31851ba0cf" title="Fill the ODEStateSpace::STATE_COLLISION_VALUE_BIT of StateType::collision member of a state...">ODEStateSpace::evaluateCollision()</a> and ODEControlSpace::propagate(). </p>
</td></tr>
<tr><td valign="top"><em><a class="anchor" id="ab075415388f31633522d44a5418029fdaa73ce13533ae4274372087653cc91c99"></a><!-- doxytag: member="STATE_COLLISION_VALUE_BIT" ref="ab075415388f31633522d44a5418029fdaa73ce13533ae4274372087653cc91c99" args="" -->STATE_COLLISION_VALUE_BIT</em>&nbsp;</td><td>
<p>Index of bit in <a class="el" href="classompl_1_1control_1_1ODEStateSpace_1_1StateType.html#a1ba5dfafa14052fd4a9ee317cddcd596" title="Flag containing information about state validity.">StateType::collision</a> indicating whether a state is in collision or not. Initially the value of this field is unspecified. The value gains meaning (1 or 0) when <a class="el" href="classompl_1_1control_1_1ODEStateSpace.html#ab075415388f31633522d44a5418029fdaed833e9de7ff11ae0e1913a2c23222f4" title="Index of bit in StateType::collision indicating whether it is known if a state is in collision or not...">ODEStateSpace::STATE_COLLISION_KNOWN_BIT</a> becomes 1. The value of this bit is updated by <a class="el" href="classompl_1_1control_1_1ODEStateSpace.html#a1f158dfa526d5573dda8dd31851ba0cf" title="Fill the ODEStateSpace::STATE_COLLISION_VALUE_BIT of StateType::collision member of a state...">ODEStateSpace::evaluateCollision()</a> and ODEControlSpace::propagate(). A value of 1 implies that there is no collision for which <a class="el" href="classompl_1_1control_1_1ODEEnvironment.html#ad9a735c35a15101711f7ba96e44ea15e" title="Decide whether a collision is a valid one or not. In some cases, collisions between some bodies can b...">ODEEnvironment::isValidCollision()</a> returns false. </p>
</td></tr>
<tr><td valign="top"><em><a class="anchor" id="ab075415388f31633522d44a5418029fda10f9959c7abdf3c6c80c7e0190a0c7fb"></a><!-- doxytag: member="STATE_VALIDITY_KNOWN_BIT" ref="ab075415388f31633522d44a5418029fda10f9959c7abdf3c6c80c7e0190a0c7fb" args="" -->STATE_VALIDITY_KNOWN_BIT</em>&nbsp;</td><td>
<p>Index of bit in <a class="el" href="classompl_1_1control_1_1ODEStateSpace_1_1StateType.html#a1ba5dfafa14052fd4a9ee317cddcd596" title="Flag containing information about state validity.">StateType::collision</a> indicating whether it is known if a state is in valid or not. Initially this is 0. The value of this bit is updated by <a class="el" href="classompl_1_1control_1_1ODEStateValidityChecker.html#a39d54933a917c0891047bdd955930544" title="A state is considered valid if it is within bounds and not in collision.">ODEStateValidityChecker::isValid()</a>. This bit is only used if the <a class="el" href="classompl_1_1control_1_1ODEStateValidityChecker.html" title="The simplest state validity checker: all states are valid.">ODEStateValidityChecker</a> is used. </p>
</td></tr>
<tr><td valign="top"><em><a class="anchor" id="ab075415388f31633522d44a5418029fda2b1ca7a8e59afc00ad7aa945589d4607"></a><!-- doxytag: member="STATE_VALIDITY_VALUE_BIT" ref="ab075415388f31633522d44a5418029fda2b1ca7a8e59afc00ad7aa945589d4607" args="" -->STATE_VALIDITY_VALUE_BIT</em>&nbsp;</td><td>
<p>Index of bit in <a class="el" href="classompl_1_1control_1_1ODEStateSpace_1_1StateType.html#a1ba5dfafa14052fd4a9ee317cddcd596" title="Flag containing information about state validity.">StateType::collision</a> indicating whether a state is valid or not. Initially the value of this field is unspecified. The value gains meaning (1 or 0) when <a class="el" href="classompl_1_1control_1_1ODEStateSpace.html#ab075415388f31633522d44a5418029fda10f9959c7abdf3c6c80c7e0190a0c7fb" title="Index of bit in StateType::collision indicating whether it is known if a state is in valid or not...">ODEStateSpace::STATE_VALIDITY_KNOWN_BIT</a> becomes 1. The value of this bit is updated by ODEEnvironment::isValid(). A value of 1 implies that a state is valid. This bit is only used if the <a class="el" href="classompl_1_1control_1_1ODEStateValidityChecker.html" title="The simplest state validity checker: all states are valid.">ODEStateValidityChecker</a> is used. </p>
</td></tr>
</table>
</dd>
</dl>

<p>Definition at line <a class="el" href="ODEStateSpace_8h_source.html#l00055">55</a> of file <a class="el" href="ODEStateSpace_8h_source.html">ODEStateSpace.h</a>.</p>

</div>
</div>
<hr/><h2>Constructor &amp; Destructor Documentation</h2>
<a class="anchor" id="ac895b311341b2fbc01fc140a5d0d654d"></a><!-- doxytag: member="ompl::control::ODEStateSpace::ODEStateSpace" ref="ac895b311341b2fbc01fc140a5d0d654d" args="(const ODEEnvironmentPtr &amp;env, double positionWeight=1.0, double linVelWeight=0.5, double angVelWeight=0.5, double orientationWeight=1.0)" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">ompl::control::ODEStateSpace::ODEStateSpace </td>
          <td>(</td>
          <td class="paramtype">const <a class="el" href="classompl_1_1control_1_1ODEEnvironmentPtr.html">ODEEnvironmentPtr</a> &amp;&#160;</td>
          <td class="paramname"><em>env</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">double&#160;</td>
          <td class="paramname"><em>positionWeight</em> = <code>1.0</code>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">double&#160;</td>
          <td class="paramname"><em>linVelWeight</em> = <code>0.5</code>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">double&#160;</td>
          <td class="paramname"><em>angVelWeight</em> = <code>0.5</code>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">double&#160;</td>
          <td class="paramname"><em>orientationWeight</em> = <code>1.0</code>&#160;</td>
        </tr>
        <tr>
          <td></td>
          <td>)</td>
          <td></td><td></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Construct a state space representing ODE states. </p>
<p>This will be a compound state space with 4 components for each body in <em>env.stateBodies_</em>. The 4 subspaces constructed for each body are: position (R<sup>3</sup>), linear velocity (R<sup>3</sup>), angular velocity (R<sup>3</sup>) and orientation (SO(3)). Default bounds are set by calling <a class="el" href="classompl_1_1control_1_1ODEStateSpace.html#aa920d89178817da99722e0fb733e72de" title="By default, the volume bounds enclosing the geometry of the environment are computed to include all o...">setDefaultBounds()</a>.</p>
<dl><dt><b>Parameters:</b></dt><dd>
  <table class="params">
    <tr><td class="paramname">env</td><td>the environment to construct the state space for </td></tr>
    <tr><td class="paramname">positionWeight</td><td>the weight to pass to CompoundStateSpace::addSubSpace() for position subspaces </td></tr>
    <tr><td class="paramname">linVelWeight</td><td>the weight to pass to CompoundStateSpace::addSubSpace() for linear velocity subspaces </td></tr>
    <tr><td class="paramname">angVelWeight</td><td>the weight to pass to CompoundStateSpace::addSubSpace() for angular velocity subspaces </td></tr>
    <tr><td class="paramname">orientationWeight</td><td>the weight to pass to CompoundStateSpace::addSubSpace() for orientation subspaces </td></tr>
  </table>
  </dd>
</dl>

<p>Definition at line <a class="el" href="ODEStateSpace_8cpp_source.html#l00043">43</a> of file <a class="el" href="ODEStateSpace_8cpp_source.html">ODEStateSpace.cpp</a>.</p>

</div>
</div>
<hr/>The documentation for this class was generated from the following files:<ul>
<li>src/ompl/extensions/ode/<a class="el" href="ODEStateSpace_8h_source.html">ODEStateSpace.h</a></li>
<li>src/ompl/extensions/ode/src/<a class="el" href="ODEStateSpace_8cpp_source.html">ODEStateSpace.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:43 by&#160;<a href="http://www.doxygen.org/index.html">doxygen</a> 1.7.4</div>
</div>
</div>
</body>
</html>