38 #include <ompl/base/SpaceInformation.h>
39 #include <ompl/tools/benchmark/Benchmark.h>
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>
77 #include <boost/lexical_cast.hpp>
83 std::vector<double> meanTime;
84 std::vector<std::string> plannerName;
85 std::map<double, std::pair<std::string, int>> plannerTimes;
87 for (
unsigned int k = 0; k < experiment.
planners.size(); k++)
90 std::vector<ompl::tools::Benchmark::RunProperties> runs = pk.
runs;
92 unsigned int N = runs.size();
94 double percentSuccess = 0.0;
95 for (
unsigned int j = 0; j < N; j++)
98 double timeJrun = std::atof(run[
"time REAL"].c_str());
99 bool runSolved = std::atoi(run[
"solved BOOLEAN"].c_str());
105 if (timeJrun < experiment.
maxTime)
109 time = time / (double)N;
110 percentSuccess = 100.0 * (percentSuccess / (double)N);
111 pk.
name.erase(0, 10);
113 plannerTimes[time] = std::make_pair(pk.
name, percentSuccess);
116 std::cout <<
"Finished Benchmark (Runtime: " << experiment.
maxTime <<
", RunCount: " << experiment.
runCount <<
")"
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)
123 std::cout <<
"Place <" << ctr <<
"> Time: <" << p.first <<
"> \%Success: <" << p.second.second <<
"> ("
124 << p.second.first <<
")" << std::endl;
127 std::cout << std::string(80,
'-') << std::endl;
130 void printEstimatedTimeToCompletion(
unsigned int numberPlanners,
unsigned int run_count,
unsigned int runtime_limit)
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 : ";
141 if (worst_case_time_estimate_in_hours < 1)
143 if (worst_case_time_estimate_in_minutes < 1)
145 std::cout << worst_case_time_estimate_in_seconds <<
"s" << std::endl;
149 std::cout << worst_case_time_estimate_in_minutes <<
"m" << std::endl;
154 std::cout << worst_case_time_estimate_in_hours <<
"h" << std::endl;
156 std::cout << std::string(80,
'-') << std::endl;
159 static unsigned int numberRuns{0};
163 static unsigned int pid = 0;
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"]);
172 bool solved = boost::lexical_cast<bool>(run[
"solved BOOLEAN"]);
174 double cost = std::numeric_limits<double>::infinity();
175 if (run.find(
"solution length REAL") != run.end())
177 cost = boost::lexical_cast<double>(run[
"solution length REAL"]);
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;
187 int numberPlanners = 0;
192 if (params.
hasParam(std::string(
"range")))
194 benchmark.addPlanner(planner);