Sophie

Sophie

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

ompl-devel-0.9.5-1.fc14.i686.rpm

<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta http-equiv="Content-Type" content="text/xhtml; charset=UTF-8"/>
<title>OMPL: ompl::Benchmark Class Reference</title>
<meta name="author" content="Ioan A. Șucan, Mark Moll, Lydia E. Kavraki">
<link rel="stylesheet" href="../css/screen.css" type="text/css" media="screen, projection">
<link rel="stylesheet" href="../css/print.css" type="text/css" media="print">
<!--[if lt IE 7]>
<script type="text/javascript" src="../js/jquery/jquery.js"></script>
<script type="text/javascript" src="../js/jquery/jquery.dropdown.js"></script>
<![endif]-->
<script type="text/javaScript" src="search/search.js"></script>
<script type="text/javascript">
  var _gaq = _gaq || [];
  _gaq.push(['_setAccount', 'UA-9156598-2']);
  _gaq.push(['_trackPageview']);
  (function() {
    var ga = document.createElement('script'); ga.type = 'text/javascript'; ga.async = true;
    ga.src = ('https:' == document.location.protocol ? 'https://ssl' : 'http://www') + '.google-analytics.com/ga.js';
    var s = document.getElementsByTagName('script')[0]; s.parentNode.insertBefore(ga, s);
  })();
</script>
</head>
<body onload='searchBox.OnSelectItem(0);'>
<script type="text/javascript"><!--
var searchBox = new SearchBox("searchBox", "search",false,'Search API');
--></script>
<div class="navigation" id="top">
  <div class="tabs" id="ompltitle">
    <ul class="tablist">
      <li>The Open Motion Planning Library</li>
      <li id="searchli">
        <div id="MSearchBox" class="MSearchBoxInactive">
        <span class="left">
          <img id="MSearchSelect" src="search/mag_sel.png"
               onmouseover="return searchBox.OnSearchSelectShow()"
               onmouseout="return searchBox.OnSearchSelectHide()"
               alt=""/>
          <input type="text" id="MSearchField" value="Search API" accesskey="S"
               onfocus="searchBox.OnSearchFieldFocus(true)"
               onblur="searchBox.OnSearchFieldFocus(false)"
               onkeyup="searchBox.OnSearchFieldChange(event)"/>
          </span><span class="right">
            <a id="MSearchClose" href="javascript:searchBox.CloseResultsWindow()"><img id="MSearchCloseImg" border="0" src="search/close.png" alt=""/></a>
          </span>
        </div>
      </li>
    </ul>
  </div>

  <ul id="nav" class="dropdown">
    <li class="first"><a href="index.html">Home</a></li>
    <li><a href="download.html">Download</a></li>
    <li><a href="documentation.html">Documentation</a></li>
    <li><span class="dir">Code API</span>
      <ul>
        <li><a href="api_overview.html">API Overview</a></li>
        <li><a href="namespaces.html">Namespaces</a></li>
        <li><a href="annotated.html">Classes</a></li>
        <li><a href="files.html">Files</a></li>
        <li><a href="dirs.html">Directories</a></li>
      </ul>
    </li>
    <li><span class="dir">Community</span>
      <ul>
        <li><a href="developers.html">Developers</a></li>
        <li><a href="thirdparty.html">Contributions</a></li>
        <li><a href="education.html">Education</a></li>
        <li><a href="gallery.html">Gallery</a></li>
      </ul>
    </li>
    <li><span class="dir">About</span>
      <ul>
        <li><a href="license.html">License</a></li>
        <li><a href="citations.html">Citations</a></li>
        <li><a href="acknowledgements.html">Acknowledgments</a></li>
        <li><a href="contact.html">Contact Us</a></li>
      </ul>
    </li>
  </ul>
</div>

<!--- window showing the filter options -->
<div id="MSearchSelectWindow"
  onmouseover="return searchBox.OnSearchSelectShow()"
  onmouseout="return searchBox.OnSearchSelectHide()"
  onkeydown="return searchBox.OnSearchSelectKey(event)">
<a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(0)"><span class="SelectionMark">&#160;</span>All</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(1)"><span class="SelectionMark">&#160;</span>Classes</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(2)"><span class="SelectionMark">&#160;</span>Namespaces</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(3)"><span class="SelectionMark">&#160;</span>Functions</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(4)"><span class="SelectionMark">&#160;</span>Variables</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(5)"><span class="SelectionMark">&#160;</span>Typedefs</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(6)"><span class="SelectionMark">&#160;</span>Enumerations</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(7)"><span class="SelectionMark">&#160;</span>Enumerator</a></div>

<!-- iframe showing the search results (closed by default) -->
<div id="MSearchResultsWindow">
  <iframe src="" frameborder="0"name="MSearchResults" id="MSearchResults"></iframe>
</div>

<div class="container">
  <div class="span-22 push-2 first last">
  <div>
<!-- Generated by Doxygen 1.7.4 -->
<script type="text/javascript"><!--
var searchBox = new SearchBox("searchBox", "search",false,'Search');
--></script>
  <div id="nav-path" class="navpath">
    <ul>
      <li class="navelem"><a class="el" href="namespaceompl.html">ompl</a>      </li>
      <li class="navelem"><a class="el" href="classompl_1_1Benchmark.html">Benchmark</a>      </li>
    </ul>
  </div>
</div>
<div class="header">
  <div class="summary">
<a href="#nested-classes">Classes</a> &#124;
<a href="#pub-types">Public Types</a> &#124;
<a href="#pub-methods">Public Member Functions</a> &#124;
<a href="#pro-attribs">Protected Attributes</a>  </div>
  <div class="headertitle">
<div class="title">ompl::Benchmark Class Reference</div>  </div>
</div>
<div class="contents">
<!-- doxytag: class="ompl::Benchmark" -->
<p><a class="el" href="classompl_1_1Benchmark.html" title="Benchmark a set of planners on a problem instance.">Benchmark</a> a set of planners on a problem instance.  
 <a href="classompl_1_1Benchmark.html#details">More...</a></p>

<p><code>#include &lt;<a class="el" href="Benchmark_8h_source.html">Benchmark.h</a>&gt;</code></p>

<p><a href="classompl_1_1Benchmark-members.html">List of all members.</a></p>
<table class="memberdecls">
<tr><td colspan="2"><h2><a name="nested-classes"></a>
Classes</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">struct &#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="structompl_1_1Benchmark_1_1CompleteExperiment.html">CompleteExperiment</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">This structure holds experimental data for a set of planners.  <a href="structompl_1_1Benchmark_1_1CompleteExperiment.html#details">More...</a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">struct &#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="structompl_1_1Benchmark_1_1PlannerExperiment.html">PlannerExperiment</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The data collected after running a planner multiple times.  <a href="structompl_1_1Benchmark_1_1PlannerExperiment.html#details">More...</a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">struct &#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="structompl_1_1Benchmark_1_1Status.html">Status</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">This structure contains information about the activity of a benchmark instance. If the instance is running, it is possible to find out information such as which planner is currently being tested or how much.  <a href="structompl_1_1Benchmark_1_1Status.html#details">More...</a><br/></td></tr>
<tr><td colspan="2"><h2><a name="pub-types"></a>
Public Types</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a5140cf758234fc69a8d9f828f5ef2e04"></a><!-- doxytag: member="ompl::Benchmark::RunProperties" ref="a5140cf758234fc69a8d9f828f5ef2e04" args="" -->
typedef std::map&lt; std::string, <br class="typebreak"/>
std::string &gt;&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1Benchmark.html#a5140cf758234fc69a8d9f828f5ef2e04">RunProperties</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The data collected from a run of a planner is stored as key-value pairs. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ae7070c3ab312a47276e2e45de7742cfa"></a><!-- doxytag: member="ompl::Benchmark::PreSetupEvent" ref="ae7070c3ab312a47276e2e45de7742cfa" args="" -->
typedef boost::function1&lt; void, <br class="typebreak"/>
const <a class="el" href="classompl_1_1base_1_1PlannerPtr.html">base::PlannerPtr</a> &amp; &gt;&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1Benchmark.html#ae7070c3ab312a47276e2e45de7742cfa">PreSetupEvent</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Signature of function that can be called before a planner execution is started. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ab1a0f51e75e4fc432caad4849bf28026"></a><!-- doxytag: member="ompl::Benchmark::PostSetupEvent" ref="ab1a0f51e75e4fc432caad4849bf28026" args="" -->
typedef boost::function2&lt; void, <br class="typebreak"/>
const <a class="el" href="classompl_1_1base_1_1PlannerPtr.html">base::PlannerPtr</a> <br class="typebreak"/>
&amp;, <a class="el" href="classompl_1_1Benchmark.html#a5140cf758234fc69a8d9f828f5ef2e04">RunProperties</a> &amp; &gt;&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1Benchmark.html#ab1a0f51e75e4fc432caad4849bf28026">PostSetupEvent</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Signature of function that can be called after a planner execution is completed. <br/></td></tr>
<tr><td colspan="2"><h2><a name="pub-methods"></a>
Public Member Functions</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a8fa4b606116d36a9fa190692b72b24fc"></a><!-- doxytag: member="ompl::Benchmark::Benchmark" ref="a8fa4b606116d36a9fa190692b72b24fc" args="(geometric::SimpleSetup &amp;setup, const std::string &amp;name=std::string())" -->
&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1Benchmark.html#a8fa4b606116d36a9fa190692b72b24fc">Benchmark</a> (<a class="el" href="classompl_1_1geometric_1_1SimpleSetup.html">geometric::SimpleSetup</a> &amp;setup, const std::string &amp;name=std::string())</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Constructor needs the SimpleSetup instance needed for planning. Optionally, the experiment name (<em>name</em>) can be specified. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a11749173c6c6ae3c05a004fcc787663a"></a><!-- doxytag: member="ompl::Benchmark::Benchmark" ref="a11749173c6c6ae3c05a004fcc787663a" args="(control::SimpleSetup &amp;setup, const std::string &amp;name=std::string())" -->
&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1Benchmark.html#a11749173c6c6ae3c05a004fcc787663a">Benchmark</a> (<a class="el" href="classompl_1_1control_1_1SimpleSetup.html">control::SimpleSetup</a> &amp;setup, const std::string &amp;name=std::string())</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Constructor needs the SimpleSetup instance needed for planning. Optionally, the experiment name (<em>name</em>) can be specified. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a74762df36d3d4890361d850c74e82cca"></a><!-- doxytag: member="ompl::Benchmark::setExperimentName" ref="a74762df36d3d4890361d850c74e82cca" args="(const std::string &amp;name)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1Benchmark.html#a74762df36d3d4890361d850c74e82cca">setExperimentName</a> (const std::string &amp;name)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Set the name of the experiment. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a8f6fe8d41acbb7e312525d4d2bcda362"></a><!-- doxytag: member="ompl::Benchmark::getExperimentName" ref="a8f6fe8d41acbb7e312525d4d2bcda362" args="(void) const " -->
const std::string &amp;&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1Benchmark.html#a8f6fe8d41acbb7e312525d4d2bcda362">getExperimentName</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Get the name of the experiment. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a5941d80248cf78397aeacfa438c8756d"></a><!-- doxytag: member="ompl::Benchmark::addPlanner" ref="a5941d80248cf78397aeacfa438c8756d" args="(const base::PlannerPtr &amp;planner)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1Benchmark.html#a5941d80248cf78397aeacfa438c8756d">addPlanner</a> (const <a class="el" href="classompl_1_1base_1_1PlannerPtr.html">base::PlannerPtr</a> &amp;planner)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Set the planner to use. If the planner is not set, an attempt is made to use the planner allocator. If no planner allocator is available either, a default planner is set. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a9c60a7a327f621f7aeee8d6daff80203"></a><!-- doxytag: member="ompl::Benchmark::addPlannerAllocator" ref="a9c60a7a327f621f7aeee8d6daff80203" args="(const base::PlannerAllocator &amp;pa)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1Benchmark.html#a9c60a7a327f621f7aeee8d6daff80203">addPlannerAllocator</a> (const <a class="el" href="namespaceompl_1_1base.html#a52191d97eed3ef76517fd4f6f94d27a9">base::PlannerAllocator</a> &amp;pa)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Set the planner allocator to use. This is only used if no planner has been set. This is optional -- a default planner will be used if no planner is otherwise specified. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a2aa434d72e918e8ff9b5f695a25329a1"></a><!-- doxytag: member="ompl::Benchmark::clearPlanners" ref="a2aa434d72e918e8ff9b5f695a25329a1" args="(void)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1Benchmark.html#a2aa434d72e918e8ff9b5f695a25329a1">clearPlanners</a> (void)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Clear the set of planners to be benchmarked. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="aa35638813ff8f0c83b2a531e597ab112"></a><!-- doxytag: member="ompl::Benchmark::setPreRunEvent" ref="aa35638813ff8f0c83b2a531e597ab112" args="(const PreSetupEvent &amp;event)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1Benchmark.html#aa35638813ff8f0c83b2a531e597ab112">setPreRunEvent</a> (const <a class="el" href="classompl_1_1Benchmark.html#ae7070c3ab312a47276e2e45de7742cfa">PreSetupEvent</a> &amp;event)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Set the event to be called before the run of a planner. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="aa063218c2c1d129f340a4821f212f0d3"></a><!-- doxytag: member="ompl::Benchmark::setPostRunEvent" ref="aa063218c2c1d129f340a4821f212f0d3" args="(const PostSetupEvent &amp;event)" -->
void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1Benchmark.html#aa063218c2c1d129f340a4821f212f0d3">setPostRunEvent</a> (const <a class="el" href="classompl_1_1Benchmark.html#ab1a0f51e75e4fc432caad4849bf28026">PostSetupEvent</a> &amp;event)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Set the event to be called after the run of a planner. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">virtual void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1Benchmark.html#a14e970715817e989b272006274a07876">benchmark</a> (double maxTime, double maxMem, unsigned int runCount, bool displayProgress=false)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight"><a class="el" href="classompl_1_1Benchmark.html" title="Benchmark a set of planners on a problem instance.">Benchmark</a> the added planners on the defined problem. Repeated calls clear previously gathered data.  <a href="#a14e970715817e989b272006274a07876"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="abfddb519370491e6e2f95e74e9e1cfe1"></a><!-- doxytag: member="ompl::Benchmark::getStatus" ref="abfddb519370491e6e2f95e74e9e1cfe1" args="(void) const " -->
const <a class="el" href="structompl_1_1Benchmark_1_1Status.html">Status</a> &amp;&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1Benchmark.html#abfddb519370491e6e2f95e74e9e1cfe1">getStatus</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Get the status of the benchmarking code. This function can be called in a separate thread to check how much progress has been made. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a2eae72e11ea4d0cc1ec11b3a4a04a8f6"></a><!-- doxytag: member="ompl::Benchmark::getRecordedExperimentData" ref="a2eae72e11ea4d0cc1ec11b3a4a04a8f6" args="(void) const " -->
const <a class="el" href="structompl_1_1Benchmark_1_1CompleteExperiment.html">CompleteExperiment</a> &amp;&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1Benchmark.html#a2eae72e11ea4d0cc1ec11b3a4a04a8f6">getRecordedExperimentData</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Return all the experiment data that would be written to the results file. The data should not be changed, but it could be useful to quickly extract cartain statistics. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="abaf7d3138d919aa4592f46108f95f4d2"></a><!-- doxytag: member="ompl::Benchmark::saveResultsToStream" ref="abaf7d3138d919aa4592f46108f95f4d2" args="(std::ostream &amp;out=std::cout) const " -->
virtual bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1Benchmark.html#abaf7d3138d919aa4592f46108f95f4d2">saveResultsToStream</a> (std::ostream &amp;out=std::cout) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Save the results of the benchmark to a stream. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="acc0d4a751aeb070d5250e6345809de19"></a><!-- doxytag: member="ompl::Benchmark::saveResultsToFile" ref="acc0d4a751aeb070d5250e6345809de19" args="(const char *filename) const " -->
bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1Benchmark.html#acc0d4a751aeb070d5250e6345809de19">saveResultsToFile</a> (const char *filename) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Save the results of the benchmark to a file. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a848349a734629a46cae8b425ea688018"></a><!-- doxytag: member="ompl::Benchmark::saveResultsToFile" ref="a848349a734629a46cae8b425ea688018" args="(void) const " -->
bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1Benchmark.html#a848349a734629a46cae8b425ea688018">saveResultsToFile</a> (void) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Save the results of the benchmark to a file. The name of the file is the current date and time. <br/></td></tr>
<tr><td colspan="2"><h2><a name="pro-attribs"></a>
Protected Attributes</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="af0aeb774cdfa2cc94cefd6fc80923e5d"></a><!-- doxytag: member="ompl::Benchmark::gsetup_" ref="af0aeb774cdfa2cc94cefd6fc80923e5d" args="" -->
<a class="el" href="classompl_1_1geometric_1_1SimpleSetup.html">geometric::SimpleSetup</a> *&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1Benchmark.html#af0aeb774cdfa2cc94cefd6fc80923e5d">gsetup_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The instance of the problem to benchmark (if geometric planning) <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a180fc28e59e5247cb62d9291405fce0f"></a><!-- doxytag: member="ompl::Benchmark::csetup_" ref="a180fc28e59e5247cb62d9291405fce0f" args="" -->
<a class="el" href="classompl_1_1control_1_1SimpleSetup.html">control::SimpleSetup</a> *&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1Benchmark.html#a180fc28e59e5247cb62d9291405fce0f">csetup_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The instance of the problem to benchmark (if planning with controls) <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a1f06e12a89c69c55407a46138ce79cfd"></a><!-- doxytag: member="ompl::Benchmark::planners_" ref="a1f06e12a89c69c55407a46138ce79cfd" args="" -->
std::vector&lt; <a class="el" href="classompl_1_1base_1_1PlannerPtr.html">base::PlannerPtr</a> &gt;&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1Benchmark.html#a1f06e12a89c69c55407a46138ce79cfd">planners_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The set of planners to be tested. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a74dfbbcaad551d0b74096e80fd1b143c"></a><!-- doxytag: member="ompl::Benchmark::exp_" ref="a74dfbbcaad551d0b74096e80fd1b143c" args="" -->
<a class="el" href="structompl_1_1Benchmark_1_1CompleteExperiment.html">CompleteExperiment</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1Benchmark.html#a74dfbbcaad551d0b74096e80fd1b143c">exp_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The collected experimental data (for all planners) <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="aaa383cc7c3b0bfa7b2987edbfdd22c6c"></a><!-- doxytag: member="ompl::Benchmark::status_" ref="aaa383cc7c3b0bfa7b2987edbfdd22c6c" args="" -->
<a class="el" href="structompl_1_1Benchmark_1_1Status.html">Status</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1Benchmark.html#aaa383cc7c3b0bfa7b2987edbfdd22c6c">status_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The current status of this benchmarking instance. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a1e1c8420d53773e031891de335444ed8"></a><!-- doxytag: member="ompl::Benchmark::preRun_" ref="a1e1c8420d53773e031891de335444ed8" args="" -->
<a class="el" href="classompl_1_1Benchmark.html#ae7070c3ab312a47276e2e45de7742cfa">PreSetupEvent</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1Benchmark.html#a1e1c8420d53773e031891de335444ed8">preRun_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Event to be called before the run of a planner. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ad10b6e89ae578bbcb4fa8bcb6f8fc7dd"></a><!-- doxytag: member="ompl::Benchmark::postRun_" ref="ad10b6e89ae578bbcb4fa8bcb6f8fc7dd" args="" -->
<a class="el" href="classompl_1_1Benchmark.html#ab1a0f51e75e4fc432caad4849bf28026">PostSetupEvent</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1Benchmark.html#ad10b6e89ae578bbcb4fa8bcb6f8fc7dd">postRun_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Event to be called after the run of a planner. <br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a739e8d29b9e507c96b91dfd234786389"></a><!-- doxytag: member="ompl::Benchmark::msg_" ref="a739e8d29b9e507c96b91dfd234786389" args="" -->
<a class="el" href="classompl_1_1msg_1_1Interface.html">msg::Interface</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1Benchmark.html#a739e8d29b9e507c96b91dfd234786389">msg_</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Interface for console output. <br/></td></tr>
</table>
<hr/><a name="details" id="details"></a><h2>Detailed Description</h2>
<div class="textblock"><p><a class="el" href="classompl_1_1Benchmark.html" title="Benchmark a set of planners on a problem instance.">Benchmark</a> a set of planners on a problem instance. </p>

<p>Definition at line <a class="el" href="Benchmark_8h_source.html#l00047">47</a> of file <a class="el" href="Benchmark_8h_source.html">Benchmark.h</a>.</p>
</div><hr/><h2>Member Function Documentation</h2>
<a class="anchor" id="a14e970715817e989b272006274a07876"></a><!-- doxytag: member="ompl::Benchmark::benchmark" ref="a14e970715817e989b272006274a07876" args="(double maxTime, double maxMem, unsigned int runCount, bool displayProgress=false)" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">void ompl::Benchmark::benchmark </td>
          <td>(</td>
          <td class="paramtype">double&#160;</td>
          <td class="paramname"><em>maxTime</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">double&#160;</td>
          <td class="paramname"><em>maxMem</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">unsigned int&#160;</td>
          <td class="paramname"><em>runCount</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">bool&#160;</td>
          <td class="paramname"><em>displayProgress</em> = <code>false</code>&#160;</td>
        </tr>
        <tr>
          <td></td>
          <td>)</td>
          <td></td><td><code> [virtual]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p><a class="el" href="classompl_1_1Benchmark.html" title="Benchmark a set of planners on a problem instance.">Benchmark</a> the added planners on the defined problem. Repeated calls clear previously gathered data. </p>
<dl><dt><b>Parameters:</b></dt><dd>
  <table class="params">
    <tr><td class="paramname">maxTime</td><td>the maximum amount of time a planner is allowed to run (seconds) </td></tr>
    <tr><td class="paramname">maxMem</td><td>the maximum amount of memory a planner is allowed to use (MB) </td></tr>
    <tr><td class="paramname">runCount</td><td>the number of times to run each planner </td></tr>
    <tr><td class="paramname">displayProgress</td><td>flag indicating whether progress is to be displayed or not</td></tr>
  </table>
  </dd>
</dl>
<dl class="note"><dt><b>Note:</b></dt><dd>The values returned for memory consumption may be misleading. Memory allocators often free memory in a lazy fashion, so the returned values for memory consumption indicate the increase in memory usage for each run. Since not all the memory for the previous run was freed, the increase in usage may be close to 0. To get correct averages for memory usage, use <em>runCount</em> = 1 and run the process multiple times. </dd></dl>

<p>Definition at line <a class="el" href="Benchmark_8cpp_source.html#l00262">262</a> of file <a class="el" href="Benchmark_8cpp_source.html">Benchmark.cpp</a>.</p>

</div>
</div>
<hr/>The documentation for this class was generated from the following files:<ul>
<li>src/ompl/tools/benchmark/<a class="el" href="Benchmark_8h_source.html">Benchmark.h</a></li>
<li>src/ompl/tools/benchmark/src/<a class="el" href="Benchmark_8cpp_source.html">Benchmark.cpp</a></li>
</ul>
</div>
<!-- window showing the filter options -->
<div id="MSearchSelectWindow"
     onmouseover="return searchBox.OnSearchSelectShow()"
     onmouseout="return searchBox.OnSearchSelectHide()"
     onkeydown="return searchBox.OnSearchSelectKey(event)">
<a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(0)"><span class="SelectionMark">&#160;</span>All</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(1)"><span class="SelectionMark">&#160;</span>Classes</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(2)"><span class="SelectionMark">&#160;</span>Namespaces</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(3)"><span class="SelectionMark">&#160;</span>Functions</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(4)"><span class="SelectionMark">&#160;</span>Variables</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(5)"><span class="SelectionMark">&#160;</span>Typedefs</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(6)"><span class="SelectionMark">&#160;</span>Enumerations</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(7)"><span class="SelectionMark">&#160;</span>Enumerator</a></div>

<!-- iframe showing the search results (closed by default) -->
<div id="MSearchResultsWindow">
<iframe src="javascript:void(0)" frameborder="0" 
        name="MSearchResults" id="MSearchResults">
</iframe>
</div>

</div>

<div class="footer span-22 push-2 last">
  <a href="http://www.kavrakilab.org">Physical and Biological Computing Group</a> &bull;
  <a href="http://www.cs.rice.edu">Department of Computer Science</a> &bull;
  <a href="http://www.rice.edu">Rice University</a><br>
  <div class="gray">Generated on Sun Oct 9 2011 23:04:41 by&#160;<a href="http://www.doxygen.org/index.html">doxygen</a> 1.7.4</div>
</div>
</div>
</body>
</html>