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 {
57 Status()
58 {
59 running = false;
60 activeRun = 0;
62 }
63
65 bool running;
66
68 std::string activePlanner;
69
71 unsigned int activeRun;
72
75 };
76
79 using RunProperties = std::map<std::string, std::string>;
80
81 using RunProgressData = std::vector<std::map<std::string, std::string>>;
82
84 using PreSetupEvent = std::function<void(const base::PlannerPtr &)>;
85
87 using PostSetupEvent = std::function<void(const base::PlannerPtr &, RunProperties &)>;
88
91 {
93 std::string name;
94
96 std::vector<RunProperties> runs;
97
100 std::vector<std::string> progressPropertyNames;
101
104 std::vector<RunProgressData> runsProgressData;
105
108
109 bool operator==(const PlannerExperiment &p) const
110 {
111 return name == p.name && runs == p.runs && common == p.common;
112 }
113 };
114
117 {
119 std::string name;
120
122 std::vector<PlannerExperiment> planners;
123
125 double maxTime;
126
128 double maxMem;
129
131 unsigned int runCount;
132
135
138
140 std::string setupInfo;
141
143 std::uint_fast32_t seed;
144
146 std::string host;
147
149 std::string cpuInfo;
150
152 std::map<std::string, std::string> parameters;
153 };
154
156 struct Request
157 {
159 Request(double maxTime = 5.0, double maxMem = 4096.0, unsigned int runCount = 100,
160 double timeBetweenUpdates = 0.05, bool displayProgress = true, bool saveConsoleOutput = true,
161 bool simplify = true)
163 , maxMem(maxMem)
169 {
170 }
171
173 double maxTime;
174
176 double maxMem;
177
180 unsigned int runCount;
181
185
188
192
195 };
196
199 Benchmark(geometric::SimpleSetup &setup, const std::string &name = std::string())
200 : gsetup_(&setup), csetup_(nullptr)
201 {
202 exp_.name = name;
203 }
204
207 Benchmark(control::SimpleSetup &setup, const std::string &name = std::string())
208 : gsetup_(nullptr), csetup_(&setup)
209 {
210 exp_.name = name;
211 }
212
213 virtual ~Benchmark() = default;
214
218 void addExperimentParameter(const std::string &name, const std::string &type, const std::string &value)
219 {
220 exp_.parameters[name + " " + type] = value;
221 }
222
224 const std::map<std::string, std::string> &getExperimentParameters() const
225 {
226 return exp_.parameters;
227 }
228
230 std::size_t numExperimentParameters() const
231 {
232 return exp_.parameters.size();
233 }
234
236 void setExperimentName(const std::string &name)
237 {
238 exp_.name = name;
239 }
240
242 const std::string &getExperimentName() const
243 {
244 return exp_.name;
245 }
246
248 void addPlanner(const base::PlannerPtr &planner)
249 {
250 if (planner &&
251 planner->getSpaceInformation().get() !=
252 (gsetup_ != nullptr ? gsetup_->getSpaceInformation().get() : csetup_->getSpaceInformation().get()))
253 throw Exception("Planner instance does not match space information");
254 planners_.push_back(planner);
255 }
256
259 {
260 planners_.push_back(pa(gsetup_ != nullptr ? gsetup_->getSpaceInformation() : csetup_->getSpaceInformation()));
261 }
262
265 {
266 planners_.clear();
267 }
268
271 {
272 plannerSwitch_ = event;
273 }
274
276 void setPreRunEvent(const PreSetupEvent &event)
277 {
278 preRun_ = event;
279 }
280
283 {
284 postRun_ = event;
285 }
286
299 virtual void benchmark(const Request &req);
300
303 const Status &getStatus() const
304 {
305 return status_;
306 }
307
313 {
314 return exp_;
315 }
316
318 virtual bool saveResultsToStream(std::ostream &out = std::cout) const;
319
321 bool saveResultsToFile(const char *filename) const;
322
325 bool saveResultsToFile() const;
326
327 protected:
330
333
335 std::vector<base::PlannerPtr> planners_;
336
339
342
345
348
351 };
352 }
353}
354#endif
The exception type for ompl.
Definition Exception.h:47
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
Benchmark a set of planners on a problem instance.
Definition Benchmark.h:49
PreSetupEvent plannerSwitch_
Event to be called when the evaluated planner is switched.
Definition Benchmark.h:344
std::function< void(const base::PlannerPtr &)> PreSetupEvent
Signature of function that can be called before a planner execution is started.
Definition Benchmark.h:84
Status status_
The current status of this benchmarking instance.
Definition Benchmark.h:341
const std::map< std::string, std::string > & getExperimentParameters() const
Get all optional benchmark parameters. The map key is 'name type'.
Definition Benchmark.h:224
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...
Definition Benchmark.h:303
void clearPlanners()
Clear the set of planners to be benchmarked.
Definition Benchmark.h:264
std::vector< base::PlannerPtr > planners_
The set of planners to be tested.
Definition Benchmark.h:335
void setPreRunEvent(const PreSetupEvent &event)
Set the event to be called before the run of a planner.
Definition Benchmark.h:276
PostSetupEvent postRun_
Event to be called after the run of a planner.
Definition Benchmark.h:350
const std::string & getExperimentName() const
Get the name of the experiment.
Definition Benchmark.h:242
void setExperimentName(const std::string &name)
Set the name of the experiment.
Definition Benchmark.h:236
void setPlannerSwitchEvent(const PreSetupEvent &event)
Set the event to be called before any runs of a particular planner (when the planner is switched)
Definition Benchmark.h:270
CompleteExperiment exp_
The collected experimental data (for all planners)
Definition Benchmark.h:338
control::SimpleSetup * csetup_
The instance of the problem to benchmark (if planning with controls)
Definition Benchmark.h:332
std::function< void(const base::PlannerPtr &, RunProperties &)> PostSetupEvent
Signature of function that can be called after a planner execution is completed.
Definition Benchmark.h:87
Benchmark(control::SimpleSetup &setup, const std::string &name=std::string())
Constructor needs the SimpleSetup instance needed for planning. Optionally, the experiment name (name...
Definition Benchmark.h:207
void addPlanner(const base::PlannerPtr &planner)
Add a planner to use.
Definition Benchmark.h:248
geometric::SimpleSetup * gsetup_
The instance of the problem to benchmark (if geometric planning)
Definition Benchmark.h:329
void setPostRunEvent(const PostSetupEvent &event)
Set the event to be called after the run of a planner.
Definition Benchmark.h:282
void addPlannerAllocator(const base::PlannerAllocator &pa)
Add a planner allocator to use.
Definition Benchmark.h:258
std::size_t numExperimentParameters() const
Return the number of optional benchmark parameters.
Definition Benchmark.h:230
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.
PreSetupEvent preRun_
Event to be called before the run of a planner.
Definition Benchmark.h:347
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:312
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:79
Benchmark(geometric::SimpleSetup &setup, const std::string &name=std::string())
Constructor needs the SimpleSetup instance needed for planning. Optionally, the experiment name (name...
Definition Benchmark.h:199
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 ...
Definition Benchmark.h:218
std::function< PlannerPtr(const SpaceInformationPtr &)> PlannerAllocator
Definition of a function that can allocate a planner.
Definition Planner.h:437
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:117
time::point startTime
The point in time when the experiment was started.
Definition Benchmark.h:134
std::string cpuInfo
Information about the CPU of the machine the benchmark ran on.
Definition Benchmark.h:149
double totalDuration
The amount of time spent to collect the information in this structure (seconds)
Definition Benchmark.h:137
double maxTime
The maximum allowed time for planner computation during the experiment (seconds)
Definition Benchmark.h:125
std::map< std::string, std::string > parameters
Additional, experiment specific parameters. This is optional.
Definition Benchmark.h:152
std::vector< PlannerExperiment > planners
The collected experimental data; each element of the array (an experiment) corresponds to a planner.
Definition Benchmark.h:122
std::uint_fast32_t seed
The random seed that was used at the start of the benchmark program.
Definition Benchmark.h:143
unsigned int runCount
The number of runs to execute for each planner.
Definition Benchmark.h:131
std::string host
Hostname that identifies the machine the benchmark ran on.
Definition Benchmark.h:146
double maxMem
The maximum allowed memory for planner computation during the experiment (MB)
Definition Benchmark.h:128
std::string setupInfo
The output of SimpleSetup::print() before the experiment was started.
Definition Benchmark.h:140
std::string name
The name of the experiment.
Definition Benchmark.h:119
The data collected after running a planner multiple times.
Definition Benchmark.h:91
std::vector< std::string > progressPropertyNames
Definition Benchmark.h:100
std::vector< RunProperties > runs
Data collected for each run.
Definition Benchmark.h:96
RunProperties common
Some common properties for all the runs.
Definition Benchmark.h:107
std::string name
The name of the planner.
Definition Benchmark.h:93
std::vector< RunProgressData > runsProgressData
Definition Benchmark.h:104
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 timeBetweenUpdates
When collecting time-varying data from a planner during its execution, the planner's progress will be...
Definition Benchmark.h:184
bool saveConsoleOutput
flag indicating whether console output is saved (in an automatically generated filename); true by def...
Definition Benchmark.h:191
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:159
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
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:65
unsigned int activeRun
The number of the run currently being executed.
Definition Benchmark.h:71
double progressPercentage
Total progress (0 to 100)
Definition Benchmark.h:74
std::string activePlanner
The name of the planner currently being tested.
Definition Benchmark.h:68