Robowflex  v0.1
Making MoveIt Easy
robowflex::Experiment Class Reference

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::OptionsgetOptions ()
 Get the options used by the underlying profiler. More...
 
ProfilergetProfiler ()
 Get a reference to the profiler used by the experiment. Add callback functions to this profiler for custom metrics. More...
 
const ProfilergetProfilerConst () 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< PlanningQueryqueries_
 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...
 

Detailed Description

A helper class for benchmarking that controls running multiple queries.

Definition at line 348 of file benchmarking.h.

Member Typedef Documentation

◆ PostQueryCallback

A callback function that is called after a result is added to the dataset.

Parameters
[in,out]

Definition at line 457 of file benchmarking.h.

◆ PostRunCallback

A callback function that is called after every query is profiled.

Parameters
[in,out]resultThe result computed by the profiler.
[in]queryThe query that was profiled.

Definition at line 451 of file benchmarking.h.

◆ PreRunCallback

A callback function that is called before every query is profiled.

Parameters
[in]queryThe query to be profiled.

Definition at line 445 of file benchmarking.h.

Constructor & Destructor Documentation

◆ Experiment()

Experiment::Experiment ( const std::string name,
const Profiler::Options options,
double  allowed_time = 60.0,
std::size_t  trials = 100,
bool  timeout = false 
)

Constructor.

Parameters
[in]nameName of this experiment.
[in]optionsOptions for the internal profiler.
[in]allowed_timeTotal planning time allowed for each query.
[in]trialsNumber of trials to run each query for.
[in]timeoutIf true, will re-run each query until the total time taken has exceeded the allotted time.

Experiment

Definition at line 308 of file benchmarking.cpp.

310  : name_(name), allowed_time_(allowed_time), trials_(trials), timeout_(timeout), options_(options)
311 {
312 }
std::size_t trials_
Number of trials to run each query for.
Definition: benchmarking.h:487
Profiler::Options options_
Options for profiler.
Definition: benchmarking.h:495
double allowed_time_
Allotted time to use for each query.
Definition: benchmarking.h:486
const std::string name_
Name of this experiment.
Definition: benchmarking.h:485

Member Function Documentation

◆ addQuery() [1/3]

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.

Parameters
[in]planner_nameName to associate with this query. Does not need to be unique.
[in]sceneScene to use for query.
[in]plannerPlanner to use for query.
[in]requestRequest to use for query.

Definition at line 322 of file benchmarking.cpp.

326 {
327  addQuery(planner_name, scene, planner, request.getRequestConst());
328 }
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.
const planning_interface::MotionPlanRequest & getRequestConst() const
Get a const reference to the currently built motion planning request.
Definition: builder.cpp:538
Functions for loading and animating scenes in Blender.

◆ addQuery() [2/3]

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.

Parameters
[in]planner_nameName to associate with this query. Does not need to be unique.
[in]sceneScene to use for query.
[in]plannerPlanner to use for query.
[in]requestRequest to use for query.

Definition at line 330 of file benchmarking.cpp.

334 {
335  addQuery(planner_name, scene, planner, *request);
336 }

◆ addQuery() [3/3]

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.

Parameters
[in]planner_nameName to associate with this query. Does not need to be unique.
[in]sceneScene to use for query.
[in]plannerPlanner to use for query.
[in]requestRequest to use for query.

Definition at line 314 of file benchmarking.cpp.

318 {
319  queries_.emplace_back(planner_name, scene, planner, request);
320 }
std::vector< PlanningQuery > queries_
Queries to test.
Definition: benchmarking.h:497

◆ benchmark()

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.

Parameters
[in]n_threadsNumber of threads to use for benchmarking.
Returns
The computed dataset.

Definition at line 383 of file benchmarking.cpp.

384 {
385  // Setup dataset to return
386  auto dataset = std::make_shared<PlanDataSet>();
387  dataset->name = name_;
388  dataset->start = IO::getDate();
389  dataset->allowed_time = allowed_time_;
390  dataset->trials = trials_;
391  dataset->enforced_single_thread = enforce_single_thread_;
392  dataset->run_till_timeout = timeout_;
393  dataset->threads = n_threads;
394  dataset->queries = queries_;
395 
396  struct ThreadInfo
397  {
398  ThreadInfo() = default;
399  ThreadInfo(const PlanningQuery *query, std::size_t trial, std::size_t index)
400  : query(query), trial(trial), index(index)
401  {
402  }
403 
404  const PlanningQuery *query;
405  std::size_t trial;
406  std::size_t index;
407  };
408 
410  std::mutex mutex;
411 
412  for (std::size_t i = 0; i < queries_.size(); ++i)
413  {
414  const auto &query = queries_[i];
415 
416  // Check if this name is unique, if so, add it to dataset list.
417  const auto &it = std::find(dataset->query_names.begin(), dataset->query_names.end(), query.name);
418  if (it == dataset->query_names.end())
419  dataset->query_names.emplace_back(query.name);
420 
421  for (std::size_t j = 0; j < trials_; ++j)
422  todo.emplace(&query, j, i);
423  }
424 
426  std::size_t completed_queries = 0;
427  std::size_t total_queries = todo.size();
428 
429  for (std::size_t i = 0; i < n_threads; ++i)
430  threads.emplace_back(std::make_shared<std::thread>([&]() {
431  std::size_t id = IO::getThreadID();
432  while (true)
433  {
434  ThreadInfo info;
435 
436  {
437  std::unique_lock<std::mutex> lock(mutex);
438  if (todo.empty()) // All done, exit.
439  return;
440 
441  info = todo.front();
442  todo.pop();
443  }
444 
445  RBX_INFO("[Thread %1%] Running Query %3% `%2%` Trial [%4%/%5%]", //
446  id, info.query->name, info.index, info.trial + 1, trials_);
447 
448  // If override, use global time. Else use query time.
449  double time_remaining =
450  (override_planning_time_) ? allowed_time_ : info.query->request.allowed_planning_time;
451 
452  std::size_t timeout_trial = 0;
453  while (time_remaining > 0.)
454  {
455  planning_interface::MotionPlanRequest request = info.query->request;
456  request.allowed_planning_time = time_remaining;
457 
458  if (enforce_single_thread_)
459  request.num_planning_attempts = 1;
460 
461  // Call pre-run callbacks
462  info.query->planner->preRun(info.query->scene, request);
463 
464  if (pre_callback_)
465  pre_callback_(*info.query);
466 
467  // Profile query
468  auto data = std::make_shared<PlanData>();
469  profiler_.profilePlan(info.query->planner, //
470  info.query->scene, //
471  request, //
472  options_, //
473  *data);
474 
475  // Add experiment specific metrics
476  data->metrics.emplace("query_trial", (int)info.trial);
477  data->metrics.emplace("query_index", (int)info.index);
478  data->metrics.emplace("query_timeout_trial", (int)timeout_trial);
479  data->metrics.emplace("query_start_time", IO::getSeconds(dataset->start, data->start));
480  data->metrics.emplace("query_finish_time", IO::getSeconds(dataset->start, data->finish));
481 
482  data->query.name = log::format("%1%:%2%:%3%", info.query->name, info.trial, info.index);
483 
484  if (timeout_)
485  data->query.name = data->query.name + log::format(":%4%", timeout_trial);
486 
487  if (post_callback_)
488  post_callback_(*data, *info.query);
489 
490  {
491  std::unique_lock<std::mutex> lock(mutex);
492 
493  dataset->addDataPoint(info.query->name, data);
494  completed_queries++;
495 
496  if (complete_callback_)
497  complete_callback_(dataset, *info.query);
498  }
499 
500  if (timeout_)
501  {
502  time_remaining -= data->time;
503  RBX_INFO( //
504  "[Thread %1%] Running Query %3% `%2%` till timeout, %4% seconds remaining...", //
505  id, info.query->name, info.index, time_remaining);
506  timeout_trial++;
507  }
508  else
509  time_remaining = 0;
510  }
511 
512  RBX_INFO("[Thread %1%] Completed Query %3% `%2%` Trial [%4%/%5%] Total: [%6%/%7%]", //
513  id, info.query->name, info.index, //
514  info.trial + 1, trials_, //
515  completed_queries, total_queries);
516  }
517  }));
518 
519  for (const auto &thread : threads)
520  thread->join();
521 
522  dataset->finish = IO::getDate();
523  dataset->time = IO::getSeconds(dataset->start, dataset->finish);
524 
525  return dataset;
526 }
T emplace_back(T... args)
T emplace(T... args)
T find(T... args)
double getSeconds(boost::posix_time::ptime start, boost::posix_time::ptime finish)
Get a duration in seconds from two times.
boost::posix_time::ptime getDate()
Get the current time (up to milliseconds)
T size(T... args)
A container structure for all elements needed in a planning query, plus an identifying name.
Definition: benchmarking.h:44

◆ enableMultipleRequests()

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.

359 {
360  enforce_single_thread_ = false;
361 }

◆ getOptions()

Profiler::Options & Experiment::getOptions ( )

Get the options used by the underlying profiler.

Returns
A reference to the options used.

Definition at line 338 of file benchmarking.cpp.

339 {
340  return options_;
341 }

◆ getProfiler()

Profiler & Experiment::getProfiler ( )

Get a reference to the profiler used by the experiment. Add callback functions to this profiler for custom metrics.

Returns
The profiler.

Definition at line 343 of file benchmarking.cpp.

344 {
345  return profiler_;
346 }
Profiler profiler_
Profiler to use for extracting data.
Definition: benchmarking.h:496

◆ getProfilerConst()

const Profiler & Experiment::getProfilerConst ( ) const

Get a reference to the profiler used by the experiment.

Returns
The profiler.

Definition at line 348 of file benchmarking.cpp.

349 {
350  return profiler_;
351 }

◆ getQueries()

const std::vector< PlanningQuery > & Experiment::getQueries ( ) const

Get the queries added to this experiment.

Returns
The queries added to the experiment.

Definition at line 353 of file benchmarking.cpp.

354 {
355  return queries_;
356 }

◆ overridePlanningTime()

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.

364 {
365  override_planning_time_ = false;
366 }

◆ setPostQueryCallback()

void Experiment::setPostQueryCallback ( const PostQueryCallback callback)

Set the post-dataset callback function.

Parameters
[in]callbackCallback to use.

Definition at line 378 of file benchmarking.cpp.

379 {
381 }
PostQueryCallback complete_callback_
Post-run callback with dataset.
Definition: benchmarking.h:501
void callback(movegroup::MoveGroupHelper::Action &action)
Definition: tapedeck.cpp:20

◆ setPostRunCallback()

void Experiment::setPostRunCallback ( const PostRunCallback callback)

Set the post-query callback function.

Parameters
[in]callbackCallback to use.

Definition at line 373 of file benchmarking.cpp.

374 {
376 }
PostRunCallback post_callback_
Post-run callback.
Definition: benchmarking.h:500

◆ setPreRunCallback()

void Experiment::setPreRunCallback ( const PreRunCallback callback)

Set the pre-query callback function.

Parameters
[in]callbackCallback to use.

Definition at line 368 of file benchmarking.cpp.

369 {
371 }
PreRunCallback pre_callback_
Pre-run callback.
Definition: benchmarking.h:499

Member Data Documentation

◆ allowed_time_

double robowflex::Experiment::allowed_time_
private

Allotted time to use for each query.

Definition at line 486 of file benchmarking.h.

◆ complete_callback_

PostQueryCallback robowflex::Experiment::complete_callback_
private

Post-run callback with dataset.

Definition at line 501 of file benchmarking.h.

◆ enforce_single_thread_

bool robowflex::Experiment::enforce_single_thread_ {true}
private

If true, will request each planner to only use a single thread.

Definition at line 490 of file benchmarking.h.

◆ name_

const std::string robowflex::Experiment::name_
private

Name of this experiment.

Definition at line 485 of file benchmarking.h.

◆ options_

Profiler::Options robowflex::Experiment::options_
private

Options for profiler.

Definition at line 495 of file benchmarking.h.

◆ override_planning_time_

bool robowflex::Experiment::override_planning_time_ {true}
private

If true, will override request planning time with global allowed time.

Definition at line 492 of file benchmarking.h.

◆ post_callback_

PostRunCallback robowflex::Experiment::post_callback_
private

Post-run callback.

Definition at line 500 of file benchmarking.h.

◆ pre_callback_

PreRunCallback robowflex::Experiment::pre_callback_
private

Pre-run callback.

Definition at line 499 of file benchmarking.h.

◆ profiler_

Profiler robowflex::Experiment::profiler_
private

Profiler to use for extracting data.

Definition at line 496 of file benchmarking.h.

◆ queries_

std::vector<PlanningQuery> robowflex::Experiment::queries_
private

Queries to test.

Definition at line 497 of file benchmarking.h.

◆ timeout_

bool robowflex::Experiment::timeout_
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.

◆ trials_

std::size_t robowflex::Experiment::trials_
private

Number of trials to run each query for.

Definition at line 487 of file benchmarking.h.


The documentation for this class was generated from the following files: