Sophie

Sophie

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

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: How to benchmark planners</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>
<div class="header">
  <div class="headertitle">
<div class="title">How to benchmark planners </div>  </div>
</div>
<div class="contents">
<div class="textblock"><ul>
<li><a class="el" href="benchmark.html#benchmark_code">Writing Benchmarking Code</a></li>
<li><a class="el" href="benchmark.html#benchmark_log">Processing the benchmarking log file</a></li>
<li><a class="el" href="benchmark.html#benchmark_sample_results">Sample benchmark results</a></li>
</ul>
<h2><a class="anchor" id="benchmark_code"></a>
Writing Benchmarking Code</h2>
<p>Benchmarking a set of planners on a specified problem is a simple task in OMPL. The steps involved are as follows:</p>
<ul>
<li>Configure the benchmark problem using <a class="el" href="classompl_1_1geometric_1_1SimpleSetup.html" title="Create the set of classes typically needed to solve a geometric problem.">ompl::geometric::SimpleSetup</a> or <a class="el" href="classompl_1_1control_1_1SimpleSetup.html" title="Create the set of classes typically needed to solve a control problem.">ompl::control::SimpleSetup</a></li>
<li>Create a <a class="el" href="classompl_1_1Benchmark.html" title="Benchmark a set of planners on a problem instance.">ompl::Benchmark</a> object that takes the problem as input</li>
<li>Add one or more planners to the benchmark</li>
<li>Optionally add events to be called before and/or after the execution of a planner</li>
<li>Run the benchmark problem a specified number of times, subject to specified time and memory limits</li>
</ul>
<p>The following code snippet shows you how to do this. We will start with some initial code that you have probably already used: </p>
<div class="fragment"><pre class="fragment"><span class="preprocessor">    #include &quot;ompl/tools/benchmark/Benchmark.h&quot;</span>

    <span class="comment">// A function that matches the ompl::base::PlannerAllocator type.</span>
    <span class="comment">// It will be used later to allocate an instance of EST</span>
    <a class="code" href="classompl_1_1base_1_1PlannerPtr.html" title="A boost shared pointer wrapper for ompl::base::Planner.">ompl::base::PlannerPtr</a> myConfiguredPlanner(<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.">ompl::base::SpaceInformationPtr</a> &amp;si)
    {
        geometric::EST *est = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1EST.html" title="Expansive Space Trees.">ompl::geometric::EST</a>(si);
        est-&gt;setRange(100.0);
        <span class="keywordflow">return</span> <a class="code" href="classompl_1_1base_1_1PlannerPtr.html" title="A boost shared pointer wrapper for ompl::base::Planner.">ompl::base::PlannerPtr</a>(est);
    }

    <span class="comment">// Create a state space for the space we are planning in</span>
    <a class="code" href="classompl_1_1geometric_1_1SimpleSetup.html" title="Create the set of classes typically needed to solve a geometric problem.">ompl::geometric::SimpleSetup</a> ss(space);

    <span class="comment">// Configure the problem to solve: set start state(s)</span>
    <span class="comment">// and goal representation</span>
    <span class="comment">// Everything must be set up to the point ss.solve()</span>
    <span class="comment">// can be called. Setting up a planner is not needed.</span>
</pre></div><p>Benchmarking code starts here: </p>
<div class="fragment"><pre class="fragment">    <span class="comment">// First we create a benchmark class:</span>
    <a class="code" href="classompl_1_1Benchmark.html" title="Benchmark a set of planners on a problem instance.">ompl::Benchmark</a> b(ss, <span class="stringliteral">&quot;my experiment&quot;</span>);

    <span class="comment">// We add the planners to evaluate.</span>
    b.addPlanner(base::PlannerPtr(<span class="keyword">new</span> geometric::KPIECE1(ss.getSpaceInformation())));
    b.addPlanner(base::PlannerPtr(<span class="keyword">new</span> geometric::RRT(ss.getSpaceInformation())));
    b.addPlanner(base::PlannerPtr(<span class="keyword">new</span> geometric::SBL(ss.getSpaceInformation())));
    b.addPlanner(base::PlannerPtr(<span class="keyword">new</span> geometric::LBKPIECE1(ss.getSpaceInformation())));
    <span class="comment">// etc</span>

    <span class="comment">// For planners that we want to configure in specific ways,</span>
    <span class="comment">// the ompl::base::PlannerAllocator should be used:</span>
    b.addPlannerAllocator(boost::bind(&amp;myConfiguredPlanner, _1));
    <span class="comment">// etc.</span>

    <span class="comment">// Now we can benchmark: 5 second time limit for each plan computation,</span>
    <span class="comment">// 100 MB maximum memory usage per plan computation, 50 runs for each planner</span>
    <span class="comment">// and true means that a text-mode progress bar should be displayed while</span>
    <span class="comment">// computation is running.</span>
    b.benchmark(5., 100., 50, <span class="keyword">true</span>);

    <span class="comment">// This will generate a file of the form ompl_host_time.log</span>
    b.saveResultsToFile();
</pre></div><p> Adding callbacks for before and after the execution of a run is also possible: </p>
<div class="fragment"><pre class="fragment">    <span class="comment">// Assume these functions are defined</span>
    <span class="keywordtype">void</span> optionalPreRunEvent(<span class="keyword">const</span> base::PlannerPtr &amp;planner)
    {
       <span class="comment">// do whatever configuration we want to the planner,</span>
       <span class="comment">// including changing of problem definition (input states)</span>
       <span class="comment">// via planner-&gt;getProblemDefinition()</span>
    }
    
    <span class="keywordtype">void</span> optionalPostRunEvent(<span class="keyword">const</span> base::PlannerPtr &amp;planner, Benchmark::RunProperties &amp;run)
    {
       <span class="comment">// do any cleanup, or set values for upcoming run (or upcoming call to the pre-run event).</span>

       <span class="comment">// adding elements to the set of collected run properties is also possible;</span>
       <span class="comment">// (the added data will be recorded in the log file)</span>

       run[<span class="stringliteral">&quot;some extra property name INTEGER&quot;</span>] = <span class="stringliteral">&quot;some value&quot;</span>;
       <span class="comment">// The format of added data is string key, string value pairs, </span>
       <span class="comment">// with the convention that the last word in string key is one of</span>
       <span class="comment">// REAL, INTEGER, BOOLEAN, STRING. (this will be the type of the field </span>
       <span class="comment">// when the log file is processed and saved as a database).</span>
       <span class="comment">// The values are always converted to string.</span>
    }

    <span class="comment">// After the Benchmark class is defined, the events can be optionally registered:</span>
    b.setPreRunEvent(boost::bind(&amp;optionalPreRunEvent, _1));
    b.setPostRunEvent(boost::bind(&amp;optionalPostRunEvent, _1, _2));
</pre></div><h2><a class="anchor" id="benchmark_log"></a>
Processing the benchmarking log file</h2>
<p>Once the C++ code computing the results has been executed, a log file is generated. This contains information about the settings of the planners, the parameters of the problem tested on, etc. To visualize this information, we provide a script that parses the log files: </p>
<div class="fragment"><pre class="fragment">    scripts/benchmark_statistics.py logfile.log -d mydatabase.db
</pre></div><p> This will generate a SQLite database containing the parsed data. If no database name is specified, the named is assumed to be benchmark.db Once this database is generated, we can construct plots: </p>
<div class="fragment"><pre class="fragment">    scripts/benchmark_statistics.py -d mydatabase.db -p boxplot.pdf
</pre></div><p> This will generate a series of plots, one for each of the attributes described below, showing the results for each planner. <a class="el" href="benchmark.html#benchmark_sample_results">Below</a> we have included some sample benchmark results.</p>
<p>If you would like to process the data in different ways, you can generate a dump file that you can load in a MySQL database: </p>
<div class="fragment"><pre class="fragment">    scripts/benchmark_statistics.py -d mydatabase.db -m mydump.sql
</pre></div><p> The database will contain 2+<em>k</em> tables:</p>
<ul>
<li><em>planners</em> is a table that contains planner configurations</li>
<li><em>experiments</em> is a table that contains details about conducted experiments</li>
<li><em>k</em> tables named <em>planner_&lt;name&gt;</em>, one for each planner, containing measurements</li>
</ul>
<p>For more details on how to use the benchmark script, see: </p>
<div class="fragment"><pre class="fragment">    scripts/benchmark_statistics.py --help
</pre></div><p>Collected benchmark data for each experiment:</p>
<ul>
<li><b>name:</b> name of experiment (optional)</li>
<li><b>totaltime:</b> the total duration for conducting the experiment (seconds)</li>
<li><b>timelimit:</b> the maximum time allowed for every planner execution (seconds)</li>
<li><b>memorylimit:</b> the maximum memory allowed for every planner execution (MB)</li>
<li><b>hostname:</b> the name of the host on which the experiment was run</li>
<li><b>date:</b> the date and time when the experiment was started</li>
</ul>
<p>Collected benchmark data for each planner execution:</p>
<ul>
<li><b>time:</b> (real) the amount of time spent planning, in seconds</li>
<li><b>memory:</b> (real) the amount of memory spent planning, in MB. Note: this may be inaccurate since memory is often freed in a lazy fashion</li>
<li><b>solved:</b> (boolean) flag indicating whether the planner found a solution. Note: the solution can be approximate</li>
<li><b>approximate solution:</b> (boolean) flag indicating whether the found solution is approximate (does not reach the goal, but moves towards it)</li>
<li><b>solution difference:</b> (real) if the solution is approximate, this is the distance from the end-point of the found approximate solution to the actual goal</li>
<li><b>solution length:</b> (real) the length of the found solution</li>
<li><b>solution smoothness:</b> (real) the smoothness of the found solution (the closer to 0, the smoother the path is)</li>
<li><b>solution clearance:</b> (real) the clearance of the found solution (the higher the value, the larger the distance to invalid regions)</li>
<li><b>solution segments:</b> (integer) the number of segments on the solution path</li>
<li><b>correct solution:</b> (boolean) flag indicating whether the found solution is correct (a separate check is conducted). This should always be true.</li>
<li><b>correct solution strict:</b> (boolean) flag indicating whether the found solution is correct when checked at a finer resolution than the planner used when validating motion segments. If this is sometimes false it means that the used state validation resolution is too high (only applies when using <a class="el" 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...">ompl::base::DiscreteMotionValidator</a>).</li>
<li><b>simplification time:</b> (real) the time spend simplifying the solution path, in seconds</li>
<li><b>simplified solution length:</b> (real) the length of the found solution after simplification</li>
<li><b>simplified solution smoothness:</b> (real) the smoothness of the found solution after simplification (the closer to 0, the smoother the path is)</li>
<li><b>simplified solution clearance:</b> (real) the clearance of the found solution after simplification (the higher the value, the larger the distance to invalid regions)</li>
<li><b>simplified solution segments:</b> (integer) the number of segments on solution path after simplification</li>
<li><b>simplified correct solution:</b> (boolean) flag indicating whether the found solution is correct after simplification. This should always be true.</li>
<li><b>simplified correct solution strict:</b> (boolean) flag indicating whether the found solution is correct after simplification, when checked at a finer resolution.</li>
<li><b>graph states:</b> (integer) the number of states in the constructed graph</li>
<li><b>graph motions:</b> (integer) the number of edges (motions) in the constructed graph</li>
<li><b>valid segment fraction:</b> (real) the fraction of segments that turned out to be valid (using <a class="el" href="classompl_1_1base_1_1MotionValidator.html" title="Abstract definition for a class checking the validity of motions -- path segments between states...">ompl::base::MotionValidator</a>) out of all the segments that were checked for validity</li>
<li>more planner-specific properties</li>
</ul>
<h2><a class="anchor" id="benchmark_sample_results"></a>
Sample benchmark results</h2>
<p>Below are sample results for running benchmarks for two example problems: the “cubicles” environment and the “Twistycool” environment. The complete benchmarking program (SE3RigidBodyPlanningBenchmark.cpp), the environment and robot files are included with OMPL.app, so you can rerun the exact same benchmarks on your own machine. See the <a class="el" href="gallery.html#gallery_omplapp">gallery</a> for visualizations of sample solutions to both problems. The results below were run on a recent model Apple MacBook Pro (2.66 GHz Intel Core i7, 8GB of RAM). It is important to note that none of the planner parameters were tuned; all benchmarks were run with default settings. From these results one cannot draw any firm conclusions about which planner is “better” than some other planner.</p>
<p>These are the PDF files with plots as generated by the benchmark_statistics.py script:</p>
<ul>
<li><a href="../images/cubicles.pdf">The “cubicles” problem with default settings</a></li>
<li><a href="../images/Twistycool.pdf">The “Twistycool” problem with default settings</a></li>
</ul>
<p>The plots show comparisons between <a class="el" href="classompl_1_1geometric_1_1RRTConnect.html" title="RRT-Connect (RRTConnect)">ompl::geometric::RRTConnect</a>, <a class="el" href="classompl_1_1geometric_1_1RRT.html" title="Rapidly-exploring Random Trees.">ompl::geometric::RRT</a>, <a class="el" href="classompl_1_1geometric_1_1LazyRRT.html" title="Lazy RRT.">ompl::geometric::LazyRRT</a>, <a class="el" href="classompl_1_1geometric_1_1LBKPIECE1.html" title="Lazy Bi-directional KPIECE with one level of discretization.">ompl::geometric::LBKPIECE1</a>, <a class="el" href="classompl_1_1geometric_1_1KPIECE1.html" title="Kinematic Planning by Interior-Exterior Cell Exploration.">ompl::geometric::KPIECE1</a>, <a class="el" href="classompl_1_1geometric_1_1SBL.html" title="Single-Query Bi-Directional Probabilistic Roadmap Planner with Lazy Collision Checking.">ompl::geometric::SBL</a>, <a class="el" href="classompl_1_1geometric_1_1EST.html" title="Expansive Space Trees.">ompl::geometric::EST</a>, and <a class="el" href="classompl_1_1geometric_1_1PRM.html" title="Probabilistic RoadMap planner.">ompl::geometric::PRM</a>. Each planner is run 500 times with a 10 second time limit for the cubicles problem for each sampling strategy, while for the Twistycool problem each planner is run 50 times with a 90 second time limit.</p>
<p>For integer and real-valued measurements the script will compute <a href="http://en.wikipedia.org/wiki/Box_plot">box plots</a>. For example, here is the plot for the real-valued attribute <b>time</b> for the cubicles environment:</p>
 <div class="span-22"><img src="../images/cubicles_time.png" class="push-2 span-12 last"></div><p>For boolean measurements the script will create bar charts with the percentage of <b>true</b> values. For example, here is the plot for the boolean attribute <b>solved</b> for the Twistycool environment, a much harder problem:</p>
 <div class="span-22"><img src="../images/Twistycool_solved.png" class="push-2 span-12 last"></div><p>Whenever measurements are not always available for a particular attribute, the columns for each planner are labeled with the number of runs for which no data was available. For instance, the boolean attribute <b>correct solution</b> is not set if a solution is not found. </p>
</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:41 by&#160;<a href="http://www.doxygen.org/index.html">doxygen</a> 1.7.4</div>
</div>
</div>
</body>
</html>