38 #include "MultiLevelPlanningCommon.h" 
   39 #include "MultiLevelPlanningHyperCubeCommon.h" 
   40 #include <ompl/base/spaces/RealVectorStateSpace.h> 
   41 #include <ompl/multilevel/datastructures/PlannerMultiLevel.h> 
   43 #include <ompl/tools/benchmark/Benchmark.h> 
   44 #include <ompl/util/String.h> 
   46 #include <ompl/base/Path.h> 
   47 #include <ompl/geometric/PathGeometric.h> 
   49 const double runtime_limit = 60;
 
   50 const double memory_limit = 1024 * 20;  
 
   51 const int run_count = 10;
 
   52 unsigned int curDim = 100;
 
   57 int main(
int argc, 
char **argv)
 
   61         curDim = std::atoi(argv[1]);
 
   64     double range = edgeWidth * 0.5;
 
   65     auto space(std::make_shared<ompl::base::RealVectorStateSpace>(curDim));
 
   74     space->setBounds(bounds);
 
   75     ss.setStateValidityChecker(std::make_shared<HyperCubeValidityChecker>(si, curDim));
 
   76     for (
unsigned int i = 0; i < curDim; ++i)
 
   81     ss.setStartAndGoalStates(start, goal);
 
   84     benchmark.addExperimentParameter(
"num_dims", 
"INTEGER", std::to_string(curDim));
 
   91     std::vector<int> proj = getHypercubeAdmissibleProjection(curDim);
 
   92     addPlanner(benchmark, GetMultiLevelPlanner<QRRT>(proj, si, 
"QRRT"), range);
 
   93     addPlanner(benchmark, GetMultiLevelPlanner<QRRTStar>(proj, si, 
"QRRTStar"), range);
 
   94     addPlanner(benchmark, GetMultiLevelPlanner<QMP>(proj, si, 
"QMP"), range);
 
   95     addPlanner(benchmark, GetMultiLevelPlanner<QMPStar>(proj, si, 
"QMPStar"), range);
 
   98     addPlanner(benchmark, std::make_shared<RRT>(si), range);
 
   99     addPlanner(benchmark, std::make_shared<RRTConnect>(si), range);
 
  100     addPlanner(benchmark, std::make_shared<RRTstar>(si), range);
 
  101     addPlanner(benchmark, std::make_shared<RRTXstatic>(si), range);
 
  102     addPlanner(benchmark, std::make_shared<LazyRRT>(si), range);
 
  104     addPlanner(benchmark, std::make_shared<TRRT>(si), range);
 
  105     addPlanner(benchmark, std::make_shared<BiTRRT>(si), range);
 
  106     addPlanner(benchmark, std::make_shared<LBTRRT>(si), range);
 
  107     addPlanner(benchmark, std::make_shared<RRTsharp>(si), range);
 
  108     addPlanner(benchmark, std::make_shared<InformedRRTstar>(si), range);
 
  110     addPlanner(benchmark, std::make_shared<SORRTstar>(si), range);
 
  111     addPlanner(benchmark, std::make_shared<SBL>(si), range);
 
  113     addPlanner(benchmark, std::make_shared<STRIDE>(si), range);
 
  114     addPlanner(benchmark, std::make_shared<FMT>(si), range);
 
  116     addPlanner(benchmark, std::make_shared<BFMT>(si), range);
 
  117     addPlanner(benchmark, std::make_shared<BITstar>(si), range);
 
  118     addPlanner(benchmark, std::make_shared<ABITstar>(si), range);
 
  119     addPlanner(benchmark, std::make_shared<EST>(si), range);
 
  120     addPlanner(benchmark, std::make_shared<BiEST>(si), range);
 
  122     addPlanner(benchmark, std::make_shared<ProjEST>(si), range);
 
  123     addPlanner(benchmark, std::make_shared<KPIECE1>(si), range);
 
  124     addPlanner(benchmark, std::make_shared<BKPIECE1>(si), range);
 
  125     addPlanner(benchmark, std::make_shared<LBKPIECE1>(si), range);
 
  128     addPlanner(benchmark, std::make_shared<PRM>(si), range);
 
  129     addPlanner(benchmark, std::make_shared<PRMstar>(si), range);
 
  130     addPlanner(benchmark, std::make_shared<LazyPRMstar>(si), range);
 
  131     addPlanner(benchmark, std::make_shared<SPARS>(si), range);
 
  132     addPlanner(benchmark, std::make_shared<SPARStwo>(si), range);
 
  136     printEstimatedTimeToCompletion(numberPlanners, run_count, runtime_limit);
 
  139     request.
maxTime = runtime_limit;
 
  140     request.
maxMem = memory_limit;
 
  144     numberRuns = numberPlanners * run_count;
 
  146     benchmark.setPostRunEvent(std::bind(&PostRunEvent, std::placeholders::_1, std::placeholders::_2));
 
  147     std::cout << 
"Run benchmark" << std::endl;
 
  148     benchmark.benchmark(request);
 
  149     benchmark.saveResultsToFile(boost::str(boost::format(
"hypercube_%i.log") % curDim).c_str());
 
  151     printBenchmarkResults(benchmark);