Loading...
Searching...
No Matches
Benchmark.h
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2010, Rice University
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 Rice University nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Ioan Sucan */
36
37#ifndef OMPL_TOOLS_BENCHMARK_BENCHMARK_
38#define OMPL_TOOLS_BENCHMARK_BENCHMARK_
39
40#include "ompl/geometric/SimpleSetup.h"
41#include "ompl/control/SimpleSetup.h"
42
43namespace ompl
44{
45 namespace tools
46 {
49 {
50 public:
55 struct Status
56 {
58 bool running{false};
59
61 unsigned int activeRun{0};
62
65
67 std::string activePlanner;
68 };
69
72 struct RunProperties : std::map<std::string, std::string>
73 {
74 };
75
76 using RunProgressData = std::vector<std::map<std::string, std::string>>;
77
79 using PreSetupEvent = std::function<void(const base::PlannerPtr &)>;
80
82 using PostSetupEvent = std::function<void(const base::PlannerPtr &, RunProperties &)>;
83
86 {
88 std::string name;
89
91 std::vector<RunProperties> runs;
92
95 std::vector<std::string> progressPropertyNames;
96
99 std::vector<RunProgressData> runsProgressData;
100
103
104 bool operator==(const PlannerExperiment &p) const
105 {
106 return name == p.name && runs == p.runs && common == p.common;
107 }
108 };
109
112 {
114 std::string name;
115
117 std::vector<PlannerExperiment> planners;
118
120 double maxTime;
121
123 double maxMem;
124
126 unsigned int runCount;
127
130
133
135 std::string setupInfo;
136
138 std::uint_fast32_t seed;
139
141 std::string host;
142
144 std::string cpuInfo;
145
147 std::map<std::string, std::string> parameters;
148 };
149
151 struct Request
152 {
154 Request(double maxTime = 5.0, double maxMem = 4096.0, unsigned int runCount = 100,
155 double timeBetweenUpdates = 0.05, bool displayProgress = true, bool saveConsoleOutput = true,
156 bool simplify = true)
158 , maxMem(maxMem)
164 {
165 }
166
168 double maxTime;
169
171 double maxMem;
172
175 unsigned int runCount;
176
180
183
187
190 };
191
194 Benchmark(geometric::SimpleSetup &setup, const std::string &name = std::string());
195
198 Benchmark(control::SimpleSetup &setup, const std::string &name = std::string());
199
200 virtual ~Benchmark() = default;
201
205 void addExperimentParameter(const std::string &name, const std::string &type, const std::string &value);
206
208 const std::map<std::string, std::string> &getExperimentParameters() const;
209
211 std::size_t numExperimentParameters() const;
212
214 void setExperimentName(const std::string &name);
215
217 const std::string &getExperimentName() const;
218
220 void addPlanner(const base::PlannerPtr &planner);
221
224
226 void clearPlanners();
227
229 void setPlannerSwitchEvent(const PreSetupEvent &event);
230
232 void setPreRunEvent(const PreSetupEvent &event);
233
235 void setPostRunEvent(const PostSetupEvent &event);
236
249 virtual void benchmark(const Request &req);
250
253 const Status &getStatus() const;
254
260
262 virtual bool saveResultsToStream(std::ostream &out = std::cout) const;
263
265 bool saveResultsToFile(const char *filename) const;
266
269 bool saveResultsToFile() const;
270
271 protected:
274
277
279 std::vector<base::PlannerPtr> planners_;
280
283
286
289
292
295 };
296 } // namespace tools
297} // namespace ompl
298#endif
Create the set of classes typically needed to solve a control problem.
Definition SimpleSetup.h:63
Create the set of classes typically needed to solve a geometric problem.
Definition SimpleSetup.h:63
PreSetupEvent plannerSwitch_
Event to be called when the evaluated planner is switched.
Definition Benchmark.h:288
std::function< void(const base::PlannerPtr &)> PreSetupEvent
Signature of function that can be called before a planner execution is started.
Definition Benchmark.h:79
Status status_
The current status of this benchmarking instance.
Definition Benchmark.h:285
const std::map< std::string, std::string > & getExperimentParameters() const
Get all optional benchmark parameters. The map key is 'name type'.
virtual void benchmark(const Request &req)
Benchmark the added planners on the defined problem. Repeated calls clear previously gathered data.
const Status & getStatus() const
Get the status of the benchmarking code. This function can be called in a separate thread to check ho...
void clearPlanners()
Clear the set of planners to be benchmarked.
std::vector< base::PlannerPtr > planners_
The set of planners to be tested.
Definition Benchmark.h:279
void setPreRunEvent(const PreSetupEvent &event)
Set the event to be called before the run of a planner.
PostSetupEvent postRun_
Event to be called after the run of a planner.
Definition Benchmark.h:294
const std::string & getExperimentName() const
Get the name of the experiment.
void setExperimentName(const std::string &name)
Set the name of the experiment.
void setPlannerSwitchEvent(const PreSetupEvent &event)
Set the event to be called before any runs of a particular planner (when the planner is switched).
CompleteExperiment exp_
The collected experimental data (for all planners).
Definition Benchmark.h:282
control::SimpleSetup * csetup_
The instance of the problem to benchmark (if planning with controls).
Definition Benchmark.h:276
std::function< void(const base::PlannerPtr &, RunProperties &)> PostSetupEvent
Signature of function that can be called after a planner execution is completed.
Definition Benchmark.h:82
void addPlanner(const base::PlannerPtr &planner)
Add a planner to use.
geometric::SimpleSetup * gsetup_
The instance of the problem to benchmark (if geometric planning).
Definition Benchmark.h:273
void setPostRunEvent(const PostSetupEvent &event)
Set the event to be called after the run of a planner.
void addPlannerAllocator(const base::PlannerAllocator &pa)
Add a planner allocator to use.
std::size_t numExperimentParameters() const
Return the number of optional benchmark parameters.
bool saveResultsToFile() const
Save the results of the benchmark to a file. The name of the file is the current date and time.
virtual bool saveResultsToStream(std::ostream &out=std::cout) const
Save the results of the benchmark to a stream.
const CompleteExperiment & getRecordedExperimentData() const
Return all the experiment data that would be written to the results file. The data should not be chan...
PreSetupEvent preRun_
Event to be called before the run of a planner.
Definition Benchmark.h:291
Benchmark(geometric::SimpleSetup &setup, const std::string &name=std::string())
Constructor needs the SimpleSetup instance needed for planning. Optionally, the experiment name (name...
void addExperimentParameter(const std::string &name, const std::string &type, const std::string &value)
Add an optional parameter's information to the benchmark output. Useful for aggregating results over ...
std::function< PlannerPtr(const SpaceInformationPtr &)> PlannerAllocator
Definition of a function that can allocate a planner.
Definition Planner.h:428
std::chrono::system_clock::time_point point
Representation of a point in time.
Definition Time.h:52
Includes various tools such as self config, benchmarking, etc.
Main namespace. Contains everything in this library.
This structure holds experimental data for a set of planners.
Definition Benchmark.h:112
time::point startTime
The point in time when the experiment was started.
Definition Benchmark.h:129
std::string cpuInfo
Information about the CPU of the machine the benchmark ran on.
Definition Benchmark.h:144
double totalDuration
The amount of time spent to collect the information in this structure (seconds).
Definition Benchmark.h:132
double maxTime
The maximum allowed time for planner computation during the experiment (seconds).
Definition Benchmark.h:120
std::map< std::string, std::string > parameters
Additional, experiment specific parameters. This is optional.
Definition Benchmark.h:147
std::vector< PlannerExperiment > planners
The collected experimental data; each element of the array (an experiment) corresponds to a planner.
Definition Benchmark.h:117
std::uint_fast32_t seed
The random seed that was used at the start of the benchmark program.
Definition Benchmark.h:138
unsigned int runCount
The number of runs to execute for each planner.
Definition Benchmark.h:126
std::string host
Hostname that identifies the machine the benchmark ran on.
Definition Benchmark.h:141
double maxMem
The maximum allowed memory for planner computation during the experiment (MB).
Definition Benchmark.h:123
std::string setupInfo
The output of SimpleSetup::print() before the experiment was started.
Definition Benchmark.h:135
std::string name
The name of the experiment.
Definition Benchmark.h:114
The data collected after running a planner multiple times.
Definition Benchmark.h:86
std::vector< std::string > progressPropertyNames
Definition Benchmark.h:95
std::vector< RunProperties > runs
Data collected for each run.
Definition Benchmark.h:91
RunProperties common
Some common properties for all the runs.
Definition Benchmark.h:102
std::string name
The name of the planner.
Definition Benchmark.h:88
std::vector< RunProgressData > runsProgressData
Definition Benchmark.h:99
Representation of a benchmark request.
Definition Benchmark.h:152
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:175
bool displayProgress
flag indicating whether progress is to be displayed or not; true by default
Definition Benchmark.h:182
double maxMem
the maximum amount of memory a planner is allowed to use (MB); 4096.0 by default
Definition Benchmark.h:171
double timeBetweenUpdates
When collecting time-varying data from a planner during its execution, the planner's progress will be...
Definition Benchmark.h:179
bool saveConsoleOutput
flag indicating whether console output is saved (in an automatically generated filename); true by def...
Definition Benchmark.h:186
Request(double maxTime=5.0, double maxMem=4096.0, unsigned int runCount=100, double timeBetweenUpdates=0.05, bool displayProgress=true, bool saveConsoleOutput=true, bool simplify=true)
Constructor that provides default values for all members.
Definition Benchmark.h:154
double maxTime
the maximum amount of time a planner is allowed to run (seconds); 5.0 by default
Definition Benchmark.h:168
bool simplify
flag indicating whether simplification should be applied to path; true by default
Definition Benchmark.h:189
The data collected from a run of a planner is stored as key-value pairs.
Definition Benchmark.h:73
This structure contains information about the activity of a benchmark instance. If the instance is ru...
Definition Benchmark.h:56
bool running
Flag indicating whether benchmarking is running.
Definition Benchmark.h:58
unsigned int activeRun
The number of the run currently being executed.
Definition Benchmark.h:61
double progressPercentage
Total progress (0 to 100).
Definition Benchmark.h:64
std::string activePlanner
The name of the planner currently being tested.
Definition Benchmark.h:67