Robowflex
v0.1
Making MoveIt Easy
|
A helper class for benchmarking that controls running multiple queries. More...
#include <benchmarking.h>
Public Member Functions | |
PlanDataSetPtr | benchmark (std::size_t n_threads=1) const |
Run benchmarking on this experiment. Note that, for some planners, multiple threads cannot be used without polluting the dataset, due to reuse of underlying datastructures between queries, e.g., the robowflex_ompl planner. More... | |
Building Experiment | |
Experiment (const std::string &name, const Profiler::Options &options, double allowed_time=60.0, std::size_t trials=100, bool timeout=false) | |
Constructor. More... | |
void | addQuery (const std::string &planner_name, const SceneConstPtr &scene, const PlannerPtr &planner, const planning_interface::MotionPlanRequest &request) |
Add a query to the experiment for profiling. More... | |
void | addQuery (const std::string &planner_name, const SceneConstPtr &scene, const PlannerPtr &planner, const MotionRequestBuilder &request) |
Add a query to the experiment for profiling. More... | |
void | addQuery (const std::string &planner_name, const SceneConstPtr &scene, const PlannerPtr &planner, const MotionRequestBuilderPtr &request) |
Add a query to the experiment for profiling. More... | |
Configuration, Getters, Setters | |
Profiler::Options & | getOptions () |
Get the options used by the underlying profiler. More... | |
Profiler & | getProfiler () |
Get a reference to the profiler used by the experiment. Add callback functions to this profiler for custom metrics. More... | |
const Profiler & | getProfilerConst () const |
Get a reference to the profiler used by the experiment. More... | |
const std::vector< PlanningQuery > & | getQueries () const |
Get the queries added to this experiment. More... | |
void | enableMultipleRequests () |
If called, will enable planners to use multiple threads. By default, planners are requested to only use one thread. More... | |
void | overridePlanningTime () |
If called, instead of using global allotted planning time (provided in the constructor), the benchmark will use the requested planning time in the planning request of the query. More... | |
Private Attributes | |
const std::string | name_ |
Name of this experiment. More... | |
double | allowed_time_ |
Allotted time to use for each query. More... | |
std::size_t | trials_ |
Number of trials to run each query for. More... | |
bool | timeout_ |
bool | enforce_single_thread_ {true} |
bool | override_planning_time_ {true} |
Profiler::Options | options_ |
Options for profiler. More... | |
Profiler | profiler_ |
Profiler to use for extracting data. More... | |
std::vector< PlanningQuery > | queries_ |
Queries to test. More... | |
PreRunCallback | pre_callback_ |
Pre-run callback. More... | |
PostRunCallback | post_callback_ |
Post-run callback. More... | |
PostQueryCallback | complete_callback_ |
Post-run callback with dataset. More... | |
Callback Functions | |
using | PreRunCallback = std::function< void(const PlanningQuery &query)> |
A callback function that is called before every query is profiled. More... | |
using | PostRunCallback = std::function< void(PlanData &result, const PlanningQuery &query)> |
A callback function that is called after every query is profiled. More... | |
using | PostQueryCallback = std::function< void(PlanDataSetPtr dataset, const PlanningQuery &query)> |
void | setPreRunCallback (const PreRunCallback &callback) |
Set the pre-query callback function. More... | |
void | setPostRunCallback (const PostRunCallback &callback) |
Set the post-query callback function. More... | |
void | setPostQueryCallback (const PostQueryCallback &callback) |
Set the post-dataset callback function. More... | |
A helper class for benchmarking that controls running multiple queries.
Definition at line 348 of file benchmarking.h.
using robowflex::Experiment::PostQueryCallback = std::function<void(PlanDataSetPtr dataset, const PlanningQuery &query)> |
A callback function that is called after a result is added to the dataset.
[in,out] |
Definition at line 457 of file benchmarking.h.
using robowflex::Experiment::PostRunCallback = std::function<void(PlanData &result, const PlanningQuery &query)> |
A callback function that is called after every query is profiled.
[in,out] | result | The result computed by the profiler. |
[in] | query | The query that was profiled. |
Definition at line 451 of file benchmarking.h.
using robowflex::Experiment::PreRunCallback = std::function<void(const PlanningQuery &query)> |
A callback function that is called before every query is profiled.
[in] | query | The query to be profiled. |
Definition at line 445 of file benchmarking.h.
Experiment::Experiment | ( | const std::string & | name, |
const Profiler::Options & | options, | ||
double | allowed_time = 60.0 , |
||
std::size_t | trials = 100 , |
||
bool | timeout = false |
||
) |
Constructor.
[in] | name | Name of this experiment. |
[in] | options | Options for the internal profiler. |
[in] | allowed_time | Total planning time allowed for each query. |
[in] | trials | Number of trials to run each query for. |
[in] | timeout | If true, will re-run each query until the total time taken has exceeded the allotted time. |
Definition at line 308 of file benchmarking.cpp.
void Experiment::addQuery | ( | const std::string & | planner_name, |
const SceneConstPtr & | scene, | ||
const PlannerPtr & | planner, | ||
const MotionRequestBuilder & | request | ||
) |
Add a query to the experiment for profiling.
[in] | planner_name | Name to associate with this query. Does not need to be unique. |
[in] | scene | Scene to use for query. |
[in] | planner | Planner to use for query. |
[in] | request | Request to use for query. |
Definition at line 322 of file benchmarking.cpp.
void Experiment::addQuery | ( | const std::string & | planner_name, |
const SceneConstPtr & | scene, | ||
const PlannerPtr & | planner, | ||
const MotionRequestBuilderPtr & | request | ||
) |
Add a query to the experiment for profiling.
[in] | planner_name | Name to associate with this query. Does not need to be unique. |
[in] | scene | Scene to use for query. |
[in] | planner | Planner to use for query. |
[in] | request | Request to use for query. |
Definition at line 330 of file benchmarking.cpp.
void Experiment::addQuery | ( | const std::string & | planner_name, |
const SceneConstPtr & | scene, | ||
const PlannerPtr & | planner, | ||
const planning_interface::MotionPlanRequest & | request | ||
) |
Add a query to the experiment for profiling.
[in] | planner_name | Name to associate with this query. Does not need to be unique. |
[in] | scene | Scene to use for query. |
[in] | planner | Planner to use for query. |
[in] | request | Request to use for query. |
Definition at line 314 of file benchmarking.cpp.
PlanDataSetPtr Experiment::benchmark | ( | std::size_t | n_threads = 1 | ) | const |
Run benchmarking on this experiment. Note that, for some planners, multiple threads cannot be used without polluting the dataset, due to reuse of underlying datastructures between queries, e.g., the robowflex_ompl planner.
[in] | n_threads | Number of threads to use for benchmarking. |
Definition at line 383 of file benchmarking.cpp.
void Experiment::enableMultipleRequests | ( | ) |
If called, will enable planners to use multiple threads. By default, planners are requested to only use one thread.
Definition at line 358 of file benchmarking.cpp.
Profiler::Options & Experiment::getOptions | ( | ) |
Get the options used by the underlying profiler.
Definition at line 338 of file benchmarking.cpp.
Profiler & Experiment::getProfiler | ( | ) |
Get a reference to the profiler used by the experiment. Add callback functions to this profiler for custom metrics.
Definition at line 343 of file benchmarking.cpp.
const Profiler & Experiment::getProfilerConst | ( | ) | const |
Get a reference to the profiler used by the experiment.
Definition at line 348 of file benchmarking.cpp.
const std::vector< PlanningQuery > & Experiment::getQueries | ( | ) | const |
Get the queries added to this experiment.
Definition at line 353 of file benchmarking.cpp.
void Experiment::overridePlanningTime | ( | ) |
If called, instead of using global allotted planning time (provided in the constructor), the benchmark will use the requested planning time in the planning request of the query.
Definition at line 363 of file benchmarking.cpp.
void Experiment::setPostQueryCallback | ( | const PostQueryCallback & | callback | ) |
Set the post-dataset callback function.
[in] | callback | Callback to use. |
Definition at line 378 of file benchmarking.cpp.
void Experiment::setPostRunCallback | ( | const PostRunCallback & | callback | ) |
Set the post-query callback function.
[in] | callback | Callback to use. |
Definition at line 373 of file benchmarking.cpp.
void Experiment::setPreRunCallback | ( | const PreRunCallback & | callback | ) |
Set the pre-query callback function.
[in] | callback | Callback to use. |
Definition at line 368 of file benchmarking.cpp.
|
private |
Allotted time to use for each query.
Definition at line 486 of file benchmarking.h.
|
private |
Post-run callback with dataset.
Definition at line 501 of file benchmarking.h.
|
private |
If true, will request each planner to only use a single thread.
Definition at line 490 of file benchmarking.h.
|
private |
Name of this experiment.
Definition at line 485 of file benchmarking.h.
|
private |
Options for profiler.
Definition at line 495 of file benchmarking.h.
|
private |
If true, will override request planning time with global allowed time.
Definition at line 492 of file benchmarking.h.
|
private |
Post-run callback.
Definition at line 500 of file benchmarking.h.
|
private |
Pre-run callback.
Definition at line 499 of file benchmarking.h.
|
private |
Profiler to use for extracting data.
Definition at line 496 of file benchmarking.h.
|
private |
Queries to test.
Definition at line 497 of file benchmarking.h.
|
private |
If true, will re-run planners on queries until total time taken has exceeded the allotted time.
Definition at line 488 of file benchmarking.h.
|
private |
Number of trials to run each query for.
Definition at line 487 of file benchmarking.h.