Sophie

Sophie

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

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/geometric/src/PathGeometric.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_09c87af92e12dad9ad42621ff12ca21c.html">geometric</a>      </li>
      <li class="navelem"><a class="el" href="dir_34704d7d63a761c950e2f36b303dd742.html">src</a>      </li>
    </ul>
  </div>
</div>
<div class="header">
  <div class="headertitle">
<div class="title">PathGeometric.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) 2008, Willow Garage, Inc.</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 Willow Garage 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/geometric/PathGeometric.h&quot;</span>
<a name="l00038"></a>00038 <span class="preprocessor">#include &quot;ompl/base/samplers/UniformValidStateSampler.h&quot;</span>
<a name="l00039"></a>00039 <span class="preprocessor">#include &quot;ompl/base/ScopedState.h&quot;</span>
<a name="l00040"></a>00040 <span class="preprocessor">#include &lt;algorithm&gt;</span>
<a name="l00041"></a>00041 <span class="preprocessor">#include &lt;cmath&gt;</span>
<a name="l00042"></a>00042 <span class="preprocessor">#include &lt;limits&gt;</span>
<a name="l00043"></a>00043 <span class="preprocessor">#include &lt;boost/math/constants/constants.hpp&gt;</span>
<a name="l00044"></a>00044 
<a name="l00045"></a><a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a45d676fcc2896ecf9e9156bac2cba4fb">00045</a> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#ab85d32ca5bce67da74a3b116ac11fd73" title="Construct a path instance for a given space information.">ompl::geometric::PathGeometric::PathGeometric</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html" title="Definition of a geometric path.">PathGeometric</a> &amp;path) : base::Path(path.si_)
<a name="l00046"></a>00046 {
<a name="l00047"></a>00047     <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a79b0a01a8075a16666b475e1c0227968" title="Copy data to this path from another path instance.">copyFrom</a>(path);
<a name="l00048"></a>00048 }
<a name="l00049"></a>00049 
<a name="l00050"></a><a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a1e872d1a6b4528ec809b2fcc1e2c34bd">00050</a> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#ab85d32ca5bce67da74a3b116ac11fd73" title="Construct a path instance for a given space information.">ompl::geometric::PathGeometric::PathGeometric</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1SpaceInformationPtr.html" title="A boost shared pointer wrapper for ompl::base::SpaceInformation.">base::SpaceInformationPtr</a> &amp;si, <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) : base::Path(si)
<a name="l00051"></a>00051 {
<a name="l00052"></a>00052     <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a3a729dab22338b733888bc2f9c9769a4" title="The list of states that make up the path.">states</a>.resize(1);
<a name="l00053"></a>00053     <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a3a729dab22338b733888bc2f9c9769a4" title="The list of states that make up the path.">states</a>[0] = <a class="code" href="classompl_1_1base_1_1Path.html#a87250f099dbe84a3c0ba515360ac4339" title="The space information this path is part of.">si_</a>-&gt;cloneState(state);
<a name="l00054"></a>00054 }
<a name="l00055"></a>00055 
<a name="l00056"></a><a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a44bcadcd08a5c494557652d7f75f0e17">00056</a> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html" title="Definition of a geometric path.">ompl::geometric::PathGeometric</a>&amp; <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a44bcadcd08a5c494557652d7f75f0e17" title="Assignment operator.">ompl::geometric::PathGeometric::operator=</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html" title="Definition of a geometric path.">PathGeometric</a> &amp;other)
<a name="l00057"></a>00057 {
<a name="l00058"></a>00058     freeMemory();
<a name="l00059"></a>00059     si_ = other.<a class="code" href="classompl_1_1base_1_1Path.html#a87250f099dbe84a3c0ba515360ac4339" title="The space information this path is part of.">si_</a>;
<a name="l00060"></a>00060     copyFrom(other);
<a name="l00061"></a>00061     <span class="keywordflow">return</span> *<span class="keyword">this</span>;
<a name="l00062"></a>00062 }
<a name="l00063"></a>00063 
<a name="l00064"></a><a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a79b0a01a8075a16666b475e1c0227968">00064</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a79b0a01a8075a16666b475e1c0227968" title="Copy data to this path from another path instance.">ompl::geometric::PathGeometric::copyFrom</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html" title="Definition of a geometric path.">PathGeometric</a> &amp;other)
<a name="l00065"></a>00065 {
<a name="l00066"></a>00066     states.resize(other.<a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a3a729dab22338b733888bc2f9c9769a4" title="The list of states that make up the path.">states</a>.size());
<a name="l00067"></a>00067     <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i &lt; states.size() ; ++i)
<a name="l00068"></a>00068         states[i] = si_-&gt;cloneState(other.<a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a3a729dab22338b733888bc2f9c9769a4" title="The list of states that make up the path.">states</a>[i]);
<a name="l00069"></a>00069 }
<a name="l00070"></a>00070 
<a name="l00071"></a><a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a4b42ad4c2bfbda7d61ba5156f7e25bc6">00071</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a4b42ad4c2bfbda7d61ba5156f7e25bc6" title="Free the memory corresponding to the states on this path.">ompl::geometric::PathGeometric::freeMemory</a>(<span class="keywordtype">void</span>)
<a name="l00072"></a>00072 {
<a name="l00073"></a>00073     <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i &lt; states.size() ; ++i)
<a name="l00074"></a>00074         si_-&gt;freeState(states[i]);
<a name="l00075"></a>00075 }
<a name="l00076"></a>00076 
<a name="l00077"></a><a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a4fde73b06380b9bcc7080150178574e2">00077</a> <span class="keywordtype">double</span> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a4fde73b06380b9bcc7080150178574e2" title="Compute the length of a geometric path (sum of lengths of segments that make up the path)...">ompl::geometric::PathGeometric::length</a>(<span class="keywordtype">void</span>)<span class="keyword"> const</span>
<a name="l00078"></a>00078 <span class="keyword"></span>{
<a name="l00079"></a>00079     <span class="keywordtype">double</span> L = 0.0;
<a name="l00080"></a>00080     <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 1 ; i &lt; states.size() ; ++i)
<a name="l00081"></a>00081         L += si_-&gt;distance(states[i-1], states[i]);
<a name="l00082"></a>00082     <span class="keywordflow">return</span> L;
<a name="l00083"></a>00083 }
<a name="l00084"></a>00084 
<a name="l00085"></a><a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#acf32f1979b45d64904711f7b3661fd97">00085</a> <span class="keywordtype">double</span> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#acf32f1979b45d64904711f7b3661fd97" title="Compute the clearance of the end points along the path (no interpolation is performed). The clearance for the points is averaged.">ompl::geometric::PathGeometric::clearance</a>(<span class="keywordtype">void</span>)<span class="keyword"> const</span>
<a name="l00086"></a>00086 <span class="keyword"></span>{
<a name="l00087"></a>00087     <span class="keywordtype">double</span> c = 0.0;
<a name="l00088"></a>00088     <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i &lt; states.size() ; ++i)
<a name="l00089"></a>00089         c += si_-&gt;getStateValidityChecker()-&gt;clearance(states[i]);
<a name="l00090"></a>00090     <span class="keywordflow">if</span> (states.empty())
<a name="l00091"></a>00091         c = std::numeric_limits&lt;double&gt;::infinity();
<a name="l00092"></a>00092     <span class="keywordflow">else</span>
<a name="l00093"></a>00093         c /= (double)states.size();
<a name="l00094"></a>00094     <span class="keywordflow">return</span> c;
<a name="l00095"></a>00095 }
<a name="l00096"></a>00096 
<a name="l00097"></a><a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#abe347b38e774fa6f5486db354d48b667">00097</a> <span class="keywordtype">double</span> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#abe347b38e774fa6f5486db354d48b667" title="Compute a notion of smootheness for this path. The closer the value is to 0, the smoother the path...">ompl::geometric::PathGeometric::smoothness</a>(<span class="keywordtype">void</span>)<span class="keyword"> const</span>
<a name="l00098"></a>00098 <span class="keyword"></span>{
<a name="l00099"></a>00099     <span class="keywordtype">double</span> s = 0.0;
<a name="l00100"></a>00100     <span class="keywordflow">if</span> (states.size() &gt; 2)
<a name="l00101"></a>00101     {
<a name="l00102"></a>00102         <span class="keywordtype">double</span> a = si_-&gt;distance(states[0], states[1]);
<a name="l00103"></a>00103         <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 2 ; i &lt; states.size() ; ++i)
<a name="l00104"></a>00104         {
<a name="l00105"></a>00105             <span class="keywordtype">double</span> b = si_-&gt;distance(states[i-1], states[i]);
<a name="l00106"></a>00106             <span class="keywordtype">double</span> c = si_-&gt;distance(states[i-2], states[i]);
<a name="l00107"></a>00107             <span class="keywordtype">double</span> acosValue = (a*a + b*b - c*c) / (2.0*a*b);
<a name="l00108"></a>00108             <span class="keywordflow">if</span> (acosValue &gt; -1.0 &amp;&amp; acosValue &lt; 1.0)
<a name="l00109"></a>00109             {
<a name="l00110"></a>00110                 <span class="keywordtype">double</span> angle = (boost::math::constants::pi&lt;double&gt;() - acos(acosValue));
<a name="l00111"></a>00111                 <span class="keywordtype">double</span> k = 2.0 * angle / (a + b);
<a name="l00112"></a>00112                 s += k * k;
<a name="l00113"></a>00113             }
<a name="l00114"></a>00114             a = b;
<a name="l00115"></a>00115         }
<a name="l00116"></a>00116     }
<a name="l00117"></a>00117     <span class="keywordflow">return</span> s;
<a name="l00118"></a>00118 }
<a name="l00119"></a>00119 
<a name="l00120"></a><a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#ad73ad8a0b425d3c34280c8ba9289bba2">00120</a> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#ad73ad8a0b425d3c34280c8ba9289bba2" title="Check if the path is valid.">ompl::geometric::PathGeometric::check</a>(<span class="keywordtype">void</span>)<span class="keyword"> const</span>
<a name="l00121"></a>00121 <span class="keyword"></span>{
<a name="l00122"></a>00122     <span class="keywordtype">bool</span> result = <span class="keyword">true</span>;
<a name="l00123"></a>00123     <span class="keywordflow">if</span> (states.size() &gt; 0)
<a name="l00124"></a>00124     {
<a name="l00125"></a>00125         <span class="keywordflow">if</span> (si_-&gt;isValid(states[0]))
<a name="l00126"></a>00126         {
<a name="l00127"></a>00127             <span class="keywordtype">int</span> last = states.size() - 1;
<a name="l00128"></a>00128             <span class="keywordflow">for</span> (<span class="keywordtype">int</span> j = 0 ; result &amp;&amp; j &lt; last ; ++j)
<a name="l00129"></a>00129                 <span class="keywordflow">if</span> (!si_-&gt;checkMotion(states[j], states[j + 1]))
<a name="l00130"></a>00130                     result = <span class="keyword">false</span>;
<a name="l00131"></a>00131         }
<a name="l00132"></a>00132         <span class="keywordflow">else</span>
<a name="l00133"></a>00133             result = <span class="keyword">false</span>;
<a name="l00134"></a>00134     }
<a name="l00135"></a>00135 
<a name="l00136"></a>00136     <span class="keywordflow">return</span> result;
<a name="l00137"></a>00137 }
<a name="l00138"></a>00138 
<a name="l00139"></a><a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a7a27d7d046e4fc52a18966cec79adbc1">00139</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a7a27d7d046e4fc52a18966cec79adbc1" title="Print the path to a stream.">ompl::geometric::PathGeometric::print</a>(std::ostream &amp;out)<span class="keyword"> const</span>
<a name="l00140"></a>00140 <span class="keyword"></span>{
<a name="l00141"></a>00141     out &lt;&lt; <span class="stringliteral">&quot;Geometric path with &quot;</span> &lt;&lt; states.size() &lt;&lt; <span class="stringliteral">&quot; states&quot;</span> &lt;&lt; std::endl;
<a name="l00142"></a>00142     <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i &lt; states.size() ; ++i)
<a name="l00143"></a>00143         si_-&gt;printState(states[i], out);
<a name="l00144"></a>00144     out &lt;&lt; std::endl;
<a name="l00145"></a>00145 }
<a name="l00146"></a>00146 
<a name="l00147"></a><a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a348f26bf4989964dddf791ef746a9098">00147</a> std::pair&lt;bool, bool&gt; <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a348f26bf4989964dddf791ef746a9098" title="Check if the path is valid. If it is not, attempts are made to fix the path by sampling around invali...">ompl::geometric::PathGeometric::checkAndRepair</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> attempts)
<a name="l00148"></a>00148 {
<a name="l00149"></a>00149     <span class="keywordflow">if</span> (states.empty())
<a name="l00150"></a>00150         <span class="keywordflow">return</span> std::make_pair(<span class="keyword">true</span>, <span class="keyword">true</span>);
<a name="l00151"></a>00151     <span class="keywordflow">if</span> (states.size() == 1)
<a name="l00152"></a>00152     {
<a name="l00153"></a>00153         <span class="keywordtype">bool</span> result = si_-&gt;isValid(states[0]);
<a name="l00154"></a>00154         <span class="keywordflow">return</span> std::make_pair(result, result);
<a name="l00155"></a>00155     }
<a name="l00156"></a>00156 
<a name="l00157"></a>00157     <span class="comment">// a path with invalid endpoints cannot be fixed; planners should not return such paths anyway</span>
<a name="l00158"></a>00158     <span class="keyword">const</span> <span class="keywordtype">int</span> n1 = states.size() - 1;
<a name="l00159"></a>00159     <span class="keywordflow">if</span> (!si_-&gt;isValid(states[0]) || !si_-&gt;isValid(states[n1]))
<a name="l00160"></a>00160         <span class="keywordflow">return</span> std::make_pair(<span class="keyword">false</span>, <span class="keyword">false</span>);
<a name="l00161"></a>00161 
<a name="l00162"></a>00162     <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">base::State</a> *temp = NULL;
<a name="l00163"></a>00163     <a class="code" href="classompl_1_1base_1_1UniformValidStateSampler.html" title="A state sampler that only samples valid states, uniformly.">base::UniformValidStateSampler</a> *uvss = NULL;
<a name="l00164"></a>00164     <span class="keywordtype">bool</span> result = <span class="keyword">true</span>;
<a name="l00165"></a>00165 
<a name="l00166"></a>00166     <span class="keywordflow">for</span> (<span class="keywordtype">int</span> i = 1 ; i &lt; n1 ; ++i)
<a name="l00167"></a>00167         <span class="keywordflow">if</span> (!si_-&gt;checkMotion(states[i-1], states[i]))
<a name="l00168"></a>00168         {
<a name="l00169"></a>00169             <span class="comment">// we now compute a state around which to sample</span>
<a name="l00170"></a>00170             <span class="keywordflow">if</span> (!temp)
<a name="l00171"></a>00171                 temp = si_-&gt;allocState();
<a name="l00172"></a>00172             <span class="keywordflow">if</span> (!uvss)
<a name="l00173"></a>00173             {
<a name="l00174"></a>00174                 uvss = <span class="keyword">new</span> <a class="code" href="classompl_1_1base_1_1UniformValidStateSampler.html" title="A state sampler that only samples valid states, uniformly.">base::UniformValidStateSampler</a>(si_.get());
<a name="l00175"></a>00175                 uvss-&gt;<a class="code" href="classompl_1_1base_1_1ValidStateSampler.html#aa134892ca5a8ae0c5ec2e37693787090" title="Finding a valid sample usually requires performing multiple attempts. This call allows setting the nu...">setNrAttempts</a>(attempts);
<a name="l00176"></a>00176             }
<a name="l00177"></a>00177 
<a name="l00178"></a>00178             <span class="comment">// and a radius of sampling around that state</span>
<a name="l00179"></a>00179             <span class="keywordtype">double</span> radius = 0.0;
<a name="l00180"></a>00180 
<a name="l00181"></a>00181             <span class="keywordflow">if</span> (si_-&gt;isValid(states[i]))
<a name="l00182"></a>00182             {
<a name="l00183"></a>00183                 si_-&gt;copyState(temp, states[i]);
<a name="l00184"></a>00184                 radius = si_-&gt;distance(states[i-1], states[i]);
<a name="l00185"></a>00185             }
<a name="l00186"></a>00186             <span class="keywordflow">else</span>
<a name="l00187"></a>00187             {
<a name="l00188"></a>00188                 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> nextValid = n1;
<a name="l00189"></a>00189                 <span class="keywordflow">for</span> (<span class="keywordtype">int</span> j = i + 1 ; j &lt; n1 ; ++j)
<a name="l00190"></a>00190                     <span class="keywordflow">if</span> (si_-&gt;isValid(states[j]))
<a name="l00191"></a>00191                     {
<a name="l00192"></a>00192                         nextValid = j;
<a name="l00193"></a>00193                         <span class="keywordflow">break</span>;
<a name="l00194"></a>00194                     }
<a name="l00195"></a>00195                 <span class="comment">// we know nextValid will be initialised because n1 is certainly valid.</span>
<a name="l00196"></a>00196                 si_-&gt;getStateSpace()-&gt;interpolate(states[i - 1], states[nextValid], 0.5, temp);
<a name="l00197"></a>00197                 radius = std::max(si_-&gt;distance(states[i-1], temp), si_-&gt;distance(states[i-1], states[i]));
<a name="l00198"></a>00198             }
<a name="l00199"></a>00199 
<a name="l00200"></a>00200             <span class="keywordtype">bool</span> success = <span class="keyword">false</span>;
<a name="l00201"></a>00201 
<a name="l00202"></a>00202             <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> a = 0 ; a &lt; attempts ; ++a)
<a name="l00203"></a>00203                 <span class="keywordflow">if</span> (uvss-&gt;<a class="code" href="classompl_1_1base_1_1UniformValidStateSampler.html#a57f0088c965889490906f71ce4c64397" title="Sample a state near another, within specified distance. Return false, in case of failure.">sampleNear</a>(states[i], temp, radius))
<a name="l00204"></a>00204                 {
<a name="l00205"></a>00205                     <span class="keywordflow">if</span> (si_-&gt;checkMotion(states[i-1], states[i]))
<a name="l00206"></a>00206                     {
<a name="l00207"></a>00207                         success = <span class="keyword">true</span>;
<a name="l00208"></a>00208                         <span class="keywordflow">break</span>;
<a name="l00209"></a>00209                     }
<a name="l00210"></a>00210                 }
<a name="l00211"></a>00211                 <span class="keywordflow">else</span>
<a name="l00212"></a>00212                     <span class="keywordflow">break</span>;
<a name="l00213"></a>00213             <span class="keywordflow">if</span> (!success)
<a name="l00214"></a>00214             {
<a name="l00215"></a>00215                 result = <span class="keyword">false</span>;
<a name="l00216"></a>00216                 <span class="keywordflow">break</span>;
<a name="l00217"></a>00217             }
<a name="l00218"></a>00218         }
<a name="l00219"></a>00219 
<a name="l00220"></a>00220     <span class="comment">// free potentially allocated memory</span>
<a name="l00221"></a>00221     <span class="keywordflow">if</span> (temp)
<a name="l00222"></a>00222         si_-&gt;freeState(temp);
<a name="l00223"></a>00223     <span class="keywordtype">bool</span> originalValid = uvss == NULL;
<a name="l00224"></a>00224     <span class="keywordflow">if</span> (uvss)
<a name="l00225"></a>00225         <span class="keyword">delete</span> uvss;
<a name="l00226"></a>00226 
<a name="l00227"></a>00227     <span class="keywordflow">return</span> std::make_pair(originalValid, result);
<a name="l00228"></a>00228 }
<a name="l00229"></a>00229 
<a name="l00230"></a><a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a25f2ba684dce223adba8a3d896934e2a">00230</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a25f2ba684dce223adba8a3d896934e2a" title="Add a state at the middle of each segment.">ompl::geometric::PathGeometric::subdivide</a>(<span class="keywordtype">void</span>)
<a name="l00231"></a>00231 {
<a name="l00232"></a>00232     <span class="keywordflow">if</span> (states.size() &lt; 2)
<a name="l00233"></a>00233         <span class="keywordflow">return</span>;
<a name="l00234"></a>00234     std::vector&lt;base::State*&gt; newStates(1, states[0]);
<a name="l00235"></a>00235     <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 1 ; i &lt; states.size() ; ++i)
<a name="l00236"></a>00236     {
<a name="l00237"></a>00237         <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">base::State</a> *temp = si_-&gt;allocState();
<a name="l00238"></a>00238         si_-&gt;getStateSpace()-&gt;interpolate(newStates.back(), states[i], 0.5, temp);
<a name="l00239"></a>00239         newStates.push_back(temp);
<a name="l00240"></a>00240         newStates.push_back(states[i]);
<a name="l00241"></a>00241     }
<a name="l00242"></a>00242     states.swap(newStates);
<a name="l00243"></a>00243 }
<a name="l00244"></a>00244 
<a name="l00245"></a><a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a1fa9d71073d2098993f96f056f69216e">00245</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a1fa9d71073d2098993f96f056f69216e" title="Insert a number of states in a path so that the path is made up of (approximately) the states checked...">ompl::geometric::PathGeometric::interpolate</a>(<span class="keywordtype">void</span>)
<a name="l00246"></a>00246 {
<a name="l00247"></a>00247     <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> n = 0;
<a name="l00248"></a>00248     <span class="keyword">const</span> <span class="keywordtype">int</span> n1 = states.size() - 1;
<a name="l00249"></a>00249     <span class="keywordflow">for</span> (<span class="keywordtype">int</span> i = 0 ; i &lt; n1 ; ++i)
<a name="l00250"></a>00250         n += si_-&gt;getStateSpace()-&gt;validSegmentCount(states[i], states[i + 1]);
<a name="l00251"></a>00251     interpolate(n);
<a name="l00252"></a>00252 }
<a name="l00253"></a>00253 
<a name="l00254"></a><a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a29c50018bc71d4d25b0f8e4d3e97aecd">00254</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a1fa9d71073d2098993f96f056f69216e" title="Insert a number of states in a path so that the path is made up of (approximately) the states checked...">ompl::geometric::PathGeometric::interpolate</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> requestCount)
<a name="l00255"></a>00255 {
<a name="l00256"></a>00256     <span class="keywordflow">if</span> (requestCount &lt; states.size() || states.size() &lt; 2)
<a name="l00257"></a>00257         <span class="keywordflow">return</span>;
<a name="l00258"></a>00258 
<a name="l00259"></a>00259     <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> count = requestCount;
<a name="l00260"></a>00260 
<a name="l00261"></a>00261     <span class="comment">// the remaining length of the path we need to add states along</span>
<a name="l00262"></a>00262     <span class="keywordtype">double</span> remainingLength = length();
<a name="l00263"></a>00263 
<a name="l00264"></a>00264     <span class="comment">// the new array of states this path will have</span>
<a name="l00265"></a>00265     std::vector&lt;base::State*&gt; newStates;
<a name="l00266"></a>00266     <span class="keyword">const</span> <span class="keywordtype">int</span> n1 = states.size() - 1;
<a name="l00267"></a>00267 
<a name="l00268"></a>00268     <span class="keywordflow">for</span> (<span class="keywordtype">int</span> i = 0 ; i &lt; n1 ; ++i)
<a name="l00269"></a>00269     {
<a name="l00270"></a>00270         <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">base::State</a> *s1 = states[i];
<a name="l00271"></a>00271         <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">base::State</a> *s2 = states[i + 1];
<a name="l00272"></a>00272 
<a name="l00273"></a>00273         newStates.push_back(s1);
<a name="l00274"></a>00274 
<a name="l00275"></a>00275         <span class="comment">// the maximum number of states that can be added on the current motion (without its endpoints)</span>
<a name="l00276"></a>00276         <span class="comment">// such that we can at least fit the remaining states</span>
<a name="l00277"></a>00277         <span class="keywordtype">int</span> maxNStates = count + i - states.size();
<a name="l00278"></a>00278 
<a name="l00279"></a>00279         <span class="keywordflow">if</span> (maxNStates &gt; 0)
<a name="l00280"></a>00280         {
<a name="l00281"></a>00281             <span class="comment">// compute an approximate number of states the following segment needs to contain; this includes endpoints</span>
<a name="l00282"></a>00282             <span class="keywordtype">double</span> segmentLength = si_-&gt;distance(s1, s2);
<a name="l00283"></a>00283             <span class="keywordtype">int</span> ns = i + 1 == n1 ? maxNStates + 2 : (int)floor(0.5 + (<span class="keywordtype">double</span>)count * segmentLength / remainingLength) + 1;
<a name="l00284"></a>00284 
<a name="l00285"></a>00285             <span class="comment">// if more than endpoints are needed</span>
<a name="l00286"></a>00286             <span class="keywordflow">if</span> (ns &gt; 2)
<a name="l00287"></a>00287             {
<a name="l00288"></a>00288                 ns -= 2; <span class="comment">// subtract endpoints</span>
<a name="l00289"></a>00289 
<a name="l00290"></a>00290                 <span class="comment">// make sure we don&#39;t add too many states</span>
<a name="l00291"></a>00291                 <span class="keywordflow">if</span> (ns &gt; maxNStates)
<a name="l00292"></a>00292                     ns = maxNStates;
<a name="l00293"></a>00293 
<a name="l00294"></a>00294                 <span class="comment">// compute intermediate states</span>
<a name="l00295"></a>00295                 std::vector&lt;base::State*&gt; block;
<a name="l00296"></a>00296                 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> ans = si_-&gt;getMotionStates(s1, s2, block, ns, <span class="keyword">false</span>, <span class="keyword">true</span>);
<a name="l00297"></a>00297                 <span class="comment">// sanity checks</span>
<a name="l00298"></a>00298                 <span class="keywordflow">if</span> ((<span class="keywordtype">int</span>)ans != ns || block.size() != ans)
<a name="l00299"></a>00299                     <span class="keywordflow">throw</span> <a class="code" href="classompl_1_1Exception.html" title="The exception type for ompl.">Exception</a>(<span class="stringliteral">&quot;Internal error in path interpolation. Incorrect number of intermediate states. Please contact the developers.&quot;</span>);
<a name="l00300"></a>00300 
<a name="l00301"></a>00301                 newStates.insert(newStates.end(), block.begin(), block.end());
<a name="l00302"></a>00302             }
<a name="l00303"></a>00303             <span class="keywordflow">else</span>
<a name="l00304"></a>00304                 ns = 0;
<a name="l00305"></a>00305 
<a name="l00306"></a>00306             <span class="comment">// update what remains to be done</span>
<a name="l00307"></a>00307             count -= (ns + 1);
<a name="l00308"></a>00308             remainingLength -= segmentLength;
<a name="l00309"></a>00309         }
<a name="l00310"></a>00310         <span class="keywordflow">else</span>
<a name="l00311"></a>00311             count--;
<a name="l00312"></a>00312     }
<a name="l00313"></a>00313 
<a name="l00314"></a>00314     <span class="comment">// add the last state</span>
<a name="l00315"></a>00315     newStates.push_back(states[n1]);
<a name="l00316"></a>00316     states.swap(newStates);
<a name="l00317"></a>00317     <span class="keywordflow">if</span> (requestCount != states.size())
<a name="l00318"></a>00318         <span class="keywordflow">throw</span> <a class="code" href="classompl_1_1Exception.html" title="The exception type for ompl.">Exception</a>(<span class="stringliteral">&quot;Internal error in path interpolation. This should never happen. Please contact the developers.&quot;</span>);
<a name="l00319"></a>00319 }
<a name="l00320"></a>00320 
<a name="l00321"></a><a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#ae4b56284e4b049df559fcb1320f69fa5">00321</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#ae4b56284e4b049df559fcb1320f69fa5" title="Reverse the path.">ompl::geometric::PathGeometric::reverse</a>(<span class="keywordtype">void</span>)
<a name="l00322"></a>00322 {
<a name="l00323"></a>00323     std::reverse(states.begin(), states.end());
<a name="l00324"></a>00324 }
<a name="l00325"></a>00325 
<a name="l00326"></a><a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a3f6694c69e6e19c1f6961f5e47db4440">00326</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a3f6694c69e6e19c1f6961f5e47db4440" title="Set this path to a random segment.">ompl::geometric::PathGeometric::random</a>(<span class="keywordtype">void</span>)
<a name="l00327"></a>00327 {
<a name="l00328"></a>00328     freeMemory();
<a name="l00329"></a>00329     states.resize(2);
<a name="l00330"></a>00330     states[0] = si_-&gt;allocState();
<a name="l00331"></a>00331     states[1] = si_-&gt;allocState();
<a name="l00332"></a>00332     <a class="code" href="classompl_1_1base_1_1StateSamplerPtr.html" title="A boost shared pointer wrapper for ompl::base::StateSampler.">base::StateSamplerPtr</a> ss = si_-&gt;allocStateSampler();
<a name="l00333"></a>00333     ss-&gt;sampleUniform(states[0]);
<a name="l00334"></a>00334     ss-&gt;sampleUniform(states[1]);
<a name="l00335"></a>00335 }
<a name="l00336"></a>00336 
<a name="l00337"></a><a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a1441132f612f309257fb172def71de1a">00337</a> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a1441132f612f309257fb172def71de1a" title="Set this path to a random valid segment. Sample attempts times for valid segments. Returns true on success.">ompl::geometric::PathGeometric::randomValid</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> attempts)
<a name="l00338"></a>00338 {
<a name="l00339"></a>00339     freeMemory();
<a name="l00340"></a>00340     states.resize(2);
<a name="l00341"></a>00341     states[0] = si_-&gt;allocState();
<a name="l00342"></a>00342     states[1] = si_-&gt;allocState();
<a name="l00343"></a>00343     <a class="code" href="classompl_1_1base_1_1UniformValidStateSampler.html" title="A state sampler that only samples valid states, uniformly.">base::UniformValidStateSampler</a> *uvss = <span class="keyword">new</span> <a class="code" href="classompl_1_1base_1_1UniformValidStateSampler.html" title="A state sampler that only samples valid states, uniformly.">base::UniformValidStateSampler</a>(si_.get());
<a name="l00344"></a>00344     uvss-&gt;<a class="code" href="classompl_1_1base_1_1ValidStateSampler.html#aa134892ca5a8ae0c5ec2e37693787090" title="Finding a valid sample usually requires performing multiple attempts. This call allows setting the nu...">setNrAttempts</a>(attempts);
<a name="l00345"></a>00345     <span class="keywordtype">bool</span> ok = <span class="keyword">false</span>;
<a name="l00346"></a>00346     <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i &lt; attempts ; ++i)
<a name="l00347"></a>00347     {
<a name="l00348"></a>00348         <span class="keywordflow">if</span> (uvss-&gt;<a class="code" href="classompl_1_1base_1_1UniformValidStateSampler.html#a8e0136c7ed25a4bfd552c6cabaebcdb3" title="Sample a state. Return false in case of failure.">sample</a>(states[0]) &amp;&amp; uvss-&gt;<a class="code" href="classompl_1_1base_1_1UniformValidStateSampler.html#a8e0136c7ed25a4bfd552c6cabaebcdb3" title="Sample a state. Return false in case of failure.">sample</a>(states[1]))
<a name="l00349"></a>00349             <span class="keywordflow">if</span> (si_-&gt;checkMotion(states[0], states[1]))
<a name="l00350"></a>00350             {
<a name="l00351"></a>00351                 ok = <span class="keyword">true</span>;
<a name="l00352"></a>00352                 <span class="keywordflow">break</span>;
<a name="l00353"></a>00353             }
<a name="l00354"></a>00354     }
<a name="l00355"></a>00355     <span class="keyword">delete</span> uvss;
<a name="l00356"></a>00356     <span class="keywordflow">if</span> (!ok)
<a name="l00357"></a>00357     {
<a name="l00358"></a>00358         freeMemory();
<a name="l00359"></a>00359         states.clear();
<a name="l00360"></a>00360     }
<a name="l00361"></a>00361     <span class="keywordflow">return</span> ok;
<a name="l00362"></a>00362 }
<a name="l00363"></a>00363 
<a name="l00364"></a><a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#addc7c545fa8a284978c1e1e016425779">00364</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#addc7c545fa8a284978c1e1e016425779" title="Overlay the path over on top of the current path. States are added to the current path if needed (by ...">ompl::geometric::PathGeometric::overlay</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html" title="Definition of a geometric path.">PathGeometric</a> &amp;over, <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> startIndex)
<a name="l00365"></a>00365 {
<a name="l00366"></a>00366     <span class="keywordflow">if</span> (startIndex &gt; states.size())
<a name="l00367"></a>00367         <span class="keywordflow">throw</span> <a class="code" href="classompl_1_1Exception.html" title="The exception type for ompl.">Exception</a>(<span class="stringliteral">&quot;Index on path is out of bounds&quot;</span>);
<a name="l00368"></a>00368     <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1StateSpacePtr.html" title="A boost shared pointer wrapper for ompl::base::StateSpace.">base::StateSpacePtr</a> &amp;sm = over.<a class="code" href="classompl_1_1base_1_1Path.html#a87250f099dbe84a3c0ba515360ac4339" title="The space information this path is part of.">si_</a>-&gt;getStateSpace();
<a name="l00369"></a>00369     <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1StateSpacePtr.html" title="A boost shared pointer wrapper for ompl::base::StateSpace.">base::StateSpacePtr</a> &amp;dm = si_-&gt;getStateSpace();
<a name="l00370"></a>00370     <span class="keywordtype">bool</span> copy = !states.empty();
<a name="l00371"></a>00371     <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0, j = startIndex ; i &lt; over.<a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a3a729dab22338b733888bc2f9c9769a4" title="The list of states that make up the path.">states</a>.size() ; ++i, ++j)
<a name="l00372"></a>00372     {
<a name="l00373"></a>00373         <span class="keywordflow">if</span> (j == states.size())
<a name="l00374"></a>00374         {
<a name="l00375"></a>00375             <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">base::State</a> *s = si_-&gt;allocState();
<a name="l00376"></a>00376             <span class="keywordflow">if</span> (copy)
<a name="l00377"></a>00377                 si_-&gt;copyState(s, states.back());
<a name="l00378"></a>00378             states.push_back(s);
<a name="l00379"></a>00379         }
<a name="l00380"></a>00380 
<a name="l00381"></a>00381         copyStateData(dm, states[j], sm, over.<a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a3a729dab22338b733888bc2f9c9769a4" title="The list of states that make up the path.">states</a>[i]);
<a name="l00382"></a>00382     }
<a name="l00383"></a>00383 }
<a name="l00384"></a>00384 
<a name="l00385"></a><a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#aa054135956c0ce6c7c447451a0a02cbb">00385</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#aa054135956c0ce6c7c447451a0a02cbb" title="Append path at the end of this path.">ompl::geometric::PathGeometric::append</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html" title="Definition of a geometric path.">PathGeometric</a> &amp;path)
<a name="l00386"></a>00386 {
<a name="l00387"></a>00387     <span class="keywordflow">if</span> (path.<a class="code" href="classompl_1_1base_1_1Path.html#a87250f099dbe84a3c0ba515360ac4339" title="The space information this path is part of.">si_</a>-&gt;getStateSpace()-&gt;getName() == si_-&gt;getStateSpace()-&gt;getName())
<a name="l00388"></a>00388     {
<a name="l00389"></a>00389         <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html" title="Definition of a geometric path.">PathGeometric</a> copy(path);
<a name="l00390"></a>00390         states.insert(states.end(), copy.<a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a3a729dab22338b733888bc2f9c9769a4" title="The list of states that make up the path.">states</a>.begin(), copy.<a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a3a729dab22338b733888bc2f9c9769a4" title="The list of states that make up the path.">states</a>.end());
<a name="l00391"></a>00391         copy.<a class="code" href="classompl_1_1geometric_1_1PathGeometric.html#a3a729dab22338b733888bc2f9c9769a4" title="The list of states that make up the path.">states</a>.clear();
<a name="l00392"></a>00392     }
<a name="l00393"></a>00393     <span class="keywordflow">else</span>
<a name="l00394"></a>00394         overlay(path, states.size());
<a name="l00395"></a>00395 }
</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>