Benchmark a set of planners on a problem instance. More...
#include <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 | 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 | |
typedef std::map< std::string, std::string > | RunProperties |
The data collected from a run of a planner is stored as key-value pairs. | |
Public Member Functions | |
void | addPlanner (const base::PlannerPtr &planner) |
Set the planner to use. If the planner is not set, an attempt is made to use the planner allocator. If no planner allocator is available either, a default planner is set. | |
void | addPlannerAllocator (const base::PlannerAllocator &pa) |
Set the planner allocator to use. This is only used if no planner has been set. This is optional -- a default planner will be used if no planner is otherwise specified. | |
virtual void | benchmark (double maxTime, double maxMem, unsigned int runCount, bool displayProgress=false) |
Benchmark the added planners on the defined problem. Repeated calls clear previously gathered data. | |
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. | |
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. | |
void | clearPlanners (void) |
Clear the set of planners to be benchmarked. | |
const std::string & | getExperimentName (void) const |
Get the name of the experiment. | |
const CompleteExperiment & | getRecordedExperimentData (void) 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. | |
const Status & | getStatus (void) 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. | |
bool | saveResultsToFile (void) const |
Save the results of the benchmark to a file. The name of the file is the current date and time. | |
bool | saveResultsToFile (const char *filename) const |
Save the results of the benchmark to a file. | |
virtual bool | saveResultsToStream (std::ostream &out=std::cout) const |
Save the results of the benchmark to a stream. | |
void | setExperimentName (const std::string &name) |
Set the name of the experiment. | |
virtual | ~Benchmark (void) |
Protected Member Functions | |
std::string | getResultsFilename (void) const |
Propose a name for a file in which results should be saved, based on the date and hostname of the experiment. | |
Protected Attributes | |
control::SimpleSetup * | csetup_ |
The instance of the problem to benchmark (if planning with controls). | |
CompleteExperiment | exp_ |
The collected experimental data (for all planners). | |
geometric::SimpleSetup * | gsetup_ |
The instance of the problem to benchmark (if geometric planning). | |
msg::Interface | msg_ |
Interface for console output. | |
std::vector< base::PlannerPtr > | planners_ |
The set of planners to be tested. | |
Status | status_ |
The current status of this benchmarking instance. |
Benchmark a set of planners on a problem instance.
Definition at line 45 of file Benchmark.h.
typedef std::map<std::string, std::string> ompl::Benchmark::RunProperties |
The data collected from a run of a planner is stored as key-value pairs.
Definition at line 74 of file Benchmark.h.
ompl::Benchmark::Benchmark | ( | geometric::SimpleSetup & | setup, | |
const std::string & | name = std::string() | |||
) | [inline] |
Constructor needs the SimpleSetup instance needed for planning. Optionally, the experiment name (name) can be specified.
Definition at line 121 of file Benchmark.h.
ompl::Benchmark::Benchmark | ( | control::SimpleSetup & | setup, | |
const std::string & | name = std::string() | |||
) | [inline] |
Constructor needs the SimpleSetup instance needed for planning. Optionally, the experiment name (name) can be specified.
Definition at line 127 of file Benchmark.h.
virtual ompl::Benchmark::~Benchmark | ( | void | ) | [inline, virtual] |
Definition at line 132 of file Benchmark.h.
void ompl::Benchmark::addPlanner | ( | const base::PlannerPtr & | planner | ) | [inline] |
Set the planner to use. If the planner is not set, an attempt is made to use the planner allocator. If no planner allocator is available either, a default planner is set.
Definition at line 152 of file Benchmark.h.
void ompl::Benchmark::addPlannerAllocator | ( | const base::PlannerAllocator & | pa | ) | [inline] |
Set the planner allocator to use. This is only used if no planner has been set. This is optional -- a default planner will be used if no planner is otherwise specified.
Definition at line 163 of file Benchmark.h.
virtual void ompl::Benchmark::benchmark | ( | double | maxTime, | |
double | maxMem, | |||
unsigned int | runCount, | |||
bool | displayProgress = false | |||
) | [virtual] |
Benchmark the added planners on the defined problem. Repeated calls clear previously gathered data.
maxTime | the maximum amount of time a planner is allowed to run (seconds) | |
maxMem | the maximum amount of memory a planner is allowed to use (MB) | |
runCount | the number of times to run each planner | |
displayProgress | flag indicating whether progress is to be displayed or not |
void ompl::Benchmark::clearPlanners | ( | void | ) | [inline] |
Clear the set of planners to be benchmarked.
Definition at line 169 of file Benchmark.h.
const std::string& ompl::Benchmark::getExperimentName | ( | void | ) | const [inline] |
Get the name of the experiment.
Definition at line 143 of file Benchmark.h.
const CompleteExperiment& ompl::Benchmark::getRecordedExperimentData | ( | void | ) | const [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 201 of file Benchmark.h.
std::string ompl::Benchmark::getResultsFilename | ( | void | ) | const [protected] |
Propose a name for a file in which results should be saved, based on the date and hostname of the experiment.
const Status& ompl::Benchmark::getStatus | ( | void | ) | const [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 192 of file Benchmark.h.
bool ompl::Benchmark::saveResultsToFile | ( | void | ) | const |
Save the results of the benchmark to a file. The name of the file is the current date and time.
bool ompl::Benchmark::saveResultsToFile | ( | const char * | filename | ) | const |
Save the results of the benchmark to a file.
virtual bool ompl::Benchmark::saveResultsToStream | ( | std::ostream & | out = std::cout |
) | const [virtual] |
Save the results of the benchmark to a stream.
void ompl::Benchmark::setExperimentName | ( | const std::string & | name | ) | [inline] |
Set the name of the experiment.
Definition at line 137 of file Benchmark.h.
control::SimpleSetup* ompl::Benchmark::csetup_ [protected] |
The instance of the problem to benchmark (if planning with controls).
Definition at line 224 of file Benchmark.h.
CompleteExperiment ompl::Benchmark::exp_ [protected] |
The collected experimental data (for all planners).
Definition at line 230 of file Benchmark.h.
geometric::SimpleSetup* ompl::Benchmark::gsetup_ [protected] |
The instance of the problem to benchmark (if geometric planning).
Definition at line 221 of file Benchmark.h.
msg::Interface ompl::Benchmark::msg_ [protected] |
Interface for console output.
Definition at line 236 of file Benchmark.h.
std::vector<base::PlannerPtr> ompl::Benchmark::planners_ [protected] |
The set of planners to be tested.
Definition at line 227 of file Benchmark.h.
Status ompl::Benchmark::status_ [protected] |
The current status of this benchmarking instance.
Definition at line 233 of file Benchmark.h.