Loading...
Searching...
No Matches
MultiLevelPlanningHyperCubeBenchmark.cpp
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 "MultiLevelPlanningCommon.h"
39#include "MultiLevelPlanningHyperCubeCommon.h"
40#include <ompl/base/spaces/RealVectorStateSpace.h>
41#include <ompl/multilevel/datastructures/PlannerMultiLevel.h>
42
43#include <ompl/tools/benchmark/Benchmark.h>
44#include <ompl/util/String.h>
45
46#include <ompl/base/Path.h>
47#include <ompl/geometric/PathGeometric.h>
48
49const double runtime_limit = 60;
50const double memory_limit = 1024 * 20; // in MB, but does not consider free operations from prev runs
51const int run_count = 10;
52unsigned int curDim = 100;
53
54using namespace ompl::geometric;
55using namespace ompl::multilevel;
56
57int main(int argc, char **argv)
58{
59 if (argc > 1)
60 {
61 curDim = std::atoi(argv[1]);
62 }
63
64 double range = edgeWidth * 0.5;
65 auto space(std::make_shared<ompl::base::RealVectorStateSpace>(curDim));
66 ompl::base::RealVectorBounds bounds(curDim);
68 ompl::base::SpaceInformationPtr si = ss.getSpaceInformation();
69 ompl::base::ProblemDefinitionPtr pdef = ss.getProblemDefinition();
70 ompl::base::ScopedState<> start(space), goal(space);
71
72 bounds.setLow(0.);
73 bounds.setHigh(1.);
74 space->setBounds(bounds);
75 ss.setStateValidityChecker(std::make_shared<HyperCubeValidityChecker>(si, curDim));
76 for (unsigned int i = 0; i < curDim; ++i)
77 {
78 start[i] = 0.;
79 goal[i] = 1.;
80 }
81 ss.setStartAndGoalStates(start, goal);
82
83 ompl::tools::Benchmark benchmark(ss, "HyperCube");
84 benchmark.addExperimentParameter("num_dims", "INTEGER", std::to_string(curDim));
85
86 //############################################################################
87 // Load All Planner
88 //############################################################################
89
90 // MultiLevel Planner
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);
96
97 // Classical Planner
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);
103
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);
109
110 addPlanner(benchmark, std::make_shared<SORRTstar>(si), range);
111 addPlanner(benchmark, std::make_shared<SBL>(si), range);
112 // addPlanner(benchmark, std::make_shared<SST>(si), range); //out of memory
113 addPlanner(benchmark, std::make_shared<STRIDE>(si), range);
114 addPlanner(benchmark, std::make_shared<FMT>(si), range);
115
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);
121
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);
126 // addPlanner(benchmark, std::make_shared<PDST>(si), range); //OOM
127
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);
133
134 //############################################################################
135
136 printEstimatedTimeToCompletion(numberPlanners, run_count, runtime_limit);
137
139 request.maxTime = runtime_limit;
140 request.maxMem = memory_limit;
141 request.runCount = run_count;
142 request.simplify = false;
143 request.displayProgress = false;
144 numberRuns = numberPlanners * run_count;
145
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());
150
151 printBenchmarkResults(benchmark);
152
153 return 0;
154}
A shared pointer wrapper for ompl::base::ProblemDefinition.
The lower and upper bounds for an Rn space.
Definition of a scoped state.
Definition ScopedState.h:57
A shared pointer wrapper for ompl::base::SpaceInformation.
Create the set of classes typically needed to solve a geometric problem.
Definition SimpleSetup.h:63
Benchmark a set of planners on a problem instance.
Definition Benchmark.h:49
This namespace contains code that is specific to planning under geometric constraints.
This namespace contains datastructures and planners to exploit multilevel abstractions,...
Representation of a benchmark request.
Definition Benchmark.h:157
unsigned int runCount
the number of times to run each planner; 100 by default If set to 0, then run each planner as many ti...
Definition Benchmark.h:180
bool displayProgress
flag indicating whether progress is to be displayed or not; true by default
Definition Benchmark.h:187
double maxMem
the maximum amount of memory a planner is allowed to use (MB); 4096.0 by default
Definition Benchmark.h:176
double maxTime
the maximum amount of time a planner is allowed to run (seconds); 5.0 by default
Definition Benchmark.h:173
bool simplify
flag indicating whether simplification should be applied to path; true by default
Definition Benchmark.h:194