MultiLevelPlanningCommon.h
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2019, University of Stuttgart
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the University of Stuttgart nor the names
18  * of its contributors may be used to endorse or promote products
19  * derived from this software without specific prior written
20  * permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 /* Author: Andreas Orthey */
37 
38 #include <ompl/base/SpaceInformation.h>
39 #include <ompl/tools/benchmark/Benchmark.h>
40 
41 // include planners
42 #include <ompl/geometric/planners/informedtrees/BITstar.h>
43 #include <ompl/geometric/planners/informedtrees/ABITstar.h>
44 #include <ompl/geometric/planners/est/BiEST.h>
45 #include <ompl/geometric/planners/est/EST.h>
46 #include <ompl/geometric/planners/est/ProjEST.h>
47 #include <ompl/geometric/planners/fmt/BFMT.h>
48 #include <ompl/geometric/planners/fmt/FMT.h>
49 #include <ompl/geometric/planners/kpiece/BKPIECE1.h>
50 #include <ompl/geometric/planners/kpiece/KPIECE1.h>
51 #include <ompl/geometric/planners/kpiece/LBKPIECE1.h>
52 #include <ompl/geometric/planners/pdst/PDST.h>
53 #include <ompl/geometric/planners/prm/LazyPRMstar.h>
54 #include <ompl/geometric/planners/prm/PRM.h>
55 #include <ompl/geometric/planners/prm/PRMstar.h>
56 #include <ompl/geometric/planners/prm/SPARS.h>
57 #include <ompl/geometric/planners/prm/SPARStwo.h>
58 #include <ompl/multilevel/planners/qrrt/QRRT.h>
59 #include <ompl/multilevel/planners/qrrt/QRRTStar.h>
60 #include <ompl/multilevel/planners/qmp/QMP.h>
61 #include <ompl/multilevel/planners/qmp/QMPStar.h>
62 #include <ompl/geometric/planners/rrt/BiTRRT.h>
63 #include <ompl/geometric/planners/rrt/InformedRRTstar.h>
64 #include <ompl/geometric/planners/rrt/LazyRRT.h>
65 #include <ompl/geometric/planners/rrt/LBTRRT.h>
66 #include <ompl/geometric/planners/rrt/RRTConnect.h>
67 #include <ompl/geometric/planners/rrt/RRT.h>
68 #include <ompl/geometric/planners/rrt/RRTsharp.h>
69 #include <ompl/geometric/planners/rrt/RRTstar.h>
70 #include <ompl/geometric/planners/rrt/RRTXstatic.h>
71 #include <ompl/geometric/planners/rrt/SORRTstar.h>
72 #include <ompl/geometric/planners/rrt/TRRT.h>
73 #include <ompl/geometric/planners/sbl/SBL.h>
74 #include <ompl/geometric/planners/sst/SST.h>
75 #include <ompl/geometric/planners/stride/STRIDE.h>
76 
77 #include <boost/lexical_cast.hpp>
78 
79 void printBenchmarkResults(const ompl::tools::Benchmark &b)
80 {
82 
83  std::vector<double> meanTime;
84  std::vector<std::string> plannerName;
85  std::map<double, std::pair<std::string, int>> plannerTimes;
86 
87  for (unsigned int k = 0; k < experiment.planners.size(); k++)
88  {
90  std::vector<ompl::tools::Benchmark::RunProperties> runs = pk.runs;
91 
92  unsigned int N = runs.size();
93  double time = 0;
94  double percentSuccess = 0.0;
95  for (unsigned int j = 0; j < N; j++)
96  {
98  double timeJrun = std::atof(run["time REAL"].c_str());
99  bool runSolved = std::atoi(run["solved BOOLEAN"].c_str());
100 
101  if (!runSolved)
102  timeJrun = experiment.maxTime;
103 
104  time += timeJrun;
105  if (timeJrun < experiment.maxTime)
106  percentSuccess++;
107  }
108 
109  time = time / (double)N;
110  percentSuccess = 100.0 * (percentSuccess / (double)N);
111  pk.name.erase(0, 10);
112 
113  plannerTimes[time] = std::make_pair(pk.name, percentSuccess);
114  }
115 
116  std::cout << "Finished Benchmark (Runtime: " << experiment.maxTime << ", RunCount: " << experiment.runCount << ")"
117  << std::endl;
118  std::cout << "Placement <Rank> <Time (in Seconds)> <Success (in Percentage)>" << std::endl;
119  unsigned int ctr = 1;
120  std::cout << std::string(80, '-') << std::endl;
121  for (auto const &p : plannerTimes)
122  {
123  std::cout << "Place <" << ctr << "> Time: <" << p.first << "> \%Success: <" << p.second.second << "> ("
124  << p.second.first << ")" << std::endl;
125  ctr++;
126  }
127  std::cout << std::string(80, '-') << std::endl;
128 }
129 
130 void printEstimatedTimeToCompletion(unsigned int numberPlanners, unsigned int run_count, unsigned int runtime_limit)
131 {
132  std::cout << std::string(80, '-') << std::endl;
133  double worst_case_time_estimate_in_seconds = numberPlanners * run_count * runtime_limit;
134  double worst_case_time_estimate_in_minutes = worst_case_time_estimate_in_seconds / 60.0;
135  double worst_case_time_estimate_in_hours = worst_case_time_estimate_in_minutes / 60.0;
136  std::cout << "Number of Planners : " << numberPlanners << std::endl;
137  std::cout << "Number of Runs Per Planner : " << run_count << std::endl;
138  std::cout << "Time Per Run (s) : " << runtime_limit << std::endl;
139  std::cout << "Worst-case time requirement : ";
140 
141  if (worst_case_time_estimate_in_hours < 1)
142  {
143  if (worst_case_time_estimate_in_minutes < 1)
144  {
145  std::cout << worst_case_time_estimate_in_seconds << "s" << std::endl;
146  }
147  else
148  {
149  std::cout << worst_case_time_estimate_in_minutes << "m" << std::endl;
150  }
151  }
152  else
153  {
154  std::cout << worst_case_time_estimate_in_hours << "h" << std::endl;
155  }
156  std::cout << std::string(80, '-') << std::endl;
157 }
158 
159 static unsigned int numberRuns{0};
160 
161 void PostRunEvent(const ompl::base::PlannerPtr &planner, ompl::tools::Benchmark::RunProperties &run)
162 {
163  static unsigned int pid = 0;
164 
165  ompl::base::SpaceInformationPtr si = planner->getSpaceInformation();
166  ompl::base::ProblemDefinitionPtr pdef = planner->getProblemDefinition();
167 
168  unsigned int states = boost::lexical_cast<int>(run["graph states INTEGER"]);
169  double time = boost::lexical_cast<double>(run["time REAL"]);
170  double memory = boost::lexical_cast<double>(run["memory REAL"]);
171 
172  bool solved = boost::lexical_cast<bool>(run["solved BOOLEAN"]);
173 
174  double cost = std::numeric_limits<double>::infinity();
175  if (run.find("solution length REAL") != run.end())
176  {
177  cost = boost::lexical_cast<double>(run["solution length REAL"]);
178  }
179 
180  std::cout << "Run " << pid << "/" << numberRuns << " [" << planner->getName() << "] "
181  << (solved ? "solved" : "FAILED") << "(time: " << time << ", cost: " << cost << ", states: " << states
182  << ", memory: " << memory << ")" << std::endl;
183  std::cout << std::string(80, '-') << std::endl;
184  pid++;
185 }
186 
187 int numberPlanners = 0;
188 
189 void addPlanner(ompl::tools::Benchmark &benchmark, const ompl::base::PlannerPtr &planner, double range = 1e-2)
190 {
191  ompl::base::ParamSet &params = planner->params();
192  if (params.hasParam(std::string("range")))
193  params.setParam(std::string("range"), ompl::toString(range));
194  benchmark.addPlanner(planner);
195  numberPlanners++;
196 }
bool setParam(const std::string &key, const std::string &value)
Algorithms in OMPL often have parameters that can be set externally. While each algorithm will have t...
bool hasParam(const std::string &key) const
Check whether this set of parameters includes the parameter named key.
Maintain a set of parameters.
Definition: GenericParam.h:289
A shared pointer wrapper for ompl::base::SpaceInformation.
double maxTime
The maximum allowed time for planner computation during the experiment (seconds)
Definition: Benchmark.h:221
The data collected after running a planner multiple times.
Definition: Benchmark.h:186
unsigned int runCount
The number of runs to execute for each planner.
Definition: Benchmark.h:227
This structure holds experimental data for a set of planners.
Definition: Benchmark.h:212
A shared pointer wrapper for ompl::base::Planner.
const CompleteExperiment & getRecordedExperimentData() const
Return all the experiment data that would be written to the results file. The data should not be chan...
Definition: Benchmark.h:408
std::vector< RunProperties > runs
Data collected for each run.
Definition: Benchmark.h:192
A shared pointer wrapper for ompl::base::ProblemDefinition.
Benchmark a set of planners on a problem instance.
Definition: Benchmark.h:112
std::vector< PlannerExperiment > planners
The collected experimental data; each element of the array (an experiment) corresponds to a planner.
Definition: Benchmark.h:218
std::string name
The name of the planner.
Definition: Benchmark.h:189
std::string toString(float val)
convert float to string using classic "C" locale semantics
Definition: String.cpp:82
std::map< std::string, std::string > RunProperties
The data collected from a run of a planner is stored as key-value pairs.
Definition: Benchmark.h:175