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

#include <benchmarking.h>

Classes

struct  Options
 Options for profiling. More...
 

Public Types

enum  Metrics {
  WAYPOINTS = 1 << 0 ,
  CORRECT = 1 << 1 ,
  LENGTH = 1 << 2 ,
  CLEARANCE = 1 << 3 ,
  SMOOTHNESS = 1 << 4
}
 Bitmask options to select what metrics to compute for each run. More...
 
using ComputeMetricCallback = std::function< PlannerMetric(const PlannerPtr &planner, const SceneConstPtr &scene, const planning_interface::MotionPlanRequest &request, const PlanData &run)>
 Type for callback function that returns a metric over the results of a planning query. More...
 
using ProgressPropertyAllocator = std::function< Planner::ProgressProperty(const PlannerPtr &planner, const SceneConstPtr &scene, const planning_interface::MotionPlanRequest &request)>
 Allocator function that returns a planner progress property function for the current planning request. More...
 
using ProgressCallback = std::function< void(const PlannerPtr &planner, const SceneConstPtr &scene, const planning_interface::MotionPlanRequest &request, const PlanData &result)>
 Type for callback function that is called in the planner progress property loop. More...
 
using ProgressCallbackAllocator = std::function< ProgressCallback(const PlannerPtr &planner, const SceneConstPtr &scene, const planning_interface::MotionPlanRequest &request)>
 Allocator function that returns a progress property callback function for the current planning request. More...
 

Public Member Functions

bool profilePlan (const PlannerPtr &planner, const SceneConstPtr &scene, const planning_interface::MotionPlanRequest &request, const Options &options, PlanData &result) const
 Profiling a single plan using a planner. More...
 
void addMetricCallback (const std::string &name, const ComputeMetricCallback &metric)
 Add a callback function to compute a metric at the end of planning. More...
 
void addProgressAllocator (const std::string &name, const ProgressPropertyAllocator &allocator)
 Add a function that allocates a function that returns a planner progress property function. More...
 
void addProgressCallback (const ProgressCallback &callback)
 Add a function that is called in the planner progress property loop. More...
 
void addProgressCallbackAllocator (const ProgressCallbackAllocator &allocator)
 Add a function that is called in the planner progress property loop. More...
 

Private Member Functions

void computeBuiltinMetrics (uint32_t options, const SceneConstPtr &scene, PlanData &run) const
 Compute the built-in metrics according to the provided bitmask options. More...
 
void computeCallbackMetrics (const PlannerPtr &planner, const SceneConstPtr &scene, const planning_interface::MotionPlanRequest &request, PlanData &run) const
 Compute the custom user callback metrics. More...
 

Private Attributes

std::map< std::string, ComputeMetricCallbackcallbacks_
 User callback metrics. More...
 
std::map< std::string, ProgressPropertyAllocatorprog_allocators_
 User progress properties. More...
 
std::vector< ProgressCallbackprog_callbacks_
 User progress callback functions. More...
 
std::vector< ProgressCallbackAllocatorprog_callback_allocators_
 

Detailed Description

Definition at line 203 of file benchmarking.h.

Member Typedef Documentation

◆ ComputeMetricCallback

Type for callback function that returns a metric over the results of a planning query.

Parameters
[in]plannerThe planner being profiled.
[in]sceneThe scene used for planning.
[in]requestThe planning request.
[in]runThe results of the planning run, including prior computed metrics.
Returns
The value of this metric. Will be stored in run data under associated name.

Definition at line 234 of file benchmarking.h.

◆ ProgressCallback

Type for callback function that is called in the planner progress property loop.

Parameters
[in]plannerThe planner being profiled.
[in]sceneThe scene used for planning.
[in]requestThe planning request.
[in]runThe results of the planning run, including prior computed metrics.

Definition at line 258 of file benchmarking.h.

◆ ProgressCallbackAllocator

Allocator function that returns a progress property callback function for the current planning request.

Parameters
[in]plannerThe planner being profiled.
[in]sceneThe scene used for planning.
[in]requestThe planning request.
Returns
A progress callback function.

Definition at line 270 of file benchmarking.h.

◆ ProgressPropertyAllocator

Allocator function that returns a planner progress property function for the current planning request.

Parameters
[in]plannerThe planner being profiled.
[in]sceneThe scene used for planning.
[in]requestThe planning request.
Returns
A planner progress property function.

Definition at line 247 of file benchmarking.h.

Member Enumeration Documentation

◆ Metrics

Bitmask options to select what metrics to compute for each run.

Enumerator
WAYPOINTS 

Number of waypoints in path.

CORRECT 

Is the path correct (no collisions?).

LENGTH 

Length of the path.

CLEARANCE 

Clearance of path from obstacles.

SMOOTHNESS 

Smoothness of path.

Definition at line 208 of file benchmarking.h.

209  {
210  WAYPOINTS = 1 << 0, ///< Number of waypoints in path.
211  CORRECT = 1 << 1, ///< Is the path correct (no collisions?).
212  LENGTH = 1 << 2, ///< Length of the path.
213  CLEARANCE = 1 << 3, ///< Clearance of path from obstacles.
214  SMOOTHNESS = 1 << 4, ///< Smoothness of path.
215  };
@ CLEARANCE
Clearance of path from obstacles.
Definition: benchmarking.h:213
@ WAYPOINTS
Number of waypoints in path.
Definition: benchmarking.h:210
@ SMOOTHNESS
Smoothness of path.
Definition: benchmarking.h:214
@ CORRECT
Is the path correct (no collisions?).
Definition: benchmarking.h:211
@ LENGTH
Length of the path.
Definition: benchmarking.h:212

Member Function Documentation

◆ addMetricCallback()

void Profiler::addMetricCallback ( const std::string name,
const ComputeMetricCallback metric 
)

Add a callback function to compute a metric at the end of planning.

Parameters
[in]nameName of the metric.
[in]metricFunction to use for callback.

Definition at line 245 of file benchmarking.cpp.

246 {
247  callbacks_.emplace(name, metric);
248 }
std::map< std::string, ComputeMetricCallback > callbacks_
User callback metrics.
Definition: benchmarking.h:330

◆ addProgressAllocator()

void Profiler::addProgressAllocator ( const std::string name,
const ProgressPropertyAllocator allocator 
)

Add a function that allocates a function that returns a planner progress property function.

Parameters
[in]nameName of the planner progress property.
[in]allocatorAllocator function.

Definition at line 250 of file benchmarking.cpp.

251 {
252  prog_allocators_.emplace(name, allocator);
253 }
std::map< std::string, ProgressPropertyAllocator > prog_allocators_
User progress properties.
Definition: benchmarking.h:331

◆ addProgressCallback()

void Profiler::addProgressCallback ( const ProgressCallback callback)

Add a function that is called in the planner progress property loop.

Parameters
[in]callbackCallback function to add.

Definition at line 255 of file benchmarking.cpp.

256 {
257  prog_callbacks_.emplace_back(callback);
258 }
std::vector< ProgressCallback > prog_callbacks_
User progress callback functions.
Definition: benchmarking.h:332
void callback(movegroup::MoveGroupHelper::Action &action)
Definition: tapedeck.cpp:20

◆ addProgressCallbackAllocator()

void Profiler::addProgressCallbackAllocator ( const ProgressCallbackAllocator allocator)

Add a function that is called in the planner progress property loop.

Parameters
[in]callbackCallback function to add.

Definition at line 260 of file benchmarking.cpp.

261 {
262  prog_callback_allocators_.emplace_back(allocator);
263 }
std::vector< ProgressCallbackAllocator > prog_callback_allocators_
Definition: benchmarking.h:333

◆ computeBuiltinMetrics()

void Profiler::computeBuiltinMetrics ( uint32_t  options,
const SceneConstPtr scene,
PlanData run 
) const
private

Compute the built-in metrics according to the provided bitmask options.

Parameters
[in]optionsBitmask of which built-in metrics to compute.
[in]sceneScene used for planning and metric computation.
[out]runMetric results.

Definition at line 265 of file benchmarking.cpp.

266 {
267  if (options & Metrics::WAYPOINTS)
268  run.metrics["waypoints"] = run.success ? int(run.trajectory->getNumWaypoints()) : int(0);
269 
270  if (options & Metrics::LENGTH)
271  run.metrics["length"] = run.success ? run.trajectory->getLength() : 0.0;
272 
273  if (options & Metrics::CORRECT)
274  run.metrics["correct"] = run.success ? run.trajectory->isCollisionFree(scene) : false;
275 
276  if (options & Metrics::CLEARANCE)
277  run.metrics["clearance"] = run.success ? std::get<0>(run.trajectory->getClearance(scene)) : 0.0;
278 
279  if (options & Metrics::SMOOTHNESS)
280  run.metrics["smoothness"] = run.success ? run.trajectory->getSmoothness() : 0.0;
281 
282  run.metrics["robowflex_planner_name"] = run.query.planner->getName();
283  run.metrics["robowflex_robot_name"] = run.query.planner->getRobot()->getName();
284 
285  run.metrics["request_planner_type"] = std::string(ROBOWFLEX_DEMANGLE(typeid(*run.query.planner).name()));
286  run.metrics["request_planner_id"] = run.query.request.planner_id;
287  run.metrics["request_group_name"] = run.query.request.group_name;
288  run.metrics["request_num_planning_attempts"] = run.query.request.num_planning_attempts;
289 
290  run.metrics["machine_hostname"] = run.hostname;
291  run.metrics["machine_thread_id"] = run.thread_id;
292  run.metrics["machine_process_id"] = run.process_id;
293 }
std::size_t process_id
Process ID of the process the profiler was run in.
Definition: benchmarking.h:104
bool success
Was the plan successful?
Definition: benchmarking.h:86
PlanningQuery query
Query evaluated to create this data.
Definition: benchmarking.h:84
TrajectoryPtr trajectory
The resulting trajectory, if available.
Definition: benchmarking.h:87
std::map< std::string, PlannerMetric > metrics
Map of metric name to value.
Definition: benchmarking.h:114
std::size_t thread_id
Thread ID of profiler execution.
Definition: benchmarking.h:105
std::string hostname
Hostname of the machine the plan was run on.
Definition: benchmarking.h:103
#define ROBOWFLEX_DEMANGLE(x)
Definition: macros.h:114
Functions for loading and animating scenes in Blender.
planning_interface::MotionPlanRequest request
Request used for the query.
Definition: benchmarking.h:63
PlannerPtr planner
Planner used for the query.
Definition: benchmarking.h:62

◆ computeCallbackMetrics()

void Profiler::computeCallbackMetrics ( const PlannerPtr planner,
const SceneConstPtr scene,
const planning_interface::MotionPlanRequest request,
PlanData run 
) const
private

Compute the custom user callback metrics.

Parameters
[in]plannerPlanner used.
[in]sceneScene used for planning.
[in]requestPlanning request.
[out]runMetric results.

Definition at line 295 of file benchmarking.cpp.

299 {
300  for (const auto &callback : callbacks_)
301  run.metrics[callback.first] = callback.second(planner, scene, request, run);
302 }

◆ profilePlan()

bool Profiler::profilePlan ( const PlannerPtr planner,
const SceneConstPtr scene,
const planning_interface::MotionPlanRequest request,
const Options options,
PlanData result 
) const

Profiling a single plan using a planner.

Parameters
[in]plannerPlanner to profile.
[in]sceneScene to plan in.
[in]requestPlanning request to profile.
[in]optionsThe options for profiling.
[out]resultThe results of profiling.
Returns
True if planning succeeded, false on failure.

Profiler

Definition at line 137 of file benchmarking.cpp.

142 {
143  bool complete = false;
144  std::mutex mutex;
145  std::shared_ptr<std::thread> progress_thread;
146 
147  result.query.scene = scene;
148  result.query.planner = planner;
149  result.query.request = request;
150 
151  result.start = IO::getDate();
152 
153  // Setup planner progress property thread
155  const auto &pp = planner->getProgressProperties(scene, request);
156  prog_props.insert(pp.begin(), pp.end());
157 
158  // Add custom progress properties
159  for (const auto &allocator : prog_allocators_)
160  prog_props.emplace(allocator.first, allocator.second(planner, scene, request));
161 
162  // Setup progress callbacks
164  prog_call.insert(prog_call.end(), prog_callbacks_.begin(), prog_callbacks_.end());
165 
166  for (const auto &allocator : prog_callback_allocators_)
167  prog_call.emplace_back(allocator(planner, scene, request));
168 
169  const bool have_prog = not prog_props.empty();
170  if (options.progress //
171  and (have_prog or not prog_call.empty()))
172  {
173  // Get names of progress properties
174  if (have_prog)
175  {
176  for (const auto &property : prog_props)
177  result.property_names.emplace_back(property.first);
178  result.property_names.emplace_back("time REAL");
179  }
180 
181  progress_thread.reset(new std::thread([&] {
182  bool at_least_once = options.progress_at_least_once;
183  while (true)
184  {
185  // Sleep until the next update
186  IO::threadSleep(options.progress_update_rate);
187 
189  if (not at_least_once and complete)
190  return;
191 
192  if (have_prog)
193  {
195 
196  // Add time stamp
197  double time = IO::getSeconds(result.start, IO::getDate());
198  data["time REAL"] = std::to_string(time);
199 
200  // Compute properties
201  for (const auto &property : prog_props)
202  data[property.first] = property.second();
203 
204  result.progress.emplace_back(data);
205  }
206 
207  for (const auto &callback : prog_call)
208  callback(planner, scene, request, result);
209 
210  at_least_once = false;
211  }
212  }));
213  }
214 
215  // Plan
216  result.response = planner->plan(scene, request);
217 
218  // Notify planner progress thread
219  {
221  complete = true;
222  }
223 
224  // Compute metrics and fill out results
225  result.finish = IO::getDate();
226  result.time = IO::getSeconds(result.start, result.finish);
227  result.success = result.response.error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS;
228 
229  if (result.success)
230  result.trajectory = std::make_shared<Trajectory>(*result.response.trajectory_);
231 
232  result.hostname = IO::getHostname();
233  result.process_id = IO::getProcessID();
234  result.thread_id = IO::getThreadID();
235 
236  computeBuiltinMetrics(options.metrics, scene, result);
237  computeCallbackMetrics(planner, scene, request, result);
238 
239  if (progress_thread)
240  progress_thread->join();
241 
242  return result.success;
243 }
boost::posix_time::ptime finish
Query end time.
Definition: benchmarking.h:96
std::vector< std::string > property_names
Planner progress value names.
Definition: benchmarking.h:112
planning_interface::MotionPlanResponse response
Planner response.
Definition: benchmarking.h:85
std::vector< std::map< std::string, std::string > > progress
Planner progress data.
Definition: benchmarking.h:113
boost::posix_time::ptime start
Query start time.
Definition: benchmarking.h:95
double time
Time that planning took in seconds.
Definition: benchmarking.h:94
void computeBuiltinMetrics(uint32_t options, const SceneConstPtr &scene, PlanData &run) const
Compute the built-in metrics according to the provided bitmask options.
void computeCallbackMetrics(const PlannerPtr &planner, const SceneConstPtr &scene, const planning_interface::MotionPlanRequest &request, PlanData &run) const
Compute the custom user callback metrics.
T emplace_back(T... args)
T emplace(T... args)
T empty(T... args)
T end(T... args)
T insert(T... args)
T lock(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)
std::size_t getProcessID()
Get the process ID of this process.
std::string getHostname()
Get the hostname of the system.
std::size_t getThreadID()
Get the thread ID of the current thread.
void threadSleep(double seconds)
Put the current thread to sleep for a desired amount of seconds.
T reset(T... args)
moveit_msgs::MoveItErrorCodes error_code_
robot_trajectory::RobotTrajectoryPtr trajectory_
SceneConstPtr scene
Scene used for the query.
Definition: benchmarking.h:61
T time(T... args)
T to_string(T... args)

Member Data Documentation

◆ callbacks_

std::map<std::string, ComputeMetricCallback> robowflex::Profiler::callbacks_
private

User callback metrics.

Definition at line 330 of file benchmarking.h.

◆ prog_allocators_

std::map<std::string, ProgressPropertyAllocator> robowflex::Profiler::prog_allocators_
private

User progress properties.

Definition at line 331 of file benchmarking.h.

◆ prog_callback_allocators_

std::vector<ProgressCallbackAllocator> robowflex::Profiler::prog_callback_allocators_
private

User progress callback function allocators.

Definition at line 333 of file benchmarking.h.

◆ prog_callbacks_

std::vector<ProgressCallback> robowflex::Profiler::prog_callbacks_
private

User progress callback functions.

Definition at line 332 of file benchmarking.h.


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