Benchmark a set of planners on a problem instance. More...
#include <ompl/tools/benchmark/Benchmark.h>
Classes | |
struct | CompleteExperiment |
This structure holds experimental data for a set of planners. More... | |
struct | PlannerExperiment |
The data collected after running a planner multiple times. More... | |
struct | Request |
Representation of a benchmark request. More... | |
struct | Status |
This structure contains information about the activity of a benchmark instance. If the instance is running, it is possible to find out information such as which planner is currently being tested or how much. More... | |
Public Types | |
using | RunProperties = std::map< std::string, std::string > |
The data collected from a run of a planner is stored as key-value pairs. More... | |
using | RunProgressData = std::vector< std::map< std::string, std::string > > |
using | PreSetupEvent = std::function< void(const base::PlannerPtr &)> |
Signature of function that can be called before a planner execution is started. More... | |
using | PostSetupEvent = std::function< void(const base::PlannerPtr &, RunProperties &)> |
Signature of function that can be called after a planner execution is completed. More... | |
Public Member Functions | |
Benchmark (geometric::SimpleSetup &setup, const std::string &name=std::string()) | |
Constructor needs the SimpleSetup instance needed for planning. Optionally, the experiment name (name) can be specified. More... | |
Benchmark (control::SimpleSetup &setup, const std::string &name=std::string()) | |
Constructor needs the SimpleSetup instance needed for planning. Optionally, the experiment name (name) can be specified. More... | |
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 different benchmark instances, e.g., parameter sweep. type is typically "BOOLEAN", "INTEGER", or "REAL". More... | |
const std::map< std::string, std::string > & | getExperimentParameters () const |
Get all optional benchmark parameters. The map key is 'name type' More... | |
std::size_t | numExperimentParameters () const |
Return the number of optional benchmark parameters. More... | |
void | setExperimentName (const std::string &name) |
Set the name of the experiment. More... | |
const std::string & | getExperimentName () const |
Get the name of the experiment. More... | |
void | addPlanner (const base::PlannerPtr &planner) |
Add a planner to use. More... | |
void | addPlannerAllocator (const base::PlannerAllocator &pa) |
Add a planner allocator to use. More... | |
void | clearPlanners () |
Clear the set of planners to be benchmarked. More... | |
void | setPlannerSwitchEvent (const PreSetupEvent &event) |
Set the event to be called before any runs of a particular planner (when the planner is switched) More... | |
void | setPreRunEvent (const PreSetupEvent &event) |
Set the event to be called before the run of a planner. More... | |
void | setPostRunEvent (const PostSetupEvent &event) |
Set the event to be called after the run of a planner. More... | |
virtual void | benchmark (const Request &req) |
Benchmark the added planners on the defined problem. Repeated calls clear previously gathered data. More... | |
const Status & | getStatus () const |
Get the status of the benchmarking code. This function can be called in a separate thread to check how much progress has been made. More... | |
const CompleteExperiment & | getRecordedExperimentData () const |
Return all the experiment data that would be written to the results file. The data should not be changed, but it could be useful to quickly extract cartain statistics. More... | |
virtual bool | saveResultsToStream (std::ostream &out=std::cout) const |
Save the results of the benchmark to a stream. More... | |
bool | saveResultsToFile (const char *filename) const |
Save the results of the benchmark to a file. More... | |
bool | saveResultsToFile () const |
Save the results of the benchmark to a file. The name of the file is the current date and time. More... | |
Protected Attributes | |
geometric::SimpleSetup * | gsetup_ |
The instance of the problem to benchmark (if geometric planning) More... | |
control::SimpleSetup * | csetup_ |
The instance of the problem to benchmark (if planning with controls) More... | |
std::vector< base::PlannerPtr > | planners_ |
The set of planners to be tested. More... | |
CompleteExperiment | exp_ |
The collected experimental data (for all planners) More... | |
Status | status_ |
The current status of this benchmarking instance. More... | |
PreSetupEvent | plannerSwitch_ |
Event to be called when the evaluated planner is switched. More... | |
PreSetupEvent | preRun_ |
Event to be called before the run of a planner. More... | |
PostSetupEvent | postRun_ |
Event to be called after the run of a planner. More... | |
Detailed Description
Benchmark a set of planners on a problem instance.
Definition at line 48 of file Benchmark.h.
Member Typedef Documentation
◆ PostSetupEvent
using ompl::tools::Benchmark::PostSetupEvent = std::function<void(const base::PlannerPtr &, RunProperties &)> |
Signature of function that can be called after a planner execution is completed.
Definition at line 87 of file Benchmark.h.
◆ PreSetupEvent
using ompl::tools::Benchmark::PreSetupEvent = std::function<void(const base::PlannerPtr &)> |
Signature of function that can be called before a planner execution is started.
Definition at line 84 of file Benchmark.h.
◆ RunProgressData
using ompl::tools::Benchmark::RunProgressData = std::vector<std::map<std::string, std::string> > |
Definition at line 81 of file Benchmark.h.
◆ RunProperties
using ompl::tools::Benchmark::RunProperties = std::map<std::string, std::string> |
The data collected from a run of a planner is stored as key-value pairs.
Definition at line 79 of file Benchmark.h.
Constructor & Destructor Documentation
◆ Benchmark() [1/2]
|
inline |
Constructor needs the SimpleSetup instance needed for planning. Optionally, the experiment name (name) can be specified.
Definition at line 199 of file Benchmark.h.
◆ Benchmark() [2/2]
|
inline |
Constructor needs the SimpleSetup instance needed for planning. Optionally, the experiment name (name) can be specified.
Definition at line 207 of file Benchmark.h.
Member Function Documentation
◆ addExperimentParameter()
|
inline |
Add an optional parameter's information to the benchmark output. Useful for aggregating results over different benchmark instances, e.g., parameter sweep. type is typically "BOOLEAN", "INTEGER", or "REAL".
Definition at line 218 of file Benchmark.h.
◆ addPlanner()
|
inline |
Add a planner to use.
Definition at line 248 of file Benchmark.h.
◆ addPlannerAllocator()
|
inline |
Add a planner allocator to use.
Definition at line 258 of file Benchmark.h.
◆ benchmark()
|
virtual |
Benchmark the added planners on the defined problem. Repeated calls clear previously gathered data.
- Parameters
-
req The parameters for the execution of the benchmark
- Note
- The values returned for memory consumption may be misleading. Memory allocators often free memory in a lazy fashion, so the returned values for memory consumption indicate the increase in memory usage for each run. Since not all the memory for the previous run was freed, the increase in usage may be close to 0. To get correct averages for memory usage, use req.runCount = 1 and run the process multiple times.
Definition at line 353 of file Benchmark.cpp.
◆ clearPlanners()
|
inline |
Clear the set of planners to be benchmarked.
Definition at line 264 of file Benchmark.h.
◆ getExperimentName()
|
inline |
Get the name of the experiment.
Definition at line 242 of file Benchmark.h.
◆ getExperimentParameters()
|
inline |
Get all optional benchmark parameters. The map key is 'name type'
Definition at line 224 of file Benchmark.h.
◆ getRecordedExperimentData()
|
inline |
Return all the experiment data that would be written to the results file. The data should not be changed, but it could be useful to quickly extract cartain statistics.
Definition at line 312 of file Benchmark.h.
◆ getStatus()
|
inline |
Get the status of the benchmarking code. This function can be called in a separate thread to check how much progress has been made.
Definition at line 303 of file Benchmark.h.
◆ numExperimentParameters()
|
inline |
Return the number of optional benchmark parameters.
Definition at line 230 of file Benchmark.h.
◆ saveResultsToFile() [1/2]
bool ompl::tools::Benchmark::saveResultsToFile | ( | ) | const |
Save the results of the benchmark to a file. The name of the file is the current date and time.
Definition at line 220 of file Benchmark.cpp.
◆ saveResultsToFile() [2/2]
bool ompl::tools::Benchmark::saveResultsToFile | ( | const char * | filename | ) | const |
Save the results of the benchmark to a file.
Definition at line 199 of file Benchmark.cpp.
◆ saveResultsToStream()
|
virtual |
Save the results of the benchmark to a stream.
Definition at line 226 of file Benchmark.cpp.
◆ setExperimentName()
|
inline |
Set the name of the experiment.
Definition at line 236 of file Benchmark.h.
◆ setPlannerSwitchEvent()
|
inline |
Set the event to be called before any runs of a particular planner (when the planner is switched)
Definition at line 270 of file Benchmark.h.
◆ setPostRunEvent()
|
inline |
Set the event to be called after the run of a planner.
Definition at line 282 of file Benchmark.h.
◆ setPreRunEvent()
|
inline |
Set the event to be called before the run of a planner.
Definition at line 276 of file Benchmark.h.
Member Data Documentation
◆ csetup_
|
protected |
The instance of the problem to benchmark (if planning with controls)
Definition at line 332 of file Benchmark.h.
◆ exp_
|
protected |
The collected experimental data (for all planners)
Definition at line 338 of file Benchmark.h.
◆ gsetup_
|
protected |
The instance of the problem to benchmark (if geometric planning)
Definition at line 329 of file Benchmark.h.
◆ planners_
|
protected |
The set of planners to be tested.
Definition at line 335 of file Benchmark.h.
◆ plannerSwitch_
|
protected |
Event to be called when the evaluated planner is switched.
Definition at line 344 of file Benchmark.h.
◆ postRun_
|
protected |
Event to be called after the run of a planner.
Definition at line 350 of file Benchmark.h.
◆ preRun_
|
protected |
Event to be called before the run of a planner.
Definition at line 347 of file Benchmark.h.
◆ status_
|
protected |
The current status of this benchmarking instance.
Definition at line 341 of file Benchmark.h.
The documentation for this class was generated from the following files:
- ompl/tools/benchmark/Benchmark.h
- ompl/tools/benchmark/src/Benchmark.cpp