Sophie

Sophie

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

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: src/ompl/extensions/ode/src/ODEStateSpace.cpp Source File</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="dir_f5421e52a658cd938113ed6044324834.html">src</a>      </li>
      <li class="navelem"><a class="el" href="dir_ae92c2ff78847f0cb49b545f9089bbbc.html">ompl</a>      </li>
      <li class="navelem"><a class="el" href="dir_1ebcd69eafda777e1b7ee573415af9b3.html">extensions</a>      </li>
      <li class="navelem"><a class="el" href="dir_1b236733af466129d307db6fd8c491fe.html">ode</a>      </li>
      <li class="navelem"><a class="el" href="dir_43adbf5ba310c2c668983d1f351bbdaf.html">src</a>      </li>
    </ul>
  </div>
</div>
<div class="header">
  <div class="headertitle">
<div class="title">ODEStateSpace.cpp</div>  </div>
</div>
<div class="contents">
<div class="fragment"><pre class="fragment"><a name="l00001"></a>00001 <span class="comment">/*********************************************************************</span>
<a name="l00002"></a>00002 <span class="comment">* Software License Agreement (BSD License)</span>
<a name="l00003"></a>00003 <span class="comment">*</span>
<a name="l00004"></a>00004 <span class="comment">*  Copyright (c) 2010, Rice University</span>
<a name="l00005"></a>00005 <span class="comment">*  All rights reserved.</span>
<a name="l00006"></a>00006 <span class="comment">*</span>
<a name="l00007"></a>00007 <span class="comment">*  Redistribution and use in source and binary forms, with or without</span>
<a name="l00008"></a>00008 <span class="comment">*  modification, are permitted provided that the following conditions</span>
<a name="l00009"></a>00009 <span class="comment">*  are met:</span>
<a name="l00010"></a>00010 <span class="comment">*</span>
<a name="l00011"></a>00011 <span class="comment">*   * Redistributions of source code must retain the above copyright</span>
<a name="l00012"></a>00012 <span class="comment">*     notice, this list of conditions and the following disclaimer.</span>
<a name="l00013"></a>00013 <span class="comment">*   * Redistributions in binary form must reproduce the above</span>
<a name="l00014"></a>00014 <span class="comment">*     copyright notice, this list of conditions and the following</span>
<a name="l00015"></a>00015 <span class="comment">*     disclaimer in the documentation and/or other materials provided</span>
<a name="l00016"></a>00016 <span class="comment">*     with the distribution.</span>
<a name="l00017"></a>00017 <span class="comment">*   * Neither the name of the Rice University nor the names of its</span>
<a name="l00018"></a>00018 <span class="comment">*     contributors may be used to endorse or promote products derived</span>
<a name="l00019"></a>00019 <span class="comment">*     from this software without specific prior written permission.</span>
<a name="l00020"></a>00020 <span class="comment">*</span>
<a name="l00021"></a>00021 <span class="comment">*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS</span>
<a name="l00022"></a>00022 <span class="comment">*  &quot;AS IS&quot; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT</span>
<a name="l00023"></a>00023 <span class="comment">*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS</span>
<a name="l00024"></a>00024 <span class="comment">*  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE</span>
<a name="l00025"></a>00025 <span class="comment">*  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,</span>
<a name="l00026"></a>00026 <span class="comment">*  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,</span>
<a name="l00027"></a>00027 <span class="comment">*  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;</span>
<a name="l00028"></a>00028 <span class="comment">*  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER</span>
<a name="l00029"></a>00029 <span class="comment">*  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT</span>
<a name="l00030"></a>00030 <span class="comment">*  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN</span>
<a name="l00031"></a>00031 <span class="comment">*  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE</span>
<a name="l00032"></a>00032 <span class="comment">*  POSSIBILITY OF SUCH DAMAGE.</span>
<a name="l00033"></a>00033 <span class="comment">*********************************************************************/</span>
<a name="l00034"></a>00034 
<a name="l00035"></a>00035 <span class="comment">/* Author: Ioan Sucan */</span>
<a name="l00036"></a>00036 
<a name="l00037"></a>00037 <span class="preprocessor">#include &quot;ompl/extensions/ode/ODEStateSpace.h&quot;</span>
<a name="l00038"></a>00038 <span class="preprocessor">#include &quot;ompl/util/Console.h&quot;</span>
<a name="l00039"></a>00039 <span class="preprocessor">#include &lt;boost/lexical_cast.hpp&gt;</span>
<a name="l00040"></a>00040 <span class="preprocessor">#include &lt;limits&gt;</span>
<a name="l00041"></a>00041 <span class="preprocessor">#include &lt;queue&gt;</span>
<a name="l00042"></a>00042 
<a name="l00043"></a><a class="code" href="classompl_1_1control_1_1ODEStateSpace.html#ac895b311341b2fbc01fc140a5d0d654d">00043</a> <a class="code" href="classompl_1_1control_1_1ODEStateSpace.html#ac895b311341b2fbc01fc140a5d0d654d" title="Construct a state space representing ODE states.">ompl::control::ODEStateSpace::ODEStateSpace</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1control_1_1ODEEnvironmentPtr.html" title="A boost shared pointer wrapper for ompl::control::ODEEnvironment.">ODEEnvironmentPtr</a> &amp;env,
<a name="l00044"></a>00044                                                   <span class="keywordtype">double</span> positionWeight, <span class="keywordtype">double</span> linVelWeight, <span class="keywordtype">double</span> angVelWeight, <span class="keywordtype">double</span> orientationWeight) :
<a name="l00045"></a>00045     base::CompoundStateSpace(), env_(env)
<a name="l00046"></a>00046 {
<a name="l00047"></a>00047     <a class="code" href="classompl_1_1base_1_1StateSpace.html#ad12cc022ef531dcb563f6d3d13b847ad" title="Set the name of the state space.">setName</a>(<span class="stringliteral">&quot;ODE&quot;</span> + <a class="code" href="classompl_1_1base_1_1StateSpace.html#a90015676df178b4406a8ab8399f0624c" title="Get the name of the state space.">getName</a>());
<a name="l00048"></a>00048     <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i &lt; <a class="code" href="classompl_1_1control_1_1ODEStateSpace.html#a14bed6203a14e8dfdb10f8a7ede817da" title="Representation of the ODE parameters OMPL needs to plan.">env_</a>-&gt;stateBodies_.size() ; ++i)
<a name="l00049"></a>00049     {
<a name="l00050"></a>00050         std::string body = <span class="stringliteral">&quot;:B&quot;</span> + boost::lexical_cast&lt;std::string&gt;(i);
<a name="l00051"></a>00051 
<a name="l00052"></a>00052         <a class="code" href="classompl_1_1base_1_1CompoundStateSpace.html#aba4aafa2e39b134bf55c5a2ba17d29af" title="Adds a new state space as part of the compound state space. For computing distances within the compou...">addSubSpace</a>(<a class="code" href="classompl_1_1base_1_1StateSpacePtr.html" title="A boost shared pointer wrapper for ompl::base::StateSpace.">base::StateSpacePtr</a>(<span class="keyword">new</span> <a class="code" href="classompl_1_1base_1_1RealVectorStateSpace.html" title="A state space representing Rn. The distance function is the L2 norm.">base::RealVectorStateSpace</a>(3)), positionWeight); <span class="comment">// position</span>
<a name="l00053"></a>00053         <a class="code" href="classompl_1_1base_1_1CompoundStateSpace.html#ae5f43ed0a30998604b18f50b007455b4" title="The state spaces that make up the compound state space.">components_</a>.back()-&gt;setName(<a class="code" href="classompl_1_1base_1_1CompoundStateSpace.html#ae5f43ed0a30998604b18f50b007455b4" title="The state spaces that make up the compound state space.">components_</a>.back()-&gt;getName() + body + <span class="stringliteral">&quot;:position&quot;</span>);
<a name="l00054"></a>00054 
<a name="l00055"></a>00055         <a class="code" href="classompl_1_1base_1_1CompoundStateSpace.html#aba4aafa2e39b134bf55c5a2ba17d29af" title="Adds a new state space as part of the compound state space. For computing distances within the compou...">addSubSpace</a>(<a class="code" href="classompl_1_1base_1_1StateSpacePtr.html" title="A boost shared pointer wrapper for ompl::base::StateSpace.">base::StateSpacePtr</a>(<span class="keyword">new</span> <a class="code" href="classompl_1_1base_1_1RealVectorStateSpace.html" title="A state space representing Rn. The distance function is the L2 norm.">base::RealVectorStateSpace</a>(3)), linVelWeight);   <span class="comment">// linear velocity</span>
<a name="l00056"></a>00056         <a class="code" href="classompl_1_1base_1_1CompoundStateSpace.html#ae5f43ed0a30998604b18f50b007455b4" title="The state spaces that make up the compound state space.">components_</a>.back()-&gt;setName(<a class="code" href="classompl_1_1base_1_1CompoundStateSpace.html#ae5f43ed0a30998604b18f50b007455b4" title="The state spaces that make up the compound state space.">components_</a>.back()-&gt;getName() + body + <span class="stringliteral">&quot;:linvel&quot;</span>);
<a name="l00057"></a>00057 
<a name="l00058"></a>00058         <a class="code" href="classompl_1_1base_1_1CompoundStateSpace.html#aba4aafa2e39b134bf55c5a2ba17d29af" title="Adds a new state space as part of the compound state space. For computing distances within the compou...">addSubSpace</a>(<a class="code" href="classompl_1_1base_1_1StateSpacePtr.html" title="A boost shared pointer wrapper for ompl::base::StateSpace.">base::StateSpacePtr</a>(<span class="keyword">new</span> <a class="code" href="classompl_1_1base_1_1RealVectorStateSpace.html" title="A state space representing Rn. The distance function is the L2 norm.">base::RealVectorStateSpace</a>(3)), angVelWeight);   <span class="comment">// angular velocity</span>
<a name="l00059"></a>00059         <a class="code" href="classompl_1_1base_1_1CompoundStateSpace.html#ae5f43ed0a30998604b18f50b007455b4" title="The state spaces that make up the compound state space.">components_</a>.back()-&gt;setName(<a class="code" href="classompl_1_1base_1_1CompoundStateSpace.html#ae5f43ed0a30998604b18f50b007455b4" title="The state spaces that make up the compound state space.">components_</a>.back()-&gt;getName() + body + <span class="stringliteral">&quot;:angvel&quot;</span>);
<a name="l00060"></a>00060 
<a name="l00061"></a>00061         <a class="code" href="classompl_1_1base_1_1CompoundStateSpace.html#aba4aafa2e39b134bf55c5a2ba17d29af" title="Adds a new state space as part of the compound state space. For computing distances within the compou...">addSubSpace</a>(<a class="code" href="classompl_1_1base_1_1StateSpacePtr.html" title="A boost shared pointer wrapper for ompl::base::StateSpace.">base::StateSpacePtr</a>(<span class="keyword">new</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace.html" title="A state space representing SO(3). The internal representation is done with quaternions. The distance between states is the angle between quaternions and interpolation is done with slerp.">base::SO3StateSpace</a>()), orientationWeight);      <span class="comment">// orientation</span>
<a name="l00062"></a>00062         <a class="code" href="classompl_1_1base_1_1CompoundStateSpace.html#ae5f43ed0a30998604b18f50b007455b4" title="The state spaces that make up the compound state space.">components_</a>.back()-&gt;setName(<a class="code" href="classompl_1_1base_1_1CompoundStateSpace.html#ae5f43ed0a30998604b18f50b007455b4" title="The state spaces that make up the compound state space.">components_</a>.back()-&gt;getName() + body + <span class="stringliteral">&quot;:orientation&quot;</span>);
<a name="l00063"></a>00063     }
<a name="l00064"></a>00064     <a class="code" href="classompl_1_1base_1_1CompoundStateSpace.html#a7aca5d3cfc2ae6bc5b2543a88ef5cb9c" title="Lock this state space. This means no further spaces can be added as components. This function can be ...">lock</a>();
<a name="l00065"></a>00065     <a class="code" 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>();
<a name="l00066"></a>00066 }
<a name="l00067"></a>00067 
<a name="l00068"></a><a class="code" href="classompl_1_1control_1_1ODEStateSpace.html#aa920d89178817da99722e0fb733e72de">00068</a> <span class="keywordtype">void</span> <a class="code" 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...">ompl::control::ODEStateSpace::setDefaultBounds</a>(<span class="keywordtype">void</span>)
<a name="l00069"></a>00069 {
<a name="l00070"></a>00070     <span class="comment">// limit all velocities to 1 m/s, 1 rad/s, respectively</span>
<a name="l00071"></a>00071     <a class="code" href="classompl_1_1base_1_1RealVectorBounds.html" title="The lower and upper bounds for an Rn space.">base::RealVectorBounds</a> bounds1(3);
<a name="l00072"></a>00072     bounds1.<a class="code" href="classompl_1_1base_1_1RealVectorBounds.html#a6f63c8d793a056e2160e5d9d85c27a58" title="Set the lower bound in each dimension to a specific value.">setLow</a>(-1);
<a name="l00073"></a>00073     bounds1.<a class="code" href="classompl_1_1base_1_1RealVectorBounds.html#a756253c602ddc6bd299dc9c870fadfee" title="Set the upper bound in each dimension to a specific value.">setHigh</a>(1);
<a name="l00074"></a>00074     setLinearVelocityBounds(bounds1);
<a name="l00075"></a>00075     setAngularVelocityBounds(bounds1);
<a name="l00076"></a>00076 
<a name="l00077"></a>00077     <span class="comment">// find the bounding box that contains all geoms included in the collision spaces</span>
<a name="l00078"></a>00078     <span class="keywordtype">double</span> mX, mY, mZ, MX, MY, MZ;
<a name="l00079"></a>00079     mX = mY = mZ = std::numeric_limits&lt;double&gt;::infinity();
<a name="l00080"></a>00080     MX = MY = MZ = -std::numeric_limits&lt;double&gt;::infinity();
<a name="l00081"></a>00081     <span class="keywordtype">bool</span> found = <span class="keyword">false</span>;
<a name="l00082"></a>00082 
<a name="l00083"></a>00083     std::queue&lt;dSpaceID&gt; spaces;
<a name="l00084"></a>00084     <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i &lt; env_-&gt;collisionSpaces_.size() ; ++i)
<a name="l00085"></a>00085         spaces.push(env_-&gt;collisionSpaces_[i]);
<a name="l00086"></a>00086 
<a name="l00087"></a>00087     <span class="keywordflow">while</span> (!spaces.empty())
<a name="l00088"></a>00088     {
<a name="l00089"></a>00089         dSpaceID space = spaces.front();
<a name="l00090"></a>00090         spaces.pop();
<a name="l00091"></a>00091 
<a name="l00092"></a>00092         <span class="keywordtype">int</span> n = dSpaceGetNumGeoms(space);
<a name="l00093"></a>00093 
<a name="l00094"></a>00094         <span class="keywordflow">for</span> (<span class="keywordtype">int</span> j = 0 ; j &lt; n ; ++j)
<a name="l00095"></a>00095         {
<a name="l00096"></a>00096             dGeomID geom = dSpaceGetGeom(space, j);
<a name="l00097"></a>00097             <span class="keywordflow">if</span> (dGeomIsSpace(geom))
<a name="l00098"></a>00098                 spaces.push((dSpaceID)geom);
<a name="l00099"></a>00099             <span class="keywordflow">else</span>
<a name="l00100"></a>00100             {
<a name="l00101"></a>00101                 <span class="keywordtype">bool</span> valid = <span class="keyword">true</span>;
<a name="l00102"></a>00102                 dReal aabb[6];
<a name="l00103"></a>00103                 dGeomGetAABB(geom, aabb);
<a name="l00104"></a>00104 
<a name="l00105"></a>00105                 <span class="comment">// things like planes are infinite; we want to ignore those</span>
<a name="l00106"></a>00106                 <span class="keywordflow">for</span> (<span class="keywordtype">int</span> k = 0 ; k &lt; 6 ; ++k)
<a name="l00107"></a>00107                     <span class="keywordflow">if</span> (fabs(aabb[k]) &gt;= std::numeric_limits&lt;dReal&gt;::max())
<a name="l00108"></a>00108                     {
<a name="l00109"></a>00109                         valid = <span class="keyword">false</span>;
<a name="l00110"></a>00110                         <span class="keywordflow">break</span>;
<a name="l00111"></a>00111                     }
<a name="l00112"></a>00112                 <span class="keywordflow">if</span> (valid)
<a name="l00113"></a>00113                 {
<a name="l00114"></a>00114                     found = <span class="keyword">true</span>;
<a name="l00115"></a>00115                     <span class="keywordflow">if</span> (aabb[0] &lt; mX) mX = aabb[0];
<a name="l00116"></a>00116                     <span class="keywordflow">if</span> (aabb[1] &gt; MX) MX = aabb[1];
<a name="l00117"></a>00117                     <span class="keywordflow">if</span> (aabb[2] &lt; mY) mY = aabb[2];
<a name="l00118"></a>00118                     <span class="keywordflow">if</span> (aabb[3] &gt; MY) MY = aabb[3];
<a name="l00119"></a>00119                     <span class="keywordflow">if</span> (aabb[4] &lt; mZ) mZ = aabb[4];
<a name="l00120"></a>00120                     <span class="keywordflow">if</span> (aabb[5] &gt; MZ) MZ = aabb[5];
<a name="l00121"></a>00121                 }
<a name="l00122"></a>00122             }
<a name="l00123"></a>00123         }
<a name="l00124"></a>00124     }
<a name="l00125"></a>00125 
<a name="l00126"></a>00126     <span class="keywordflow">if</span> (found)
<a name="l00127"></a>00127     {
<a name="l00128"></a>00128         <span class="keywordtype">double</span> dx = MX - mX;
<a name="l00129"></a>00129         <span class="keywordtype">double</span> dy = MY - mY;
<a name="l00130"></a>00130         <span class="keywordtype">double</span> dz = MZ - mZ;
<a name="l00131"></a>00131         <span class="keywordtype">double</span> dM = std::max(dx, std::max(dy, dz));
<a name="l00132"></a>00132 
<a name="l00133"></a>00133         <span class="comment">// add 10% in each dimension + 1% of the max dimension</span>
<a name="l00134"></a>00134         dx = dx / 10.0 + dM / 100.0;
<a name="l00135"></a>00135         dy = dy / 10.0 + dM / 100.0;
<a name="l00136"></a>00136         dz = dz / 10.0 + dM / 100.0;
<a name="l00137"></a>00137 
<a name="l00138"></a>00138         bounds1.<a class="code" href="classompl_1_1base_1_1RealVectorBounds.html#a36ebebb6a9e116093581afbd07425baa" title="Lower bound.">low</a>[0] = mX - dx;
<a name="l00139"></a>00139         bounds1.<a class="code" href="classompl_1_1base_1_1RealVectorBounds.html#a06827561804a768d6ee86a20a664153c" title="Upper bound.">high</a>[0] = MX + dx;
<a name="l00140"></a>00140         bounds1.<a class="code" href="classompl_1_1base_1_1RealVectorBounds.html#a36ebebb6a9e116093581afbd07425baa" title="Lower bound.">low</a>[1] = mY - dy;
<a name="l00141"></a>00141         bounds1.<a class="code" href="classompl_1_1base_1_1RealVectorBounds.html#a06827561804a768d6ee86a20a664153c" title="Upper bound.">high</a>[1] = MY + dy;
<a name="l00142"></a>00142         bounds1.<a class="code" href="classompl_1_1base_1_1RealVectorBounds.html#a36ebebb6a9e116093581afbd07425baa" title="Lower bound.">low</a>[2] = mZ - dz;
<a name="l00143"></a>00143         bounds1.<a class="code" href="classompl_1_1base_1_1RealVectorBounds.html#a06827561804a768d6ee86a20a664153c" title="Upper bound.">high</a>[2] = MZ + dz;
<a name="l00144"></a>00144 
<a name="l00145"></a>00145         setVolumeBounds(bounds1);
<a name="l00146"></a>00146     }
<a name="l00147"></a>00147 }
<a name="l00148"></a>00148 
<a name="l00149"></a><a class="code" href="classompl_1_1control_1_1ODEStateSpace.html#a74b7cd10a3e11b62f5e3d6c0bda79d92">00149</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1control_1_1ODEStateSpace.html#a74b7cd10a3e11b62f5e3d6c0bda79d92" title="Copy a state to another. The memory of source and destination should NOT overlap.">ompl::control::ODEStateSpace::copyState</a>(<a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">base::State</a> *destination, <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">base::State</a> *source)<span class="keyword"> const</span>
<a name="l00150"></a>00150 <span class="keyword"></span>{
<a name="l00151"></a>00151     CompoundStateSpace::copyState(destination, source);
<a name="l00152"></a>00152     destination-&gt;<a class="code" href="classompl_1_1base_1_1State.html#ae4ed5c095a6b2d4a5c946b91bc65e9cb" title="Cast this instance to a desired type.">as</a>&lt;<a class="code" href="classompl_1_1control_1_1ODEStateSpace_1_1StateType.html" title="ODE State. This is a compound state that allows accessing the properties of the bodies the state spac...">StateType</a>&gt;()-&gt;collision = source-&gt;<a class="code" href="classompl_1_1base_1_1State.html#ae4ed5c095a6b2d4a5c946b91bc65e9cb" title="Cast this instance to a desired type.">as</a>&lt;<a class="code" href="classompl_1_1control_1_1ODEStateSpace_1_1StateType.html" title="ODE State. This is a compound state that allows accessing the properties of the bodies the state spac...">StateType</a>&gt;()-&gt;<a class="code" href="classompl_1_1control_1_1ODEStateSpace_1_1StateType.html#a1ba5dfafa14052fd4a9ee317cddcd596" title="Flag containing information about state validity.">collision</a>;
<a name="l00153"></a>00153 }
<a name="l00154"></a>00154 
<a name="l00155"></a>00155 <span class="keyword">namespace </span>ompl
<a name="l00156"></a>00156 {
<a name="l00158"></a>00158     <span class="keyword">struct </span>CallbackParam
<a name="l00159"></a>00159     {
<a name="l00160"></a>00160         <span class="keyword">const</span> <a class="code" href="classompl_1_1control_1_1ODEEnvironment.html" title="This class contains the ODE constructs OMPL needs to know about when planning.">control::ODEEnvironment</a> *env;
<a name="l00161"></a>00161         <span class="keywordtype">bool</span>                           collision;
<a name="l00162"></a>00162     };
<a name="l00163"></a>00163 
<a name="l00164"></a>00164     <span class="keyword">static</span> <span class="keywordtype">void</span> nearCallback(<span class="keywordtype">void</span> *data, dGeomID o1, dGeomID o2)
<a name="l00165"></a>00165     {
<a name="l00166"></a>00166         <span class="comment">// if a collision has not already been detected</span>
<a name="l00167"></a>00167         <span class="keywordflow">if</span> (reinterpret_cast&lt;CallbackParam*&gt;(data)-&gt;collision == <span class="keyword">false</span>)
<a name="l00168"></a>00168         {
<a name="l00169"></a>00169             dBodyID b1 = dGeomGetBody(o1);
<a name="l00170"></a>00170             dBodyID b2 = dGeomGetBody(o2);
<a name="l00171"></a>00171             <span class="keywordflow">if</span> (b1 &amp;&amp; b2 &amp;&amp; dAreConnectedExcluding(b1, b2, dJointTypeContact)) <span class="keywordflow">return</span>;
<a name="l00172"></a>00172 
<a name="l00173"></a>00173             dContact contact[1];  <span class="comment">// one contact is sufficient</span>
<a name="l00174"></a>00174             <span class="keywordtype">int</span> numc = dCollide(o1, o2, 1, &amp;contact[0].geom, <span class="keyword">sizeof</span>(dContact));
<a name="l00175"></a>00175 
<a name="l00176"></a>00176             <span class="comment">// check if there is really a collision</span>
<a name="l00177"></a>00177             <span class="keywordflow">if</span> (numc)
<a name="l00178"></a>00178             {
<a name="l00179"></a>00179                 <span class="comment">// check if the collision is allowed</span>
<a name="l00180"></a>00180                 <span class="keywordtype">bool</span> valid = <span class="keyword">reinterpret_cast&lt;</span>CallbackParam*<span class="keyword">&gt;</span>(data)-&gt;env-&gt;isValidCollision(o1, o2, contact[0]);
<a name="l00181"></a>00181                 <span class="keyword">reinterpret_cast&lt;</span>CallbackParam*<span class="keyword">&gt;</span>(data)-&gt;collision = !valid;
<a name="l00182"></a>00182                 <span class="keywordflow">if</span> (reinterpret_cast&lt;CallbackParam*&gt;(data)-&gt;env-&gt;verboseContacts_)
<a name="l00183"></a>00183                 {
<a name="l00184"></a>00184                     <span class="keyword">static</span> <a class="code" href="classompl_1_1msg_1_1Interface.html" title="The piece of code that desires interaction with an action or an output handler should use an instance...">msg::Interface</a> msg;
<a name="l00185"></a>00185                     msg.<a class="code" href="classompl_1_1msg_1_1Interface.html#ad690e77cfd4c31b55cd221ed9c8ee94e" title="Forward a debug message.">debug</a>((valid ? <span class="stringliteral">&quot;Valid&quot;</span> : <span class="stringliteral">&quot;Invalid&quot;</span>) + std::string(<span class="stringliteral">&quot; contact between &quot;</span>) +
<a name="l00186"></a>00186                               reinterpret_cast&lt;CallbackParam*&gt;(data)-&gt;env-&gt;getGeomName(o1) + <span class="stringliteral">&quot; and &quot;</span> +
<a name="l00187"></a>00187                               <span class="keyword">reinterpret_cast&lt;</span>CallbackParam*<span class="keyword">&gt;</span>(data)-&gt;env-&gt;getGeomName(o2));
<a name="l00188"></a>00188                 }
<a name="l00189"></a>00189             }
<a name="l00190"></a>00190         }
<a name="l00191"></a>00191     }
<a name="l00193"></a>00193 }
<a name="l00194"></a>00194 
<a name="l00195"></a><a class="code" href="classompl_1_1control_1_1ODEStateSpace.html#a1f158dfa526d5573dda8dd31851ba0cf">00195</a> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1control_1_1ODEStateSpace.html#a1f158dfa526d5573dda8dd31851ba0cf" title="Fill the ODEStateSpace::STATE_COLLISION_VALUE_BIT of StateType::collision member of a state...">ompl::control::ODEStateSpace::evaluateCollision</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">base::State</a> *state)<span class="keyword"> const</span>
<a name="l00196"></a>00196 <span class="keyword"></span>{
<a name="l00197"></a>00197     <span class="keywordflow">if</span> (state-&gt;<a class="code" href="classompl_1_1base_1_1State.html#ae4ed5c095a6b2d4a5c946b91bc65e9cb" title="Cast this instance to a desired type.">as</a>&lt;<a class="code" href="classompl_1_1control_1_1ODEStateSpace_1_1StateType.html" title="ODE State. This is a compound state that allows accessing the properties of the bodies the state spac...">StateType</a>&gt;()-&gt;<a class="code" href="classompl_1_1control_1_1ODEStateSpace_1_1StateType.html#a1ba5dfafa14052fd4a9ee317cddcd596" title="Flag containing information about state validity.">collision</a> &amp; (1 &lt;&lt; STATE_COLLISION_KNOWN_BIT))
<a name="l00198"></a>00198         <span class="keywordflow">return</span> state-&gt;<a class="code" href="classompl_1_1base_1_1State.html#ae4ed5c095a6b2d4a5c946b91bc65e9cb" title="Cast this instance to a desired type.">as</a>&lt;<a class="code" href="classompl_1_1control_1_1ODEStateSpace_1_1StateType.html" title="ODE State. This is a compound state that allows accessing the properties of the bodies the state spac...">StateType</a>&gt;()-&gt;collision &amp; (1 &lt;&lt; STATE_COLLISION_VALUE_BIT);
<a name="l00199"></a>00199     env_-&gt;mutex_.lock();
<a name="l00200"></a>00200     writeState(state);
<a name="l00201"></a>00201     CallbackParam cp = { env_.get(), <span class="keyword">false</span> };
<a name="l00202"></a>00202     <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; cp.collision == <span class="keyword">false</span> &amp;&amp; i &lt; env_-&gt;collisionSpaces_.size() ; ++i)
<a name="l00203"></a>00203         dSpaceCollide(env_-&gt;collisionSpaces_[i], &amp;cp, &amp;nearCallback);
<a name="l00204"></a>00204     env_-&gt;mutex_.unlock();
<a name="l00205"></a>00205     <span class="keywordflow">if</span> (cp.collision)
<a name="l00206"></a>00206         state-&gt;<a class="code" href="classompl_1_1base_1_1State.html#ae4ed5c095a6b2d4a5c946b91bc65e9cb" title="Cast this instance to a desired type.">as</a>&lt;<a class="code" href="classompl_1_1control_1_1ODEStateSpace_1_1StateType.html" title="ODE State. This is a compound state that allows accessing the properties of the bodies the state spac...">StateType</a>&gt;()-&gt;collision &amp;= (1 &lt;&lt; STATE_COLLISION_VALUE_BIT);
<a name="l00207"></a>00207     state-&gt;<a class="code" href="classompl_1_1base_1_1State.html#ae4ed5c095a6b2d4a5c946b91bc65e9cb" title="Cast this instance to a desired type.">as</a>&lt;<a class="code" href="classompl_1_1control_1_1ODEStateSpace_1_1StateType.html" title="ODE State. This is a compound state that allows accessing the properties of the bodies the state spac...">StateType</a>&gt;()-&gt;collision &amp;= (1 &lt;&lt; STATE_COLLISION_KNOWN_BIT);
<a name="l00208"></a>00208     <span class="keywordflow">return</span> cp.collision;
<a name="l00209"></a>00209 }
<a name="l00210"></a>00210 
<a name="l00211"></a><a class="code" href="classompl_1_1control_1_1ODEStateSpace.html#a5b061f3f0cfeb29a70ac6aaa9f2add11">00211</a> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1control_1_1ODEStateSpace.html#a5b061f3f0cfeb29a70ac6aaa9f2add11" title="This is a convenience function provided for optimization purposes. It checks whether a state satisfie...">ompl::control::ODEStateSpace::satisfiesBoundsExceptRotation</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1control_1_1ODEStateSpace_1_1StateType.html" title="ODE State. This is a compound state that allows accessing the properties of the bodies the state spac...">StateType</a> *state)<span class="keyword"> const</span>
<a name="l00212"></a>00212 <span class="keyword"></span>{
<a name="l00213"></a>00213     <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i &lt; componentCount_ ; ++i)
<a name="l00214"></a>00214         <span class="keywordflow">if</span> (i % 4 != 3)
<a name="l00215"></a>00215             <span class="keywordflow">if</span> (!components_[i]-&gt;satisfiesBounds(state-&gt;<a class="code" href="classompl_1_1base_1_1CompoundState.html#acbfb1f1ff3d5eb2315f47c13fc79a86e" title="The components that make up a compound state.">components</a>[i]))
<a name="l00216"></a>00216                 <span class="keywordflow">return</span> <span class="keyword">false</span>;
<a name="l00217"></a>00217     <span class="keywordflow">return</span> <span class="keyword">true</span>;
<a name="l00218"></a>00218 }
<a name="l00219"></a>00219 
<a name="l00220"></a><a class="code" href="classompl_1_1control_1_1ODEStateSpace.html#a572348387ab7d3176a4a1063e6b3009e">00220</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1control_1_1ODEStateSpace.html#a572348387ab7d3176a4a1063e6b3009e" title="Set the bounds for each of the position subspaces.">ompl::control::ODEStateSpace::setVolumeBounds</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1RealVectorBounds.html" title="The lower and upper bounds for an Rn space.">base::RealVectorBounds</a> &amp;bounds)
<a name="l00221"></a>00221 {
<a name="l00222"></a>00222     <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i &lt; env_-&gt;stateBodies_.size() ; ++i)
<a name="l00223"></a>00223         components_[i * 4]-&gt;as&lt;base::RealVectorStateSpace&gt;()-&gt;setBounds(bounds);
<a name="l00224"></a>00224 }
<a name="l00225"></a>00225 
<a name="l00226"></a><a class="code" href="classompl_1_1control_1_1ODEStateSpace.html#a0d779b1d59544cf4bfb90de4def851a5">00226</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1control_1_1ODEStateSpace.html#a0d779b1d59544cf4bfb90de4def851a5" title="Set the bounds for each of the linear velocity subspaces.">ompl::control::ODEStateSpace::setLinearVelocityBounds</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1RealVectorBounds.html" title="The lower and upper bounds for an Rn space.">base::RealVectorBounds</a> &amp;bounds)
<a name="l00227"></a>00227 {
<a name="l00228"></a>00228     <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i &lt; env_-&gt;stateBodies_.size() ; ++i)
<a name="l00229"></a>00229         components_[i * 4 + 1]-&gt;as&lt;base::RealVectorStateSpace&gt;()-&gt;setBounds(bounds);
<a name="l00230"></a>00230 }
<a name="l00231"></a>00231 
<a name="l00232"></a><a class="code" href="classompl_1_1control_1_1ODEStateSpace.html#aa7390b20c14d2e09f803b46d2fa9aeed">00232</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1control_1_1ODEStateSpace.html#aa7390b20c14d2e09f803b46d2fa9aeed" title="Set the bounds for each of the angular velocity subspaces.">ompl::control::ODEStateSpace::setAngularVelocityBounds</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1RealVectorBounds.html" title="The lower and upper bounds for an Rn space.">base::RealVectorBounds</a> &amp;bounds)
<a name="l00233"></a>00233 {
<a name="l00234"></a>00234     <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i &lt; env_-&gt;stateBodies_.size() ; ++i)
<a name="l00235"></a>00235         components_[i * 4 + 2]-&gt;as&lt;base::RealVectorStateSpace&gt;()-&gt;setBounds(bounds);
<a name="l00236"></a>00236 }
<a name="l00237"></a>00237 
<a name="l00238"></a><a class="code" href="classompl_1_1control_1_1ODEStateSpace.html#a6a322bef2a5ca80db337ecd977235be9">00238</a> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">ompl::base::State</a>* <a class="code" href="classompl_1_1control_1_1ODEStateSpace.html#a6a322bef2a5ca80db337ecd977235be9" title="Allocate a state that can store a point in the described space.">ompl::control::ODEStateSpace::allocState</a>(<span class="keywordtype">void</span>)<span class="keyword"> const</span>
<a name="l00239"></a>00239 <span class="keyword"></span>{
<a name="l00240"></a>00240     <a class="code" href="classompl_1_1control_1_1ODEStateSpace_1_1StateType.html" title="ODE State. This is a compound state that allows accessing the properties of the bodies the state spac...">StateType</a> *state = <span class="keyword">new</span> <a class="code" href="classompl_1_1control_1_1ODEStateSpace_1_1StateType.html" title="ODE State. This is a compound state that allows accessing the properties of the bodies the state spac...">StateType</a>();
<a name="l00241"></a>00241     allocStateComponents(state);
<a name="l00242"></a>00242     <span class="keywordflow">return</span> state;
<a name="l00243"></a>00243 }
<a name="l00244"></a>00244 
<a name="l00245"></a><a class="code" href="classompl_1_1control_1_1ODEStateSpace.html#a22e049b3b64c43fc4dc5bf8020c0bbd2">00245</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1control_1_1ODEStateSpace.html#a22e049b3b64c43fc4dc5bf8020c0bbd2" title="Free the memory of the allocated state.">ompl::control::ODEStateSpace::freeState</a>(<a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">base::State</a> *state)<span class="keyword"> const</span>
<a name="l00246"></a>00246 <span class="keyword"></span>{
<a name="l00247"></a>00247     CompoundStateSpace::freeState(state);
<a name="l00248"></a>00248 }
<a name="l00249"></a>00249 
<a name="l00250"></a><a class="code" href="classompl_1_1control_1_1ODEStateSpace.html#a17b12710391410fc3fd0cc6e3eca9f1f">00250</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1control_1_1ODEStateSpace.html#a17b12710391410fc3fd0cc6e3eca9f1f" title="Read the parameters of the ODE bodies and store them in state.">ompl::control::ODEStateSpace::readState</a>(<a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">base::State</a> *state)<span class="keyword"> const</span>
<a name="l00251"></a>00251 <span class="keyword"></span>{
<a name="l00252"></a>00252     <a class="code" href="classompl_1_1control_1_1ODEStateSpace_1_1StateType.html" title="ODE State. This is a compound state that allows accessing the properties of the bodies the state spac...">StateType</a> *s = state-&gt;<a class="code" href="classompl_1_1base_1_1State.html#ae4ed5c095a6b2d4a5c946b91bc65e9cb" title="Cast this instance to a desired type.">as</a>&lt;<a class="code" href="classompl_1_1control_1_1ODEStateSpace_1_1StateType.html" title="ODE State. This is a compound state that allows accessing the properties of the bodies the state spac...">StateType</a>&gt;();
<a name="l00253"></a>00253     <span class="keywordflow">for</span> (<span class="keywordtype">int</span> i = (<span class="keywordtype">int</span>)env_-&gt;stateBodies_.size() - 1 ; i &gt;= 0 ; --i)
<a name="l00254"></a>00254     {
<a name="l00255"></a>00255         <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> _i4 = i * 4;
<a name="l00256"></a>00256 
<a name="l00257"></a>00257         <span class="keyword">const</span> dReal *pos = dBodyGetPosition(env_-&gt;stateBodies_[i]);
<a name="l00258"></a>00258         <span class="keyword">const</span> dReal *vel = dBodyGetLinearVel(env_-&gt;stateBodies_[i]);
<a name="l00259"></a>00259         <span class="keyword">const</span> dReal *ang = dBodyGetAngularVel(env_-&gt;stateBodies_[i]);
<a name="l00260"></a>00260         <span class="keywordtype">double</span> *s_pos = s-&gt;<a class="code" href="classompl_1_1base_1_1CompoundState.html#ae51035c1a4c69165f2688d252b527ba7" title="Cast a component of this instance to a desired type.">as</a>&lt;<a class="code" href="classompl_1_1base_1_1RealVectorStateSpace_1_1StateType.html" title="The definition of a state in Rn">base::RealVectorStateSpace::StateType</a>&gt;(_i4)-&gt;values; ++_i4;
<a name="l00261"></a>00261         <span class="keywordtype">double</span> *s_vel = s-&gt;<a class="code" href="classompl_1_1base_1_1CompoundState.html#ae51035c1a4c69165f2688d252b527ba7" title="Cast a component of this instance to a desired type.">as</a>&lt;<a class="code" href="classompl_1_1base_1_1RealVectorStateSpace_1_1StateType.html" title="The definition of a state in Rn">base::RealVectorStateSpace::StateType</a>&gt;(_i4)-&gt;values; ++_i4;
<a name="l00262"></a>00262         <span class="keywordtype">double</span> *s_ang = s-&gt;<a class="code" href="classompl_1_1base_1_1CompoundState.html#ae51035c1a4c69165f2688d252b527ba7" title="Cast a component of this instance to a desired type.">as</a>&lt;<a class="code" href="classompl_1_1base_1_1RealVectorStateSpace_1_1StateType.html" title="The definition of a state in Rn">base::RealVectorStateSpace::StateType</a>&gt;(_i4)-&gt;values; ++_i4;
<a name="l00263"></a>00263 
<a name="l00264"></a>00264         <span class="keywordflow">for</span> (<span class="keywordtype">int</span> j = 0; j &lt; 3; ++j)
<a name="l00265"></a>00265         {
<a name="l00266"></a>00266             s_pos[j] = pos[j];
<a name="l00267"></a>00267             s_vel[j] = vel[j];
<a name="l00268"></a>00268             s_ang[j] = ang[j];
<a name="l00269"></a>00269         }
<a name="l00270"></a>00270 
<a name="l00271"></a>00271         <span class="keyword">const</span> dReal *rot = dBodyGetQuaternion(env_-&gt;stateBodies_[i]);
<a name="l00272"></a>00272             <a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">base::SO3StateSpace::StateType</a> &amp;s_rot = *s-&gt;<a class="code" href="classompl_1_1base_1_1CompoundState.html#ae51035c1a4c69165f2688d252b527ba7" title="Cast a component of this instance to a desired type.">as</a>&lt;<a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">base::SO3StateSpace::StateType</a>&gt;(_i4);
<a name="l00273"></a>00273 
<a name="l00274"></a>00274         s_rot.<a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a819bd3faba4f19b9f2f58c310c5d6e3c" title="scalar component of quaternion">w</a> = rot[0];
<a name="l00275"></a>00275         s_rot.<a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a525d64ca3f68c8e6492c6e26199d4717" title="X component of quaternion vector.">x</a> = rot[1];
<a name="l00276"></a>00276         s_rot.<a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae9e99008a6b4448e6a5e53ba42430bcd" title="Y component of quaternion vector.">y</a> = rot[2];
<a name="l00277"></a>00277         s_rot.<a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae4b1013f96d9ad164e54c758711377d0" title="Z component of quaternion vector.">z</a> = rot[3];
<a name="l00278"></a>00278     }
<a name="l00279"></a>00279 }
<a name="l00280"></a>00280 
<a name="l00281"></a><a class="code" href="classompl_1_1control_1_1ODEStateSpace.html#a7cebbdb127b722b783fab82f1873d71d">00281</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1control_1_1ODEStateSpace.html#a7cebbdb127b722b783fab82f1873d71d" title="Set the parameters of the ODE bodies to be the ones read from state. The code will technically work i...">ompl::control::ODEStateSpace::writeState</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">base::State</a> *state)<span class="keyword"> const</span>
<a name="l00282"></a>00282 <span class="keyword"></span>{
<a name="l00283"></a>00283     <span class="keyword">const</span> <a class="code" href="classompl_1_1control_1_1ODEStateSpace_1_1StateType.html" title="ODE State. This is a compound state that allows accessing the properties of the bodies the state spac...">StateType</a> *s = state-&gt;<a class="code" href="classompl_1_1base_1_1State.html#ae4ed5c095a6b2d4a5c946b91bc65e9cb" title="Cast this instance to a desired type.">as</a>&lt;<a class="code" href="classompl_1_1control_1_1ODEStateSpace_1_1StateType.html" title="ODE State. This is a compound state that allows accessing the properties of the bodies the state spac...">StateType</a>&gt;();
<a name="l00284"></a>00284     <span class="keywordflow">for</span> (<span class="keywordtype">int</span> i = (<span class="keywordtype">int</span>)env_-&gt;stateBodies_.size() - 1 ; i &gt;= 0 ; --i)
<a name="l00285"></a>00285     {
<a name="l00286"></a>00286         <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> _i4 = i * 4;
<a name="l00287"></a>00287 
<a name="l00288"></a>00288         <span class="keywordtype">double</span> *s_pos = s-&gt;<a class="code" href="classompl_1_1base_1_1CompoundState.html#ae51035c1a4c69165f2688d252b527ba7" title="Cast a component of this instance to a desired type.">as</a>&lt;<a class="code" href="classompl_1_1base_1_1RealVectorStateSpace_1_1StateType.html" title="The definition of a state in Rn">base::RealVectorStateSpace::StateType</a>&gt;(_i4)-&gt;values; ++_i4;
<a name="l00289"></a>00289         dBodySetPosition(env_-&gt;stateBodies_[i], s_pos[0], s_pos[1], s_pos[2]);
<a name="l00290"></a>00290 
<a name="l00291"></a>00291         <span class="keywordtype">double</span> *s_vel = s-&gt;<a class="code" href="classompl_1_1base_1_1CompoundState.html#ae51035c1a4c69165f2688d252b527ba7" title="Cast a component of this instance to a desired type.">as</a>&lt;<a class="code" href="classompl_1_1base_1_1RealVectorStateSpace_1_1StateType.html" title="The definition of a state in Rn">base::RealVectorStateSpace::StateType</a>&gt;(_i4)-&gt;values; ++_i4;
<a name="l00292"></a>00292         dBodySetLinearVel(env_-&gt;stateBodies_[i], s_vel[0], s_vel[1], s_vel[2]);
<a name="l00293"></a>00293 
<a name="l00294"></a>00294         <span class="keywordtype">double</span> *s_ang = s-&gt;<a class="code" href="classompl_1_1base_1_1CompoundState.html#ae51035c1a4c69165f2688d252b527ba7" title="Cast a component of this instance to a desired type.">as</a>&lt;<a class="code" href="classompl_1_1base_1_1RealVectorStateSpace_1_1StateType.html" title="The definition of a state in Rn">base::RealVectorStateSpace::StateType</a>&gt;(_i4)-&gt;values; ++_i4;
<a name="l00295"></a>00295         dBodySetAngularVel(env_-&gt;stateBodies_[i],  s_ang[0], s_ang[1], s_ang[2]);
<a name="l00296"></a>00296 
<a name="l00297"></a>00297             <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">base::SO3StateSpace::StateType</a> &amp;s_rot = *s-&gt;<a class="code" href="classompl_1_1base_1_1CompoundState.html#ae51035c1a4c69165f2688d252b527ba7" title="Cast a component of this instance to a desired type.">as</a>&lt;<a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">base::SO3StateSpace::StateType</a>&gt;(_i4);
<a name="l00298"></a>00298         dQuaternion q;
<a name="l00299"></a>00299         q[0] = s_rot.<a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a819bd3faba4f19b9f2f58c310c5d6e3c" title="scalar component of quaternion">w</a>;
<a name="l00300"></a>00300         q[1] = s_rot.<a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a525d64ca3f68c8e6492c6e26199d4717" title="X component of quaternion vector.">x</a>;
<a name="l00301"></a>00301         q[2] = s_rot.<a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae9e99008a6b4448e6a5e53ba42430bcd" title="Y component of quaternion vector.">y</a>;
<a name="l00302"></a>00302         q[3] = s_rot.<a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae4b1013f96d9ad164e54c758711377d0" title="Z component of quaternion vector.">z</a>;
<a name="l00303"></a>00303         dBodySetQuaternion(env_-&gt;stateBodies_[i], q);
<a name="l00304"></a>00304     }
<a name="l00305"></a>00305 }
</pre></div></div>
</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:40 by&#160;<a href="http://www.doxygen.org/index.html">doxygen</a> 1.7.4</div>
</div>
</div>
</body>
</html>