<!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/base/src/SpaceInformation.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"> </span>All</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(1)"><span class="SelectionMark"> </span>Classes</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(2)"><span class="SelectionMark"> </span>Namespaces</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(3)"><span class="SelectionMark"> </span>Functions</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(4)"><span class="SelectionMark"> </span>Variables</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(5)"><span class="SelectionMark"> </span>Typedefs</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(6)"><span class="SelectionMark"> </span>Enumerations</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(7)"><span class="SelectionMark"> </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_40bc83a902349ad67ef9d1cb49964511.html">base</a> </li> <li class="navelem"><a class="el" href="dir_638c121d1114340bf3e84a5e9d67e9f2.html">src</a> </li> </ul> </div> </div> <div class="header"> <div class="headertitle"> <div class="title">SpaceInformation.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">* "AS IS" 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 "ompl/base/SpaceInformation.h"</span> <a name="l00038"></a>00038 <span class="preprocessor">#include "ompl/base/samplers/UniformValidStateSampler.h"</span> <a name="l00039"></a>00039 <span class="preprocessor">#include "ompl/base/DiscreteMotionValidator.h"</span> <a name="l00040"></a>00040 <span class="preprocessor">#include "ompl/util/Exception.h"</span> <a name="l00041"></a>00041 <span class="preprocessor">#include "ompl/tools/config/MagicConstants.h"</span> <a name="l00042"></a>00042 <span class="preprocessor">#include <queue></span> <a name="l00043"></a>00043 <span class="preprocessor">#include <cassert></span> <a name="l00044"></a>00044 <a name="l00045"></a><a class="code" href="classompl_1_1base_1_1SpaceInformation.html#a60718797ea47fe7ccd4a5c14acaee510">00045</a> <a class="code" href="classompl_1_1base_1_1SpaceInformation.html#a60718797ea47fe7ccd4a5c14acaee510" title="Constructor. Sets the instance of the state space to plan with.">ompl::base::SpaceInformation::SpaceInformation</a>(<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.">StateSpacePtr</a> &space) : <a name="l00046"></a>00046 stateSpace_(space), motionValidator_(new <a class="code" href="classompl_1_1base_1_1DiscreteMotionValidator.html" title="A motion validator that only uses the state validity checker. Motions are checked for validity at a s...">DiscreteMotionValidator</a>(this)), setup_(false), msg_(<span class="stringliteral">"SpaceInformation"</span>) <a name="l00047"></a>00047 { <a name="l00048"></a>00048 <span class="keywordflow">if</span> (!<a class="code" href="classompl_1_1base_1_1SpaceInformation.html#ab7d8d572b76a5899b6c3816a544abe7a" title="The state space planning is to be performed in.">stateSpace_</a>) <a name="l00049"></a>00049 <span class="keywordflow">throw</span> <a class="code" href="classompl_1_1Exception.html" title="The exception type for ompl.">Exception</a>(<span class="stringliteral">"Invalid space definition"</span>); <a name="l00050"></a>00050 } <a name="l00051"></a>00051 <a name="l00052"></a><a class="code" href="classompl_1_1base_1_1SpaceInformation.html#ac39aa0c4b92e3ca5acfa75eeb56b080f">00052</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1base_1_1SpaceInformation.html#ac39aa0c4b92e3ca5acfa75eeb56b080f" title="Perform additional setup tasks (run once, before use). If state validity checking resolution has not ...">ompl::base::SpaceInformation::setup</a>(<span class="keywordtype">void</span>) <a name="l00053"></a>00053 { <a name="l00054"></a>00054 <span class="keywordflow">if</span> (!stateValidityChecker_) <a name="l00055"></a>00055 { <a name="l00056"></a>00056 stateValidityChecker_.reset(<span class="keyword">new</span> <a class="code" href="classompl_1_1base_1_1AllValidStateValidityChecker.html" title="The simplest state validity checker: all states are valid.">AllValidStateValidityChecker</a>(<span class="keyword">this</span>)); <a name="l00057"></a>00057 msg_.warn(<span class="stringliteral">"State validity checker not set! No collision checking is performed"</span>); <a name="l00058"></a>00058 } <a name="l00059"></a>00059 <a name="l00060"></a>00060 <span class="keywordflow">if</span> (!motionValidator_) <a name="l00061"></a>00061 motionValidator_.reset(<span class="keyword">new</span> <a class="code" href="classompl_1_1base_1_1DiscreteMotionValidator.html" title="A motion validator that only uses the state validity checker. Motions are checked for validity at a s...">DiscreteMotionValidator</a>(<span class="keyword">this</span>)); <a name="l00062"></a>00062 <a name="l00063"></a>00063 stateSpace_->setup(); <a name="l00064"></a>00064 <span class="keywordflow">if</span> (stateSpace_->getDimension() <= 0) <a name="l00065"></a>00065 <span class="keywordflow">throw</span> <a class="code" href="classompl_1_1Exception.html" title="The exception type for ompl.">Exception</a>(<span class="stringliteral">"The dimension of the state space we plan in must be > 0"</span>); <a name="l00066"></a>00066 <a name="l00067"></a>00067 setup_ = <span class="keyword">true</span>; <a name="l00068"></a>00068 } <a name="l00069"></a>00069 <a name="l00070"></a><a class="code" href="classompl_1_1base_1_1SpaceInformation.html#a9260fb70aa7d41e968c97d90f9f25867">00070</a> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1base_1_1SpaceInformation.html#a9260fb70aa7d41e968c97d90f9f25867" title="Return true if setup was called.">ompl::base::SpaceInformation::isSetup</a>(<span class="keywordtype">void</span>)<span class="keyword"> const</span> <a name="l00071"></a>00071 <span class="keyword"></span>{ <a name="l00072"></a>00072 <span class="keywordflow">return</span> setup_; <a name="l00073"></a>00073 } <a name="l00074"></a>00074 <a name="l00075"></a><a class="code" href="classompl_1_1base_1_1SpaceInformation.html#ac60c96cd6f8450bf8cd1a3a08ed1dee6">00075</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1base_1_1SpaceInformation.html#a0449ec0893e02aca2bdfc63323b624e5" title="Set the instance of the state validity checker to use. Parallel implementations of planners assume th...">ompl::base::SpaceInformation::setStateValidityChecker</a>(<span class="keyword">const</span> <a class="code" href="namespaceompl_1_1base.html#a208ad51fcef09961293d23b589a4dbfa" title="If no state validity checking class is specified (StateValidityChecker), a boost function can be spec...">StateValidityCheckerFn</a> &svc) <a name="l00076"></a>00076 { <a name="l00077"></a>00077 <span class="keyword">class </span>BoostFnStateValidityChecker : <span class="keyword">public</span> <a class="code" href="classompl_1_1base_1_1StateValidityChecker.html" title="Abstract definition for a class checking the validity of states. The implementation of this class mus...">StateValidityChecker</a> <a name="l00078"></a>00078 { <a name="l00079"></a>00079 <span class="keyword">public</span>: <a name="l00080"></a>00080 <a name="l00081"></a>00081 BoostFnStateValidityChecker(<a class="code" href="classompl_1_1base_1_1SpaceInformation.html" title="The base class for space information. This contains all the information about the space planning is d...">SpaceInformation</a>* si, <a name="l00082"></a>00082 <span class="keyword">const</span> <a class="code" href="namespaceompl_1_1base.html#a208ad51fcef09961293d23b589a4dbfa" title="If no state validity checking class is specified (StateValidityChecker), a boost function can be spec...">StateValidityCheckerFn</a> &fn) : <a class="code" href="classompl_1_1base_1_1StateValidityChecker.html" title="Abstract definition for a class checking the validity of states. The implementation of this class mus...">StateValidityChecker</a>(si), fn_(fn) <a name="l00083"></a>00083 { <a name="l00084"></a>00084 } <a name="l00085"></a>00085 <a name="l00086"></a>00086 <span class="keyword">virtual</span> <span class="keywordtype">bool</span> isValid(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *state)<span class="keyword"> const</span> <a name="l00087"></a>00087 <span class="keyword"> </span>{ <a name="l00088"></a>00088 <span class="keywordflow">return</span> fn_(state); <a name="l00089"></a>00089 } <a name="l00090"></a>00090 <a name="l00091"></a>00091 <span class="keyword">protected</span>: <a name="l00092"></a>00092 <a name="l00093"></a>00093 <a class="code" href="namespaceompl_1_1base.html#a208ad51fcef09961293d23b589a4dbfa" title="If no state validity checking class is specified (StateValidityChecker), a boost function can be spec...">StateValidityCheckerFn</a> fn_; <a name="l00094"></a>00094 }; <a name="l00095"></a>00095 <a name="l00096"></a>00096 <span class="keywordflow">if</span> (!svc) <a name="l00097"></a>00097 <span class="keywordflow">throw</span> <a class="code" href="classompl_1_1Exception.html" title="The exception type for ompl.">Exception</a>(<span class="stringliteral">"Invalid function definition for state validity checking"</span>); <a name="l00098"></a>00098 <a name="l00099"></a>00099 setStateValidityChecker(<a class="code" href="classompl_1_1base_1_1StateValidityCheckerPtr.html" title="A boost shared pointer wrapper for ompl::base::StateValidityChecker.">StateValidityCheckerPtr</a>(dynamic_cast<StateValidityChecker*>(<span class="keyword">new</span> BoostFnStateValidityChecker(<span class="keyword">this</span>, svc)))); <a name="l00100"></a>00100 } <a name="l00101"></a>00101 <a name="l00102"></a><a class="code" href="classompl_1_1base_1_1SpaceInformation.html#a67f3734521dd86233648b0c9c3c80e74">00102</a> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="classompl_1_1base_1_1SpaceInformation.html#a67f3734521dd86233648b0c9c3c80e74" title="Produce a valid motion starting at start by randomly bouncing off of invalid states. The start state start is not included in the computed motion (states). Returns the number of elements written to states (less or equal to steps).">ompl::base::SpaceInformation::randomBounceMotion</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1StateSamplerPtr.html" title="A boost shared pointer wrapper for ompl::base::StateSampler.">StateSamplerPtr</a> &sss, <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *start, <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> steps, std::vector<State*> &states, <span class="keywordtype">bool</span> alloc)<span class="keyword"> const</span> <a name="l00103"></a>00103 <span class="keyword"></span>{ <a name="l00104"></a>00104 <span class="keywordflow">if</span> (alloc) <a name="l00105"></a>00105 { <a name="l00106"></a>00106 states.resize(steps); <a name="l00107"></a>00107 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < steps ; ++i) <a name="l00108"></a>00108 states[i] = allocState(); <a name="l00109"></a>00109 } <a name="l00110"></a>00110 <span class="keywordflow">else</span> <a name="l00111"></a>00111 <span class="keywordflow">if</span> (states.size() < steps) <a name="l00112"></a>00112 steps = states.size(); <a name="l00113"></a>00113 <a name="l00114"></a>00114 <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *prev = start; <a name="l00115"></a>00115 std::pair<State*, double> lastValid; <a name="l00116"></a>00116 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> j = 0; <a name="l00117"></a>00117 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < steps ; ++i) <a name="l00118"></a>00118 { <a name="l00119"></a>00119 sss->sampleUniform(states[j]); <a name="l00120"></a>00120 lastValid.first = states[j]; <a name="l00121"></a>00121 <span class="keywordflow">if</span> (checkMotion(prev, states[j], lastValid) || lastValid.second > std::numeric_limits<double>::epsilon()) <a name="l00122"></a>00122 prev = states[j++]; <a name="l00123"></a>00123 } <a name="l00124"></a>00124 <a name="l00125"></a>00125 <span class="keywordflow">return</span> j; <a name="l00126"></a>00126 } <a name="l00127"></a>00127 <a name="l00128"></a><a class="code" href="classompl_1_1base_1_1SpaceInformation.html#ac4d572f3f831e3cfb96bd387b05798cf">00128</a> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1base_1_1SpaceInformation.html#af936d24f2adf320e2158c855a0dad0af" title="Find a valid state near a given one. If the given state is valid, it will be returned itself...">ompl::base::SpaceInformation::searchValidNearby</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1ValidStateSamplerPtr.html" title="A boost shared pointer wrapper for ompl::base::ValidStateSampler.">ValidStateSamplerPtr</a> &sampler, <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *state, <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *near, <span class="keywordtype">double</span> distance)<span class="keyword"> const</span> <a name="l00129"></a>00129 <span class="keyword"></span>{ <a name="l00130"></a>00130 <span class="keywordflow">if</span> (state != near) <a name="l00131"></a>00131 copyState(state, near); <a name="l00132"></a>00132 <a name="l00133"></a>00133 <span class="comment">// fix bounds, if needed</span> <a name="l00134"></a>00134 <span class="keywordflow">if</span> (!satisfiesBounds(state)) <a name="l00135"></a>00135 enforceBounds(state); <a name="l00136"></a>00136 <a name="l00137"></a>00137 <span class="keywordtype">bool</span> result = isValid(state); <a name="l00138"></a>00138 <a name="l00139"></a>00139 <span class="keywordflow">if</span> (!result) <a name="l00140"></a>00140 { <a name="l00141"></a>00141 <span class="comment">// try to find a valid state nearby</span> <a name="l00142"></a>00142 <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *temp = cloneState(state); <a name="l00143"></a>00143 result = sampler->sampleNear(state, temp, distance); <a name="l00144"></a>00144 freeState(temp); <a name="l00145"></a>00145 } <a name="l00146"></a>00146 <a name="l00147"></a>00147 <span class="keywordflow">return</span> result; <a name="l00148"></a>00148 } <a name="l00149"></a>00149 <a name="l00150"></a><a class="code" href="classompl_1_1base_1_1SpaceInformation.html#af936d24f2adf320e2158c855a0dad0af">00150</a> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1base_1_1SpaceInformation.html#af936d24f2adf320e2158c855a0dad0af" title="Find a valid state near a given one. If the given state is valid, it will be returned itself...">ompl::base::SpaceInformation::searchValidNearby</a>(<a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *state, <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *near, <span class="keywordtype">double</span> distance, <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> attempts)<span class="keyword"> const</span> <a name="l00151"></a>00151 <span class="keyword"></span>{ <a name="l00152"></a>00152 <span class="keywordflow">if</span> (satisfiesBounds(near) && isValid(near)) <a name="l00153"></a>00153 { <a name="l00154"></a>00154 <span class="keywordflow">if</span> (state != near) <a name="l00155"></a>00155 copyState(state, near); <a name="l00156"></a>00156 <span class="keywordflow">return</span> <span class="keyword">true</span>; <a name="l00157"></a>00157 } <a name="l00158"></a>00158 <span class="keywordflow">else</span> <a name="l00159"></a>00159 { <a name="l00160"></a>00160 <span class="comment">// try to find a valid state nearby</span> <a name="l00161"></a>00161 <a class="code" href="classompl_1_1base_1_1UniformValidStateSampler.html" title="A state sampler that only samples valid states, uniformly.">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.">UniformValidStateSampler</a>(<span class="keyword">this</span>); <a name="l00162"></a>00162 uvss-><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="l00163"></a>00163 <span class="keywordflow">return</span> searchValidNearby(<a class="code" href="classompl_1_1base_1_1ValidStateSamplerPtr.html" title="A boost shared pointer wrapper for ompl::base::ValidStateSampler.">ValidStateSamplerPtr</a>(uvss), state, near, distance); <a name="l00164"></a>00164 } <a name="l00165"></a>00165 } <a name="l00166"></a>00166 <a name="l00167"></a><a class="code" href="classompl_1_1base_1_1SpaceInformation.html#a3e5a6cdbe7c636d8e60ed7833c573668">00167</a> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="classompl_1_1base_1_1SpaceInformation.html#a3e5a6cdbe7c636d8e60ed7833c573668" title="Get count states that make up a motion between s1 and s2. Returns the number of states that were adde...">ompl::base::SpaceInformation::getMotionStates</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *s1, <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *s2, std::vector<State*> &states, <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> count, <span class="keywordtype">bool</span> endpoints, <span class="keywordtype">bool</span> alloc)<span class="keyword"> const</span> <a name="l00168"></a>00168 <span class="keyword"></span>{ <a name="l00169"></a>00169 <span class="comment">// add 1 to the number of states we want to add between s1 & s2. This gives us the number of segments to split the motion into</span> <a name="l00170"></a>00170 count++; <a name="l00171"></a>00171 <a name="l00172"></a>00172 <span class="keywordflow">if</span> (count < 2) <a name="l00173"></a>00173 { <a name="l00174"></a>00174 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> added = 0; <a name="l00175"></a>00175 <a name="l00176"></a>00176 <span class="comment">// if they want endpoints, then at most endpoints are included</span> <a name="l00177"></a>00177 <span class="keywordflow">if</span> (endpoints) <a name="l00178"></a>00178 { <a name="l00179"></a>00179 <span class="keywordflow">if</span> (alloc) <a name="l00180"></a>00180 { <a name="l00181"></a>00181 states.resize(2); <a name="l00182"></a>00182 states[0] = allocState(); <a name="l00183"></a>00183 states[1] = allocState(); <a name="l00184"></a>00184 } <a name="l00185"></a>00185 <span class="keywordflow">if</span> (states.size() > 0) <a name="l00186"></a>00186 { <a name="l00187"></a>00187 copyState(states[0], s1); <a name="l00188"></a>00188 added++; <a name="l00189"></a>00189 } <a name="l00190"></a>00190 <a name="l00191"></a>00191 <span class="keywordflow">if</span> (states.size() > 1) <a name="l00192"></a>00192 { <a name="l00193"></a>00193 copyState(states[1], s2); <a name="l00194"></a>00194 added++; <a name="l00195"></a>00195 } <a name="l00196"></a>00196 } <a name="l00197"></a>00197 <span class="keywordflow">else</span> <a name="l00198"></a>00198 <span class="keywordflow">if</span> (alloc) <a name="l00199"></a>00199 states.resize(0); <a name="l00200"></a>00200 <span class="keywordflow">return</span> added; <a name="l00201"></a>00201 } <a name="l00202"></a>00202 <a name="l00203"></a>00203 <span class="keywordflow">if</span> (alloc) <a name="l00204"></a>00204 { <a name="l00205"></a>00205 states.resize(count + (endpoints ? 1 : -1)); <a name="l00206"></a>00206 <span class="keywordflow">if</span> (endpoints) <a name="l00207"></a>00207 states[0] = allocState(); <a name="l00208"></a>00208 } <a name="l00209"></a>00209 <a name="l00210"></a>00210 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> added = 0; <a name="l00211"></a>00211 <a name="l00212"></a>00212 <span class="keywordflow">if</span> (endpoints && states.size() > 0) <a name="l00213"></a>00213 { <a name="l00214"></a>00214 copyState(states[0], s1); <a name="l00215"></a>00215 added++; <a name="l00216"></a>00216 } <a name="l00217"></a>00217 <a name="l00218"></a>00218 <span class="comment">/* find the states in between */</span> <a name="l00219"></a>00219 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> j = 1 ; j < count && added < states.size() ; ++j) <a name="l00220"></a>00220 { <a name="l00221"></a>00221 <span class="keywordflow">if</span> (alloc) <a name="l00222"></a>00222 states[added] = allocState(); <a name="l00223"></a>00223 stateSpace_->interpolate(s1, s2, (<span class="keywordtype">double</span>)j / (<span class="keywordtype">double</span>)count, states[added]); <a name="l00224"></a>00224 added++; <a name="l00225"></a>00225 } <a name="l00226"></a>00226 <a name="l00227"></a>00227 <span class="keywordflow">if</span> (added < states.size() && endpoints) <a name="l00228"></a>00228 { <a name="l00229"></a>00229 <span class="keywordflow">if</span> (alloc) <a name="l00230"></a>00230 states[added] = allocState(); <a name="l00231"></a>00231 copyState(states[added], s2); <a name="l00232"></a>00232 added++; <a name="l00233"></a>00233 } <a name="l00234"></a>00234 <a name="l00235"></a>00235 <span class="keywordflow">return</span> added; <a name="l00236"></a>00236 } <a name="l00237"></a>00237 <a name="l00238"></a>00238 <a name="l00239"></a><a class="code" href="classompl_1_1base_1_1SpaceInformation.html#a6db453dae47c734046689c11fe7173f1">00239</a> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1base_1_1SpaceInformation.html#a6047b893546bab139139104a0a7b756e" title="Incrementally check if the path between two motions is valid. Also compute the last state that was va...">ompl::base::SpaceInformation::checkMotion</a>(<span class="keyword">const</span> std::vector<State*> &states, <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> count, <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> &firstInvalidStateIndex)<span class="keyword"> const</span> <a name="l00240"></a>00240 <span class="keyword"></span>{ <a name="l00241"></a>00241 assert(states.size() >= count); <a name="l00242"></a>00242 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < count ; ++i) <a name="l00243"></a>00243 <span class="keywordflow">if</span> (!isValid(states[i])) <a name="l00244"></a>00244 { <a name="l00245"></a>00245 firstInvalidStateIndex = i; <a name="l00246"></a>00246 <span class="keywordflow">return</span> <span class="keyword">false</span>; <a name="l00247"></a>00247 } <a name="l00248"></a>00248 <span class="keywordflow">return</span> <span class="keyword">true</span>; <a name="l00249"></a>00249 } <a name="l00250"></a>00250 <a name="l00251"></a><a class="code" href="classompl_1_1base_1_1SpaceInformation.html#a7bdcc0c19a133e5d324af2c536c3779d">00251</a> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1base_1_1SpaceInformation.html#a6047b893546bab139139104a0a7b756e" title="Incrementally check if the path between two motions is valid. Also compute the last state that was va...">ompl::base::SpaceInformation::checkMotion</a>(<span class="keyword">const</span> std::vector<State*> &states, <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> count)<span class="keyword"> const</span> <a name="l00252"></a>00252 <span class="keyword"></span>{ <a name="l00253"></a>00253 assert(states.size() >= count); <a name="l00254"></a>00254 <span class="keywordflow">if</span> (count > 0) <a name="l00255"></a>00255 { <a name="l00256"></a>00256 <span class="keywordflow">if</span> (count > 1) <a name="l00257"></a>00257 { <a name="l00258"></a>00258 <span class="keywordflow">if</span> (!isValid(states.front())) <a name="l00259"></a>00259 <span class="keywordflow">return</span> <span class="keyword">false</span>; <a name="l00260"></a>00260 <span class="keywordflow">if</span> (!isValid(states[count - 1])) <a name="l00261"></a>00261 <span class="keywordflow">return</span> <span class="keyword">false</span>; <a name="l00262"></a>00262 <a name="l00263"></a>00263 <span class="comment">// we have 2 or more states, and the first and last states are valid</span> <a name="l00264"></a>00264 <a name="l00265"></a>00265 <span class="keywordflow">if</span> (count > 2) <a name="l00266"></a>00266 { <a name="l00267"></a>00267 std::queue< std::pair<int, int> > pos; <a name="l00268"></a>00268 pos.push(std::make_pair(0, count - 1)); <a name="l00269"></a>00269 <a name="l00270"></a>00270 <span class="keywordflow">while</span> (!pos.empty()) <a name="l00271"></a>00271 { <a name="l00272"></a>00272 std::pair<int, int> x = pos.front(); <a name="l00273"></a>00273 <a name="l00274"></a>00274 <span class="keywordtype">int</span> mid = (x.first + x.second) / 2; <a name="l00275"></a>00275 <span class="keywordflow">if</span> (!isValid(states[mid])) <a name="l00276"></a>00276 <span class="keywordflow">return</span> <span class="keyword">false</span>; <a name="l00277"></a>00277 <a name="l00278"></a>00278 <span class="keywordflow">if</span> (x.first < mid - 1) <a name="l00279"></a>00279 pos.push(std::make_pair(x.first, mid)); <a name="l00280"></a>00280 <span class="keywordflow">if</span> (x.second > mid + 1) <a name="l00281"></a>00281 pos.push(std::make_pair(mid, x.second)); <a name="l00282"></a>00282 } <a name="l00283"></a>00283 } <a name="l00284"></a>00284 } <a name="l00285"></a>00285 <span class="keywordflow">else</span> <a name="l00286"></a>00286 <span class="keywordflow">return</span> isValid(states.front()); <a name="l00287"></a>00287 } <a name="l00288"></a>00288 <span class="keywordflow">return</span> <span class="keyword">true</span>; <a name="l00289"></a>00289 } <a name="l00290"></a>00290 <a name="l00291"></a><a class="code" href="classompl_1_1base_1_1SpaceInformation.html#acb94231d22c1763e3f79e5d67e5e7428">00291</a> <a class="code" href="classompl_1_1base_1_1ValidStateSamplerPtr.html" title="A boost shared pointer wrapper for ompl::base::ValidStateSampler.">ompl::base::ValidStateSamplerPtr</a> <a class="code" href="classompl_1_1base_1_1SpaceInformation.html#acb94231d22c1763e3f79e5d67e5e7428" title="Allocate an instance of a valid state sampler for this space. If setValidStateSamplerAllocator() was ...">ompl::base::SpaceInformation::allocValidStateSampler</a>(<span class="keywordtype">void</span>)<span class="keyword"> const</span> <a name="l00292"></a>00292 <span class="keyword"></span>{ <a name="l00293"></a>00293 <span class="keywordflow">if</span> (vssa_) <a name="l00294"></a>00294 <span class="keywordflow">return</span> vssa_(<span class="keyword">this</span>); <a name="l00295"></a>00295 <span class="keywordflow">else</span> <a name="l00296"></a>00296 <span class="keywordflow">return</span> <a class="code" href="classompl_1_1base_1_1ValidStateSamplerPtr.html" title="A boost shared pointer wrapper for ompl::base::ValidStateSampler.">ValidStateSamplerPtr</a>(<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.">UniformValidStateSampler</a>(<span class="keyword">this</span>)); <a name="l00297"></a>00297 } <a name="l00298"></a>00298 <a name="l00299"></a><a class="code" href="classompl_1_1base_1_1SpaceInformation.html#a84daee3700b856630c676b37536c9787">00299</a> <span class="keywordtype">double</span> <a class="code" href="classompl_1_1base_1_1SpaceInformation.html#a84daee3700b856630c676b37536c9787" title="Estimate probability of sampling a valid state. setup() is assumed to have been called.">ompl::base::SpaceInformation::probabilityOfValidState</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> attempts)<span class="keyword"> const</span> <a name="l00300"></a>00300 <span class="keyword"></span>{ <a name="l00301"></a>00301 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> valid = 0; <a name="l00302"></a>00302 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> invalid = 0; <a name="l00303"></a>00303 <a name="l00304"></a>00304 <a class="code" href="classompl_1_1base_1_1StateSamplerPtr.html" title="A boost shared pointer wrapper for ompl::base::StateSampler.">StateSamplerPtr</a> ss = allocStateSampler(); <a name="l00305"></a>00305 <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *s = allocState(); <a name="l00306"></a>00306 <a name="l00307"></a>00307 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < attempts ; ++i) <a name="l00308"></a>00308 { <a name="l00309"></a>00309 ss->sampleUniform(s); <a name="l00310"></a>00310 <span class="keywordflow">if</span> (isValid(s)) <a name="l00311"></a>00311 ++valid; <a name="l00312"></a>00312 <span class="keywordflow">else</span> <a name="l00313"></a>00313 ++invalid; <a name="l00314"></a>00314 } <a name="l00315"></a>00315 <a name="l00316"></a>00316 freeState(s); <a name="l00317"></a>00317 <a name="l00318"></a>00318 <span class="keywordflow">return</span> (<span class="keywordtype">double</span>)valid / (double)(valid + invalid); <a name="l00319"></a>00319 } <a name="l00320"></a>00320 <a name="l00321"></a><a class="code" href="classompl_1_1base_1_1SpaceInformation.html#ae83e285ab400971f1e5e6d171a83eb6c">00321</a> <span class="keywordtype">double</span> <a class="code" href="classompl_1_1base_1_1SpaceInformation.html#ae83e285ab400971f1e5e6d171a83eb6c" title="Estimate the length of a valid motion. setup() is assumed to have been called.">ompl::base::SpaceInformation::averageValidMotionLength</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> attempts)<span class="keyword"> const</span> <a name="l00322"></a>00322 <span class="keyword"></span>{ <a name="l00323"></a>00323 <a class="code" href="classompl_1_1base_1_1StateSamplerPtr.html" title="A boost shared pointer wrapper for ompl::base::StateSampler.">StateSamplerPtr</a> ss = allocStateSampler(); <a name="l00324"></a>00324 <a class="code" href="classompl_1_1base_1_1UniformValidStateSampler.html" title="A state sampler that only samples valid states, uniformly.">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.">UniformValidStateSampler</a>(<span class="keyword">this</span>); <a name="l00325"></a>00325 uvss-><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="l00326"></a>00326 <a name="l00327"></a>00327 <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *s1 = allocState(); <a name="l00328"></a>00328 <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *s2 = allocState(); <a name="l00329"></a>00329 <a name="l00330"></a>00330 std::pair<State*, double> lastValid; <a name="l00331"></a>00331 lastValid.first = NULL; <a name="l00332"></a>00332 <a name="l00333"></a>00333 <span class="keywordtype">double</span> d = 0.0; <a name="l00334"></a>00334 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> count = 0; <a name="l00335"></a>00335 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < attempts ; ++i) <a name="l00336"></a>00336 <span class="keywordflow">if</span> (uvss-><a class="code" href="classompl_1_1base_1_1UniformValidStateSampler.html#a8e0136c7ed25a4bfd552c6cabaebcdb3" title="Sample a state. Return false in case of failure.">sample</a>(s1)) <a name="l00337"></a>00337 { <a name="l00338"></a>00338 ++count; <a name="l00339"></a>00339 ss->sampleUniform(s2); <a name="l00340"></a>00340 <span class="keywordflow">if</span> (checkMotion(s1, s2, lastValid)) <a name="l00341"></a>00341 d += distance(s1, s2); <a name="l00342"></a>00342 <span class="keywordflow">else</span> <a name="l00343"></a>00343 d += distance(s1, s2) * lastValid.second; <a name="l00344"></a>00344 } <a name="l00345"></a>00345 <a name="l00346"></a>00346 freeState(s2); <a name="l00347"></a>00347 freeState(s1); <a name="l00348"></a>00348 <span class="keyword">delete</span> uvss; <a name="l00349"></a>00349 <a name="l00350"></a>00350 <span class="keywordflow">if</span> (count > 0) <a name="l00351"></a>00351 <span class="keywordflow">return</span> d / (double)count; <a name="l00352"></a>00352 <span class="keywordflow">else</span> <a name="l00353"></a>00353 <span class="keywordflow">return</span> 0.0; <a name="l00354"></a>00354 } <a name="l00355"></a>00355 <a name="l00356"></a><a class="code" href="classompl_1_1base_1_1SpaceInformation.html#a9887f6b2810e5d3befa9a7b886b5b4dd">00356</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1base_1_1SpaceInformation.html#a9887f6b2810e5d3befa9a7b886b5b4dd" title="Print information about the current instance of the state space.">ompl::base::SpaceInformation::printSettings</a>(std::ostream &out)<span class="keyword"> const</span> <a name="l00357"></a>00357 <span class="keyword"></span>{ <a name="l00358"></a>00358 out << <span class="stringliteral">"Settings for the state space '"</span> << stateSpace_->getName() << <span class="stringliteral">"'"</span> << std::endl; <a name="l00359"></a>00359 out << <span class="stringliteral">" - dimension: "</span> << stateSpace_->getDimension() << std::endl; <a name="l00360"></a>00360 out << <span class="stringliteral">" - state validity check resolution: "</span> << (getStateValidityCheckingResolution() * 100.0) << <span class="charliteral">'%'</span> << std::endl; <a name="l00361"></a>00361 out << <span class="stringliteral">" - valid segment count factor: "</span> << stateSpace_->getValidSegmentCountFactor() << std::endl; <a name="l00362"></a>00362 out << <span class="stringliteral">" - state space:"</span> << std::endl; <a name="l00363"></a>00363 stateSpace_->printSettings(out); <a name="l00364"></a>00364 } <a name="l00365"></a>00365 <a name="l00366"></a><a class="code" href="classompl_1_1base_1_1SpaceInformation.html#abaeaf7d8730ba3c1ae6b428be87a098c">00366</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1base_1_1SpaceInformation.html#abaeaf7d8730ba3c1ae6b428be87a098c" title="Print properties of the current instance of the state space.">ompl::base::SpaceInformation::printProperties</a>(std::ostream &out)<span class="keyword"> const</span> <a name="l00367"></a>00367 <span class="keyword"></span>{ <a name="l00368"></a>00368 out << <span class="stringliteral">"Properties of the state space '"</span> << stateSpace_->getName() << <span class="stringliteral">"'"</span> << std::endl; <a name="l00369"></a>00369 out << <span class="stringliteral">" - extent: "</span> << stateSpace_->getMaximumExtent() << std::endl; <a name="l00370"></a>00370 <span class="keywordflow">if</span> (isSetup()) <a name="l00371"></a>00371 { <a name="l00372"></a>00372 <span class="keywordtype">bool</span> result = <span class="keyword">true</span>; <a name="l00373"></a>00373 <span class="keywordflow">try</span> <a name="l00374"></a>00374 { <a name="l00375"></a>00375 stateSpace_->sanityChecks(); <a name="l00376"></a>00376 } <a name="l00377"></a>00377 <span class="keywordflow">catch</span>(<a class="code" href="classompl_1_1Exception.html" title="The exception type for ompl.">Exception</a> &e) <a name="l00378"></a>00378 { <a name="l00379"></a>00379 result = <span class="keyword">false</span>; <a name="l00380"></a>00380 out << std::endl << <span class="stringliteral">" - SANITY CHECKS FOR STATE SPACE ***DID NOT PASS*** ("</span> << e.what() << <span class="stringliteral">")"</span> << std::endl << std::endl; <a name="l00381"></a>00381 msg_.error(e.what()); <a name="l00382"></a>00382 } <a name="l00383"></a>00383 <span class="keywordflow">if</span> (result) <a name="l00384"></a>00384 out << <span class="stringliteral">" - sanity checks for state space passed"</span> << std::endl; <a name="l00385"></a>00385 out << <span class="stringliteral">" - probability of valid states: "</span> << probabilityOfValidState(<a class="code" href="namespaceompl_1_1magic.html#ad96353c64e790206f36a2fb9b2c7d646" title="When multiple states need to be generated as part of the computation of various information (usually ...">magic::TEST_STATE_COUNT</a>) << std::endl; <a name="l00386"></a>00386 out << <span class="stringliteral">" - average length of a valid motion: "</span> << averageValidMotionLength(<a class="code" href="namespaceompl_1_1magic.html#ad96353c64e790206f36a2fb9b2c7d646" title="When multiple states need to be generated as part of the computation of various information (usually ...">magic::TEST_STATE_COUNT</a>) << std::endl; <a name="l00387"></a>00387 } <a name="l00388"></a>00388 <span class="keywordflow">else</span> <a name="l00389"></a>00389 out << <span class="stringliteral">"Call setup() before to get more information"</span> << std::endl; <a name="l00390"></a>00390 } </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"> </span>All</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(1)"><span class="SelectionMark"> </span>Classes</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(2)"><span class="SelectionMark"> </span>Namespaces</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(3)"><span class="SelectionMark"> </span>Functions</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(4)"><span class="SelectionMark"> </span>Variables</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(5)"><span class="SelectionMark"> </span>Typedefs</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(6)"><span class="SelectionMark"> </span>Enumerations</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(7)"><span class="SelectionMark"> </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> • <a href="http://www.cs.rice.edu">Department of Computer Science</a> • <a href="http://www.rice.edu">Rice University</a><br> <div class="gray">Generated on Sun Oct 9 2011 23:04:39 by <a href="http://www.doxygen.org/index.html">doxygen</a> 1.7.4</div> </div> </div> </body> </html>