BenchmarkExecutor.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015, Rice University
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Rice University nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ryan Luna */
36 
39 #include <moveit/version.h>
40 #include <tf2_eigen/tf2_eigen.h>
41 
42 #include <boost/regex.hpp>
43 
44 #if __has_include(<boost/timer/progress_display.hpp>)
45 #include <boost/timer/progress_display.hpp>
46 using boost_progress_display = boost::timer::progress_display;
47 #else
48 // boost < 1.72
49 #define BOOST_TIMER_ENABLE_DEPRECATED 1
50 #include <boost/progress.hpp>
51 #undef BOOST_TIMER_ENABLE_DEPRECATED
52 using boost_progress_display = boost::progress_display;
53 #endif
54 
55 #include <boost/math/constants/constants.hpp>
56 #include <boost/filesystem.hpp>
57 #include <boost/date_time/posix_time/posix_time.hpp>
58 #ifndef _WIN32
59 #include <unistd.h>
60 #else
61 #include <winsock2.h>
62 #endif
63 
64 using namespace moveit_ros_benchmarks;
65 
66 static std::string getHostname()
67 {
68  static const int BUF_SIZE = 1024;
69  char buffer[BUF_SIZE];
70  int err = gethostname(buffer, sizeof(buffer));
71  if (err != 0)
72  return std::string();
73  else
74  {
75  buffer[BUF_SIZE - 1] = '\0';
76  return std::string(buffer);
77  }
78 }
79 
80 BenchmarkExecutor::BenchmarkExecutor(const std::string& robot_description_param)
81 {
82  pss_ = nullptr;
83  psws_ = nullptr;
84  rs_ = nullptr;
85  cs_ = nullptr;
86  tcs_ = nullptr;
87  psm_ = new planning_scene_monitor::PlanningSceneMonitor(robot_description_param);
89 }
90 
92 {
93  delete pss_;
94  delete psws_;
95  delete rs_;
96  delete cs_;
97  delete tcs_;
98  delete psm_;
99 }
100 
101 void BenchmarkExecutor::initialize(const std::vector<std::string>& planning_pipeline_names)
102 {
103  planning_pipelines_.clear();
104 
105  ros::NodeHandle pnh("~");
106  for (const std::string& planning_pipeline_name : planning_pipeline_names)
107  {
108  // Initialize planning pipelines from configured child namespaces
109  ros::NodeHandle child_nh(pnh, planning_pipeline_name);
110  planning_pipeline::PlanningPipelinePtr pipeline(new planning_pipeline::PlanningPipeline(
111  planning_scene_->getRobotModel(), child_nh, "planning_plugin", "request_adapters"));
112 
113  // Verify the pipeline has successfully initialized a planner
114  if (!pipeline->getPlannerManager())
115  {
116  ROS_ERROR("Failed to initialize planning pipeline '%s'", planning_pipeline_name.c_str());
117  continue;
118  }
119 
120  // Disable visualizations and store pipeline
121  pipeline->displayComputedMotionPlans(false);
122  pipeline->checkSolutionPaths(false);
123  planning_pipelines_[planning_pipeline_name] = pipeline;
124  }
125 
126  // Error check
127  if (planning_pipelines_.empty())
128  ROS_ERROR("No planning pipelines have been loaded. Nothing to do for the benchmarking service.");
129  else
130  {
131  ROS_INFO("Available planning pipelines:");
132  for (const std::pair<const std::string, planning_pipeline::PlanningPipelinePtr>& entry : planning_pipelines_)
133  ROS_INFO_STREAM("Pipeline: " << entry.first << ", Planner: " << entry.second->getPlannerPluginName());
134  }
135 }
136 
138 {
139  if (pss_)
140  {
141  delete pss_;
142  pss_ = nullptr;
143  }
144  if (psws_)
145  {
146  delete psws_;
147  psws_ = nullptr;
148  }
149  if (rs_)
150  {
151  delete rs_;
152  rs_ = nullptr;
153  }
154  if (cs_)
155  {
156  delete cs_;
157  cs_ = nullptr;
158  }
159  if (tcs_)
160  {
161  delete tcs_;
162  tcs_ = nullptr;
163  }
164 
165  benchmark_data_.clear();
166  pre_event_fns_.clear();
167  post_event_fns_.clear();
168  planner_start_fns_.clear();
169  planner_completion_fns_.clear();
170  query_start_fns_.clear();
171  query_end_fns_.clear();
172 }
173 
175 {
176  pre_event_fns_.push_back(func);
177 }
178 
180 {
181  post_event_fns_.push_back(func);
182 }
183 
185 {
186  planner_start_fns_.push_back(func);
187 }
188 
190 {
191  planner_completion_fns_.push_back(func);
192 }
193 
195 {
196  query_start_fns_.push_back(func);
197 }
198 
200 {
201  query_end_fns_.push_back(func);
202 }
203 
205 {
206  if (planning_pipelines_.empty())
207  {
208  ROS_ERROR("No planning pipelines configured. Did you call BenchmarkExecutor::initialize?");
209  return false;
210  }
211 
212  std::vector<BenchmarkRequest> queries;
213  moveit_msgs::PlanningScene scene_msg;
214 
215  if (initializeBenchmarks(opts, scene_msg, queries))
216  {
218  return false;
219 
220  for (std::size_t i = 0; i < queries.size(); ++i)
221  {
222  // Configure planning scene
223  if (scene_msg.robot_model_name != planning_scene_->getRobotModel()->getName())
224  {
225  // Clear all geometry from the scene
226  planning_scene_->getWorldNonConst()->clearObjects();
227  planning_scene_->getCurrentStateNonConst().clearAttachedBodies();
228  planning_scene_->getCurrentStateNonConst().setToDefaultValues();
229 
230  planning_scene_->processPlanningSceneWorldMsg(scene_msg.world);
231  }
232  else
233  planning_scene_->usePlanningSceneMsg(scene_msg);
234 
235  // Calling query start events
236  for (QueryStartEventFunction& query_start_fn : query_start_fns_)
237  query_start_fn(queries[i].request, planning_scene_);
238 
239  ROS_INFO("Benchmarking query '%s' (%lu of %lu)", queries[i].name.c_str(), i + 1, queries.size());
240  ros::WallTime start_time = ros::WallTime::now();
242  double duration = (ros::WallTime::now() - start_time).toSec();
243 
244  for (QueryCompletionEventFunction& query_end_fn : query_end_fns_)
245  query_end_fn(queries[i].request, planning_scene_);
246 
247  writeOutput(queries[i], boost::posix_time::to_iso_extended_string(start_time.toBoost()), duration);
248  }
249 
250  return true;
251  }
252  return false;
253 }
254 
255 bool BenchmarkExecutor::queriesAndPlannersCompatible(const std::vector<BenchmarkRequest>& requests,
256  const std::map<std::string, std::vector<std::string>>& /*planners*/)
257 {
258  // Make sure that the planner interfaces can service the desired queries
259  for (const std::pair<const std::string, planning_pipeline::PlanningPipelinePtr>& pipeline_entry : planning_pipelines_)
260  {
261  for (const BenchmarkRequest& request : requests)
262  {
263  if (!pipeline_entry.second->getPlannerManager()->canServiceRequest(request.request))
264  {
265  ROS_ERROR("Interface '%s' in pipeline '%s' cannot service the benchmark request '%s'",
266  pipeline_entry.second->getPlannerPluginName().c_str(), pipeline_entry.first.c_str(),
267  request.name.c_str());
268  return false;
269  }
270  }
271  }
272 
273  return true;
274 }
275 
276 bool BenchmarkExecutor::initializeBenchmarks(const BenchmarkOptions& opts, moveit_msgs::PlanningScene& scene_msg,
277  std::vector<BenchmarkRequest>& requests)
278 {
280  return false;
281 
282  std::vector<StartState> start_states;
283  std::vector<PathConstraints> path_constraints;
284  std::vector<PathConstraints> goal_constraints;
285  std::vector<TrajectoryConstraints> traj_constraints;
286  std::vector<BenchmarkRequest> queries;
287 
288  if (!loadBenchmarkQueryData(opts, scene_msg, start_states, path_constraints, goal_constraints, traj_constraints,
289  queries))
290  {
291  ROS_ERROR("Failed to load benchmark query data");
292  return false;
293  }
294 
295  ROS_INFO("Benchmark loaded %lu starts, %lu goals, %lu path constraints, %lu trajectory constraints, and %lu queries",
296  start_states.size(), goal_constraints.size(), path_constraints.size(), traj_constraints.size(),
297  queries.size());
298 
299  moveit_msgs::WorkspaceParameters workspace_parameters = opts.getWorkspaceParameters();
300  // Make sure that workspace_parameters are set
301  if (workspace_parameters.min_corner.x == workspace_parameters.max_corner.x &&
302  workspace_parameters.min_corner.x == 0.0 &&
303  workspace_parameters.min_corner.y == workspace_parameters.max_corner.y &&
304  workspace_parameters.min_corner.y == 0.0 &&
305  workspace_parameters.min_corner.z == workspace_parameters.max_corner.z &&
306  workspace_parameters.min_corner.z == 0.0)
307  {
308  workspace_parameters.min_corner.x = workspace_parameters.min_corner.y = workspace_parameters.min_corner.z = -5.0;
309 
310  workspace_parameters.max_corner.x = workspace_parameters.max_corner.y = workspace_parameters.max_corner.z = 5.0;
311  }
312 
313  std::vector<double> goal_offset;
314  opts.getGoalOffsets(goal_offset);
315 
316  // Create the combinations of BenchmarkRequests
317 
318  // 1) Create requests for combinations of start states,
319  // goal constraints, and path constraints
320  for (PathConstraints& goal_constraint : goal_constraints)
321  {
322  // Common benchmark request properties
323  BenchmarkRequest brequest;
324  brequest.name = goal_constraint.name;
325  brequest.request.workspace_parameters = workspace_parameters;
326  brequest.request.goal_constraints = goal_constraint.constraints;
327  brequest.request.group_name = opts.getGroupName();
328  brequest.request.allowed_planning_time = opts.getTimeout();
329  brequest.request.num_planning_attempts = 1;
330 
331  if (brequest.request.goal_constraints.size() == 1 &&
332  brequest.request.goal_constraints[0].position_constraints.size() == 1 &&
333  brequest.request.goal_constraints[0].orientation_constraints.size() == 1 &&
334  brequest.request.goal_constraints[0].visibility_constraints.empty() &&
335  brequest.request.goal_constraints[0].joint_constraints.empty())
336  shiftConstraintsByOffset(brequest.request.goal_constraints[0], goal_offset);
337 
338  std::vector<BenchmarkRequest> request_combos;
339  createRequestCombinations(brequest, start_states, path_constraints, request_combos);
340  requests.insert(requests.end(), request_combos.begin(), request_combos.end());
341  }
342 
343  // 2) Existing queries are treated like goal constraints.
344  // Create all combos of query, start states, and path constraints
345  for (BenchmarkRequest& query : queries)
346  {
347  // Common benchmark request properties
348  BenchmarkRequest brequest;
349  brequest.name = query.name;
350  brequest.request = query.request;
351  brequest.request.group_name = opts.getGroupName();
352  brequest.request.allowed_planning_time = opts.getTimeout();
353  brequest.request.num_planning_attempts = 1;
354 
355  // Make sure that workspace_parameters are set
356  if (brequest.request.workspace_parameters.min_corner.x == brequest.request.workspace_parameters.max_corner.x &&
357  brequest.request.workspace_parameters.min_corner.x == 0.0 &&
358  brequest.request.workspace_parameters.min_corner.y == brequest.request.workspace_parameters.max_corner.y &&
359  brequest.request.workspace_parameters.min_corner.y == 0.0 &&
360  brequest.request.workspace_parameters.min_corner.z == brequest.request.workspace_parameters.max_corner.z &&
361  brequest.request.workspace_parameters.min_corner.z == 0.0)
362  {
363  // ROS_WARN("Workspace parameters are not set for request %s. Setting defaults", queries[i].name.c_str());
364  brequest.request.workspace_parameters = workspace_parameters;
365  }
366 
367  // Create all combinations of start states and path constraints
368  std::vector<BenchmarkRequest> request_combos;
369  createRequestCombinations(brequest, start_states, path_constraints, request_combos);
370  requests.insert(requests.end(), request_combos.begin(), request_combos.end());
371  }
372 
373  // 3) Trajectory constraints are also treated like goal constraints
374  for (TrajectoryConstraints& traj_constraint : traj_constraints)
375  {
376  // Common benchmark request properties
377  BenchmarkRequest brequest;
378  brequest.name = traj_constraint.name;
379  brequest.request.trajectory_constraints = traj_constraint.constraints;
380  brequest.request.group_name = opts.getGroupName();
381  brequest.request.allowed_planning_time = opts.getTimeout();
382  brequest.request.num_planning_attempts = 1;
383 
384  if (brequest.request.trajectory_constraints.constraints.size() == 1 &&
385  brequest.request.trajectory_constraints.constraints[0].position_constraints.size() == 1 &&
386  brequest.request.trajectory_constraints.constraints[0].orientation_constraints.size() == 1 &&
387  brequest.request.trajectory_constraints.constraints[0].visibility_constraints.empty() &&
388  brequest.request.trajectory_constraints.constraints[0].joint_constraints.empty())
389  shiftConstraintsByOffset(brequest.request.trajectory_constraints.constraints[0], goal_offset);
390 
391  std::vector<BenchmarkRequest> request_combos;
392  std::vector<PathConstraints> no_path_constraints;
393  createRequestCombinations(brequest, start_states, no_path_constraints, request_combos);
394  requests.insert(requests.end(), request_combos.begin(), request_combos.end());
395  }
396 
397  options_ = opts;
398  return true;
399 }
400 
401 bool BenchmarkExecutor::loadBenchmarkQueryData(const BenchmarkOptions& opts, moveit_msgs::PlanningScene& scene_msg,
402  std::vector<StartState>& start_states,
403  std::vector<PathConstraints>& path_constraints,
404  std::vector<PathConstraints>& goal_constraints,
405  std::vector<TrajectoryConstraints>& traj_constraints,
406  std::vector<BenchmarkRequest>& queries)
407 {
408  try
409  {
411  warehouse_connection->setParams(opts.getHostName(), opts.getPort(), 20);
412  if (warehouse_connection->connect())
413  {
414  pss_ = new moveit_warehouse::PlanningSceneStorage(warehouse_connection);
415  psws_ = new moveit_warehouse::PlanningSceneWorldStorage(warehouse_connection);
416  rs_ = new moveit_warehouse::RobotStateStorage(warehouse_connection);
417  cs_ = new moveit_warehouse::ConstraintsStorage(warehouse_connection);
418  tcs_ = new moveit_warehouse::TrajectoryConstraintsStorage(warehouse_connection);
419  }
420  else
421  {
422  ROS_ERROR("Failed to connect to DB");
423  return false;
424  }
425  }
426  catch (std::exception& e)
427  {
428  ROS_ERROR("Failed to initialize benchmark server: '%s'", e.what());
429  return false;
430  }
431 
432  return loadPlanningScene(opts.getSceneName(), scene_msg) && loadStates(opts.getStartStateRegex(), start_states) &&
433  loadPathConstraints(opts.getGoalConstraintRegex(), goal_constraints) &&
434  loadPathConstraints(opts.getPathConstraintRegex(), path_constraints) &&
435  loadTrajectoryConstraints(opts.getTrajectoryConstraintRegex(), traj_constraints) &&
436  loadQueries(opts.getQueryRegex(), opts.getSceneName(), queries);
437 }
438 
439 void BenchmarkExecutor::shiftConstraintsByOffset(moveit_msgs::Constraints& constraints,
440  const std::vector<double>& offset)
441 {
442  Eigen::Isometry3d offset_tf(Eigen::AngleAxis<double>(offset[3], Eigen::Vector3d::UnitX()) *
443  Eigen::AngleAxis<double>(offset[4], Eigen::Vector3d::UnitY()) *
444  Eigen::AngleAxis<double>(offset[5], Eigen::Vector3d::UnitZ()));
445  offset_tf.translation() = Eigen::Vector3d(offset[0], offset[1], offset[2]);
446 
447  geometry_msgs::Pose constraint_pose_msg;
448  constraint_pose_msg.position = constraints.position_constraints[0].constraint_region.primitive_poses[0].position;
449  constraint_pose_msg.orientation = constraints.orientation_constraints[0].orientation;
450  Eigen::Isometry3d constraint_pose;
451  tf2::fromMsg(constraint_pose_msg, constraint_pose);
452 
453  Eigen::Isometry3d new_pose = constraint_pose * offset_tf;
454  geometry_msgs::Pose new_pose_msg;
455  new_pose_msg = tf2::toMsg(new_pose);
456 
457  constraints.position_constraints[0].constraint_region.primitive_poses[0].position = new_pose_msg.position;
458  constraints.orientation_constraints[0].orientation = new_pose_msg.orientation;
459 }
460 
462  const std::vector<StartState>& start_states,
463  const std::vector<PathConstraints>& path_constraints,
464  std::vector<BenchmarkRequest>& requests)
465 {
466  // Use default start state
467  if (start_states.empty())
468  {
469  // Adding path constraints
470  for (const PathConstraints& path_constraint : path_constraints)
471  {
472  BenchmarkRequest new_brequest = brequest;
473  new_brequest.request.path_constraints = path_constraint.constraints[0];
474  new_brequest.name = brequest.name + "_" + path_constraint.name;
475  requests.push_back(new_brequest);
476  }
477 
478  if (path_constraints.empty())
479  requests.push_back(brequest);
480  }
481  else // Create a request for each start state specified
482  {
483  for (const StartState& start_state : start_states)
484  {
485  // Skip start states that have the same name as the goal
486  if (start_state.name == brequest.name)
487  continue;
488 
489  BenchmarkRequest new_brequest = brequest;
490  new_brequest.request.start_state = start_state.state;
491 
492  // Duplicate the request for each of the path constraints
493  for (const PathConstraints& path_constraint : path_constraints)
494  {
495  new_brequest.request.path_constraints = path_constraint.constraints[0];
496  new_brequest.name = start_state.name + "_" + new_brequest.name + "_" + path_constraint.name;
497  requests.push_back(new_brequest);
498  }
499 
500  if (path_constraints.empty())
501  {
502  new_brequest.name = start_state.name + "_" + brequest.name;
503  requests.push_back(new_brequest);
504  }
505  }
506  }
507 }
508 
510  const std::map<std::string, std::vector<std::string>>& pipeline_configurations, const std::string& group_name)
511 {
512  // Make sure planner plugins exist
513  for (const std::pair<const std::string, std::vector<std::string>>& pipeline_config_entry : pipeline_configurations)
514  {
515  bool pipeline_exists = false;
516  for (const std::pair<const std::string, planning_pipeline::PlanningPipelinePtr>& pipeline_entry :
518  {
519  pipeline_exists = pipeline_entry.first == pipeline_config_entry.first;
520  if (pipeline_exists)
521  break;
522  }
523 
524  if (!pipeline_exists)
525  {
526  ROS_ERROR("Planning pipeline '%s' does NOT exist", pipeline_config_entry.first.c_str());
527  return false;
528  }
529  }
530 
531  // Make sure planners exist within those pipelines
532  for (const std::pair<const std::string, std::vector<std::string>>& entry : pipeline_configurations)
533  {
534  planning_interface::PlannerManagerPtr pm = planning_pipelines_[entry.first]->getPlannerManager();
535  const planning_interface::PlannerConfigurationMap& config_map = pm->getPlannerConfigurations();
536 
537  // if the planner is chomp or stomp skip this function and return true for checking planner configurations for the
538  // planning group otherwise an error occurs, because for OMPL a specific planning algorithm needs to be defined for
539  // a planning group, whereas with STOMP and CHOMP this is not necessary
540  if (pm->getDescription().compare("stomp") || pm->getDescription().compare("chomp"))
541  continue;
542 
543  for (std::size_t i = 0; i < entry.second.size(); ++i)
544  {
545  bool planner_exists = false;
546  for (const std::pair<const std::string, planning_interface::PlannerConfigurationSettings>& config_entry :
547  config_map)
548  {
549  std::string planner_name = group_name + "[" + entry.second[i] + "]";
550  planner_exists = (config_entry.second.group == group_name && config_entry.second.name == planner_name);
551  }
552 
553  if (!planner_exists)
554  {
555  ROS_ERROR("Planner '%s' does NOT exist for group '%s' in pipeline '%s'", entry.second[i].c_str(),
556  group_name.c_str(), entry.first.c_str());
557  std::cout << "There are " << config_map.size() << " planner entries: " << std::endl;
558  for (const auto& config_map_entry : config_map)
559  std::cout << config_map_entry.second.name << std::endl;
560  return false;
561  }
562  }
563  }
564 
565  return true;
566 }
567 
568 bool BenchmarkExecutor::loadPlanningScene(const std::string& scene_name, moveit_msgs::PlanningScene& scene_msg)
569 {
570  bool ok = false;
571  try
572  {
573  if (pss_->hasPlanningScene(scene_name)) // whole planning scene
574  {
576  ok = pss_->getPlanningScene(pswm, scene_name);
577  scene_msg = static_cast<moveit_msgs::PlanningScene>(*pswm);
578 
579  if (!ok)
580  ROS_ERROR("Failed to load planning scene '%s'", scene_name.c_str());
581  }
582  else if (psws_->hasPlanningSceneWorld(scene_name)) // Just the world (no robot)
583  {
585  ok = psws_->getPlanningSceneWorld(pswwm, scene_name);
586  scene_msg.world = static_cast<moveit_msgs::PlanningSceneWorld>(*pswwm);
587  scene_msg.robot_model_name =
588  "NO ROBOT INFORMATION. ONLY WORLD GEOMETRY"; // this will be fixed when running benchmark
589 
590  if (!ok)
591  ROS_ERROR("Failed to load planning scene '%s'", scene_name.c_str());
592  }
593  else
594  ROS_ERROR("Failed to find planning scene '%s'", scene_name.c_str());
595  }
596  catch (std::exception& ex)
597  {
598  ROS_ERROR("Error loading planning scene: %s", ex.what());
599  }
600  ROS_INFO("Loaded planning scene successfully");
601  return ok;
602 }
603 
604 bool BenchmarkExecutor::loadQueries(const std::string& regex, const std::string& scene_name,
605  std::vector<BenchmarkRequest>& queries)
606 {
607  if (regex.empty())
608  return true;
609 
610  std::vector<std::string> query_names;
611  try
612  {
613  pss_->getPlanningQueriesNames(regex, query_names, scene_name);
614  }
615  catch (std::exception& ex)
616  {
617  ROS_ERROR("Error loading motion planning queries: %s", ex.what());
618  return false;
619  }
620 
621  if (query_names.empty())
622  {
623  ROS_ERROR("Scene '%s' has no associated queries", scene_name.c_str());
624  return false;
625  }
626 
627  for (const std::string& query_name : query_names)
628  {
630  try
631  {
632  pss_->getPlanningQuery(planning_query, scene_name, query_name);
633  }
634  catch (std::exception& ex)
635  {
636  ROS_ERROR("Error loading motion planning query '%s': %s", query_name.c_str(), ex.what());
637  continue;
638  }
639 
640  BenchmarkRequest query;
641  query.name = query_name;
642  query.request = static_cast<moveit_msgs::MotionPlanRequest>(*planning_query);
643  queries.push_back(query);
644  }
645  ROS_INFO("Loaded queries successfully");
646  return true;
647 }
648 
649 bool BenchmarkExecutor::loadStates(const std::string& regex, std::vector<StartState>& start_states)
650 {
651  if (!regex.empty())
652  {
653  boost::regex start_regex(regex);
654  std::vector<std::string> state_names;
655  rs_->getKnownRobotStates(state_names);
656  for (const std::string& state_name : state_names)
657  {
658  boost::cmatch match;
659  if (boost::regex_match(state_name.c_str(), match, start_regex))
660  {
662  try
663  {
664  if (rs_->getRobotState(robot_state, state_name))
665  {
666  StartState start_state;
667  start_state.state = moveit_msgs::RobotState(*robot_state);
668  start_state.name = state_name;
669  start_states.push_back(start_state);
670  }
671  }
672  catch (std::exception& ex)
673  {
674  ROS_ERROR("Runtime error when loading state '%s': %s", state_name.c_str(), ex.what());
675  continue;
676  }
677  }
678  }
679 
680  if (start_states.empty())
681  ROS_WARN("No stored states matched the provided start state regex: '%s'", regex.c_str());
682  }
683  ROS_INFO("Loaded states successfully");
684  return true;
685 }
686 
687 bool BenchmarkExecutor::loadPathConstraints(const std::string& regex, std::vector<PathConstraints>& constraints)
688 {
689  if (!regex.empty())
690  {
691  std::vector<std::string> cnames;
692  cs_->getKnownConstraints(regex, cnames);
693 
694  for (const std::string& cname : cnames)
695  {
697  try
698  {
699  if (cs_->getConstraints(constr, cname))
700  {
701  PathConstraints constraint;
702  constraint.constraints.push_back(*constr);
703  constraint.name = cname;
704  constraints.push_back(constraint);
705  }
706  }
707  catch (std::exception& ex)
708  {
709  ROS_ERROR("Runtime error when loading path constraint '%s': %s", cname.c_str(), ex.what());
710  continue;
711  }
712  }
713 
714  if (constraints.empty())
715  ROS_WARN("No path constraints found that match regex: '%s'", regex.c_str());
716  else
717  ROS_INFO("Loaded path constraints successfully");
718  }
719  return true;
720 }
721 
722 bool BenchmarkExecutor::loadTrajectoryConstraints(const std::string& regex,
723  std::vector<TrajectoryConstraints>& constraints)
724 {
725  if (!regex.empty())
726  {
727  std::vector<std::string> cnames;
728  tcs_->getKnownTrajectoryConstraints(regex, cnames);
729 
730  for (const std::string& cname : cnames)
731  {
733  try
734  {
735  if (tcs_->getTrajectoryConstraints(constr, cname))
736  {
737  TrajectoryConstraints constraint;
738  constraint.constraints = *constr;
739  constraint.name = cname;
740  constraints.push_back(constraint);
741  }
742  }
743  catch (std::exception& ex)
744  {
745  ROS_ERROR("Runtime error when loading trajectory constraint '%s': %s", cname.c_str(), ex.what());
746  continue;
747  }
748  }
749 
750  if (constraints.empty())
751  ROS_WARN("No trajectory constraints found that match regex: '%s'", regex.c_str());
752  else
753  ROS_INFO("Loaded trajectory constraints successfully");
754  }
755  return true;
756 }
757 
758 void BenchmarkExecutor::runBenchmark(moveit_msgs::MotionPlanRequest request,
759  const std::map<std::string, std::vector<std::string>>& pipeline_map, int runs)
760 {
761  benchmark_data_.clear();
762 
763  unsigned int num_planners = 0;
764  for (const std::pair<const std::string, std::vector<std::string>>& pipeline_entry : pipeline_map)
765  num_planners += pipeline_entry.second.size();
766 
767  boost_progress_display progress(num_planners * runs, std::cout);
768 
769  // Iterate through all planning pipelines
770  for (const std::pair<const std::string, std::vector<std::string>>& pipeline_entry : pipeline_map)
771  {
772  planning_pipeline::PlanningPipelinePtr planning_pipeline = planning_pipelines_[pipeline_entry.first];
773  // Use the planning context if the pipeline only contains the planner plugin
774  bool use_planning_context = planning_pipeline->getAdapterPluginNames().empty();
775  // Iterate through all planners configured for the pipeline
776  for (const std::string& planner_id : pipeline_entry.second)
777  {
778  // This container stores all of the benchmark data for this planner
779  PlannerBenchmarkData planner_data(runs);
780  // This vector stores all motion plan results for further evaluation
781  std::vector<planning_interface::MotionPlanDetailedResponse> responses(runs);
782  std::vector<bool> solved(runs);
783 
784  request.planner_id = planner_id;
785 
786  // Planner start events
787  for (PlannerStartEventFunction& planner_start_fn : planner_start_fns_)
788  planner_start_fn(request, planner_data);
789 
790  planning_interface::PlanningContextPtr planning_context;
791  if (use_planning_context)
792  planning_context = planning_pipeline->getPlannerManager()->getPlanningContext(planning_scene_, request);
793 
794  // Iterate runs
795  for (int j = 0; j < runs; ++j)
796  {
797  // Pre-run events
798  for (PreRunEventFunction& pre_event_fn : pre_event_fns_)
799  pre_event_fn(request);
800 
801  // Solve problem
803  if (use_planning_context)
804  {
805  solved[j] = planning_context->solve(responses[j]);
806  }
807  else
808  {
809  // The planning pipeline does not support MotionPlanDetailedResponse
811  solved[j] = planning_pipeline->generatePlan(planning_scene_, request, response);
812  responses[j].error_code_ = response.error_code_;
813  if (response.trajectory_)
814  {
815  responses[j].description_.push_back("plan");
816  responses[j].trajectory_.push_back(response.trajectory_);
817  responses[j].processing_time_.push_back(response.planning_time_);
818  }
819  }
820  double total_time = (ros::WallTime::now() - start).toSec();
821 
822  // Collect data
824 
825  // Post-run events
826  for (PostRunEventFunction& post_event_fn : post_event_fns_)
827  post_event_fn(request, responses[j], planner_data[j]);
828  collectMetrics(planner_data[j], responses[j], solved[j], total_time);
829  double metrics_time = (ros::WallTime::now() - start).toSec();
830  ROS_DEBUG("Spent %lf seconds collecting metrics", metrics_time);
831 
832  ++progress;
833  }
834 
835  computeAveragePathSimilarities(planner_data, responses, solved);
836 
837  // Planner completion events
838  for (PlannerCompletionEventFunction& planner_completion_fn : planner_completion_fns_)
839  planner_completion_fn(request, planner_data);
840 
841  benchmark_data_.push_back(planner_data);
842  }
843  }
844 }
845 
847  const planning_interface::MotionPlanDetailedResponse& mp_res, bool solved,
848  double total_time)
849 {
850  metrics["time REAL"] = moveit::core::toString(total_time);
851  metrics["solved BOOLEAN"] = boost::lexical_cast<std::string>(solved);
852 
853  if (solved)
854  {
855  // Analyzing the trajectory(ies) geometrically
856  double traj_len = 0.0; // trajectory length
857  double clearance = 0.0; // trajectory clearance (average)
858  double smoothness = 0.0; // trajectory smoothness (average)
859  bool correct = true; // entire trajectory collision free and in bounds
860 
861  double process_time = total_time;
862  for (std::size_t j = 0; j < mp_res.trajectory_.size(); ++j)
863  {
864  correct = true;
865  traj_len = 0.0;
866  clearance = 0.0;
867  smoothness = 0.0;
868  const robot_trajectory::RobotTrajectory& p = *mp_res.trajectory_[j];
869 
870  // compute path length
871  for (std::size_t k = 1; k < p.getWayPointCount(); ++k)
872  traj_len += p.getWayPoint(k - 1).distance(p.getWayPoint(k));
873 
874  // compute correctness and clearance
876  for (std::size_t k = 0; k < p.getWayPointCount(); ++k)
877  {
879  planning_scene_->checkCollisionUnpadded(req, res, p.getWayPoint(k));
880  if (res.collision)
881  correct = false;
882  if (!p.getWayPoint(k).satisfiesBounds())
883  correct = false;
884  double d = planning_scene_->distanceToCollisionUnpadded(p.getWayPoint(k));
885  if (d > 0.0) // in case of collision, distance is negative
886  clearance += d;
887  }
888  clearance /= (double)p.getWayPointCount();
889 
890  // compute smoothness
891  if (p.getWayPointCount() > 2)
892  {
893  double a = p.getWayPoint(0).distance(p.getWayPoint(1));
894  for (std::size_t k = 2; k < p.getWayPointCount(); ++k)
895  {
896  // view the path as a sequence of segments, and look at the triangles it forms:
897  // s1
898  // /\ s4
899  // a / \ b |
900  // / \ |
901  // /......\_______|
902  // s0 c s2 s3
903  //
904 
905  // use Pythagoras generalized theorem to find the cos of the angle between segments a and b
906  double b = p.getWayPoint(k - 1).distance(p.getWayPoint(k));
907  double cdist = p.getWayPoint(k - 2).distance(p.getWayPoint(k));
908  double acos_value = (a * a + b * b - cdist * cdist) / (2.0 * a * b);
909  if (acos_value > -1.0 && acos_value < 1.0)
910  {
911  // the smoothness is actually the outside angle of the one we compute
912  double angle = (boost::math::constants::pi<double>() - acos(acos_value));
913 
914  // and we normalize by the length of the segments
915  double u = 2.0 * angle;
916  smoothness += u * u;
917  }
918  a = b;
919  }
920  smoothness /= (double)p.getWayPointCount();
921  }
922  metrics["path_" + mp_res.description_[j] + "_correct BOOLEAN"] = boost::lexical_cast<std::string>(correct);
923  metrics["path_" + mp_res.description_[j] + "_length REAL"] = moveit::core::toString(traj_len);
924  metrics["path_" + mp_res.description_[j] + "_clearance REAL"] = moveit::core::toString(clearance);
925  metrics["path_" + mp_res.description_[j] + "_smoothness REAL"] = moveit::core::toString(smoothness);
926  metrics["path_" + mp_res.description_[j] + "_time REAL"] = moveit::core::toString(mp_res.processing_time_[j]);
927 
928  if (j == mp_res.trajectory_.size() - 1)
929  {
930  metrics["final_path_correct BOOLEAN"] = boost::lexical_cast<std::string>(correct);
931  metrics["final_path_length REAL"] = moveit::core::toString(traj_len);
932  metrics["final_path_clearance REAL"] = moveit::core::toString(clearance);
933  metrics["final_path_smoothness REAL"] = moveit::core::toString(smoothness);
934  metrics["final_path_time REAL"] = moveit::core::toString(mp_res.processing_time_[j]);
935  }
936  process_time -= mp_res.processing_time_[j];
937  }
938  if (process_time <= 0.0)
939  process_time = 0.0;
940  metrics["process_time REAL"] = moveit::core::toString(process_time);
941  }
942 }
943 
945  PlannerBenchmarkData& planner_data, const std::vector<planning_interface::MotionPlanDetailedResponse>& responses,
946  const std::vector<bool>& solved)
947 {
948  ROS_INFO("Computing result path similarity");
949  const size_t result_count = planner_data.size();
950  size_t unsolved = std::count_if(solved.begin(), solved.end(), [](bool s) { return !s; });
951  std::vector<double> average_distances(responses.size());
952  for (size_t first_traj_i = 0; first_traj_i < result_count; ++first_traj_i)
953  {
954  // If trajectory was not solved there is no valid average distance so it's set to max double only
955  if (!solved[first_traj_i])
956  {
957  average_distances[first_traj_i] = std::numeric_limits<double>::max();
958  continue;
959  }
960  // Iterate all result trajectories that haven't been compared yet
961  for (size_t second_traj_i = first_traj_i + 1; second_traj_i < result_count; ++second_traj_i)
962  {
963  // Ignore if other result has not been solved
964  if (!solved[second_traj_i])
965  continue;
966 
967  // Get final trajectories
968  const robot_trajectory::RobotTrajectory& traj_first = *responses[first_traj_i].trajectory_.back();
969  const robot_trajectory::RobotTrajectory& traj_second = *responses[second_traj_i].trajectory_.back();
970 
971  // Compute trajectory distance
972  double trajectory_distance;
973  if (!computeTrajectoryDistance(traj_first, traj_second, trajectory_distance))
974  continue;
975 
976  // Add average distance to counters of both trajectories
977  average_distances[first_traj_i] += trajectory_distance;
978  average_distances[second_traj_i] += trajectory_distance;
979  }
980  // Normalize average distance by number of actual comparisons
981  average_distances[first_traj_i] /= result_count - unsolved - 1;
982  }
983 
984  // Store results in planner_data
985  for (size_t i = 0; i < result_count; ++i)
986  planner_data[i]["average_waypoint_distance REAL"] = moveit::core::toString(average_distances[i]);
987 }
988 
990  const robot_trajectory::RobotTrajectory& traj_second,
991  double& result_distance)
992 {
993  // Abort if trajectories are empty
994  if (traj_first.empty() || traj_second.empty())
995  return false;
996 
997  // Waypoint counter
998  size_t pos_first = 0;
999  size_t pos_second = 0;
1000  const size_t max_pos_first = traj_first.getWayPointCount() - 1;
1001  const size_t max_pos_second = traj_second.getWayPointCount() - 1;
1002 
1003  // Compute total distance between pairwise waypoints of both trajectories.
1004  // The selection of waypoint pairs is based on what steps results in the minimal distance between the next pair of
1005  // waypoints. We first check what steps are still possible or if we reached the end of the trajectories. Then we
1006  // compute the pairwise waypoint distances of the pairs from increasing both, the first, or the second trajectory.
1007  // Finally we select the pair that results in the minimal distance, summarize the total distance and iterate
1008  // accordingly. After that we compute the average trajectory distance by normalizing over the number of steps.
1009  double total_distance = 0;
1010  size_t steps = 0;
1011  double current_distance = traj_first.getWayPoint(pos_first).distance(traj_second.getWayPoint(pos_second));
1012  while (true)
1013  {
1014  // Keep track of total distance and number of comparisons
1015  total_distance += current_distance;
1016  ++steps;
1017  if (pos_first == max_pos_first && pos_second == max_pos_second) // end reached
1018  break;
1019 
1020  // Determine what steps are still possible
1021  bool can_up_first = pos_first < max_pos_first;
1022  bool can_up_second = pos_second < max_pos_second;
1023  bool can_up_both = can_up_first && can_up_second;
1024 
1025  // Compute pair-wise waypoint distances (increasing both, first, or second trajectories).
1026  double up_both = std::numeric_limits<double>::max();
1027  double up_first = std::numeric_limits<double>::max();
1028  double up_second = std::numeric_limits<double>::max();
1029  if (can_up_both)
1030  up_both = traj_first.getWayPoint(pos_first + 1).distance(traj_second.getWayPoint(pos_second + 1));
1031  if (can_up_first)
1032  up_first = traj_first.getWayPoint(pos_first + 1).distance(traj_second.getWayPoint(pos_second));
1033  if (can_up_second)
1034  up_second = traj_first.getWayPoint(pos_first).distance(traj_second.getWayPoint(pos_second + 1));
1035 
1036  // Select actual step, store new distance value and iterate trajectory positions
1037  if (can_up_both && up_both < up_first && up_both < up_second)
1038  {
1039  ++pos_first;
1040  ++pos_second;
1041  current_distance = up_both;
1042  }
1043  else if ((can_up_first && up_first < up_second) || !can_up_second)
1044  {
1045  ++pos_first;
1046  current_distance = up_first;
1047  }
1048  else if (can_up_second)
1049  {
1050  ++pos_second;
1051  current_distance = up_second;
1052  }
1053  }
1054  // Normalize trajectory distance by number of comparison steps
1055  result_distance = total_distance / static_cast<double>(steps);
1056  return true;
1057 }
1058 
1059 void BenchmarkExecutor::writeOutput(const BenchmarkRequest& brequest, const std::string& start_time,
1060  double benchmark_duration)
1061 {
1062  const std::map<std::string, std::vector<std::string>>& pipelines = options_.getPlanningPipelineConfigurations();
1063 
1064  size_t num_planners = 0;
1065  for (const std::pair<const std::string, std::vector<std::string>>& pipeline : pipelines)
1066  num_planners += pipeline.second.size();
1067 
1068  std::string hostname = getHostname();
1069  if (hostname.empty())
1070  hostname = "UNKNOWN";
1071 
1072  std::string filename = options_.getOutputDirectory();
1073  if (!filename.empty() && filename[filename.size() - 1] != '/')
1074  filename.append("/");
1075 
1076  // Ensure directories exist
1077  boost::filesystem::create_directories(filename);
1078 
1079  filename += (options_.getBenchmarkName().empty() ? "" : options_.getBenchmarkName() + "_") + brequest.name + "_" +
1080  getHostname() + "_" + start_time + ".log";
1081  std::ofstream out(filename.c_str());
1082  if (!out)
1083  {
1084  ROS_ERROR("Failed to open '%s' for benchmark output", filename.c_str());
1085  return;
1086  }
1087 
1088  out << "MoveIt version " << MOVEIT_VERSION_STR << std::endl;
1089  out << "Experiment " << brequest.name << std::endl;
1090  out << "Running on " << hostname << std::endl;
1091  out << "Starting at " << start_time << std::endl;
1092 
1093  // Experiment setup
1094  moveit_msgs::PlanningScene scene_msg;
1095  planning_scene_->getPlanningSceneMsg(scene_msg);
1096  out << "<<<|" << std::endl;
1097  out << "Motion plan request:" << std::endl << brequest.request << std::endl;
1098  out << "Planning scene: " << std::endl << scene_msg << std::endl << "|>>>" << std::endl;
1099 
1100  // Not writing optional cpu information
1101 
1102  // The real random seed is unknown. Writing a fake value
1103  out << "0 is the random seed" << std::endl;
1104  out << brequest.request.allowed_planning_time << " seconds per run" << std::endl;
1105  // There is no memory cap
1106  out << "-1 MB per run" << std::endl;
1107  out << options_.getNumRuns() << " runs per planner" << std::endl;
1108  out << benchmark_duration << " seconds spent to collect the data" << std::endl;
1109 
1110  // No enum types
1111  out << "0 enum types" << std::endl;
1112 
1113  out << num_planners << " planners" << std::endl;
1114 
1115  size_t run_id = 0;
1116  for (const std::pair<const std::string, std::vector<std::string>>& pipeline : pipelines)
1117  {
1118  for (std::size_t i = 0; i < pipeline.second.size(); ++i, ++run_id)
1119  {
1120  // Write the name of the planner and the used pipeline
1121  out << pipeline.second[i] << " (" << pipeline.first << ")" << std::endl;
1122 
1123  // in general, we could have properties specific for a planner;
1124  // right now, we do not include such properties
1125  out << "0 common properties" << std::endl;
1126 
1127  // Create a list of the benchmark properties for this planner
1128  std::set<std::string> properties_set;
1129  for (PlannerRunData& planner_run_data : benchmark_data_[run_id]) // each run of this planner
1130  for (PlannerRunData::const_iterator pit = planner_run_data.begin(); pit != planner_run_data.end();
1131  ++pit) // each benchmark property of the given run
1132  properties_set.insert(pit->first);
1133 
1134  // Writing property list
1135  out << properties_set.size() << " properties for each run" << std::endl;
1136  for (const std::string& property : properties_set)
1137  out << property << std::endl;
1138 
1139  // Number of runs
1140  out << benchmark_data_[run_id].size() << " runs" << std::endl;
1141 
1142  // And the benchmark properties
1143  for (PlannerRunData& planner_run_data : benchmark_data_[run_id]) // each run of this planner
1144  {
1145  // Write out properties in the order we listed them above
1146  for (const std::string& property : properties_set)
1147  {
1148  // Make sure this run has this property
1149  PlannerRunData::const_iterator runit = planner_run_data.find(property);
1150  if (runit != planner_run_data.end())
1151  out << runit->second;
1152  out << "; ";
1153  }
1154  out << std::endl; // end of the run
1155  }
1156  out << "." << std::endl; // end the planner
1157  }
1158  }
1159 
1160  out.close();
1161  ROS_INFO("Benchmark results saved to '%s'", filename.c_str());
1162 }
response
const std::string response
moveit_warehouse::PlanningSceneStorage::getPlanningScene
bool getPlanningScene(PlanningSceneWithMetadata &scene_m, const std::string &scene_name) const
moveit_ros_benchmarks::BenchmarkExecutor::query_start_fns_
std::vector< QueryStartEventFunction > query_start_fns_
Definition: BenchmarkExecutor.h:285
moveit_ros_benchmarks::BenchmarkExecutor::planning_scene_
planning_scene::PlanningScenePtr planning_scene_
Definition: BenchmarkExecutor.h:273
boost_progress_display
boost::progress_display boost_progress_display
Definition: BenchmarkExecutor.cpp:52
moveit::core::RobotState::distance
double distance(const RobotState &other) const
moveit_ros_benchmarks::BenchmarkExecutor::runBenchmark
void runBenchmark(moveit_msgs::MotionPlanRequest request, const std::map< std::string, std::vector< std::string >> &planners, int runs)
Execute the given motion plan request on the set of planners for the set number of runs.
Definition: BenchmarkExecutor.cpp:758
moveit_ros_benchmarks::BenchmarkExecutor::planning_pipelines_
std::map< std::string, planning_pipeline::PlanningPipelinePtr > planning_pipelines_
Definition: BenchmarkExecutor.h:277
robot_trajectory::RobotTrajectory::getWayPointCount
std::size_t getWayPointCount() const
lexical_casts.h
moveit_ros_benchmarks::BenchmarkExecutor::PlannerStartEventFunction
boost::function< void(const moveit_msgs::MotionPlanRequest &request, PlannerBenchmarkData &benchmark_data)> PlannerStartEventFunction
Definition: BenchmarkExecutor.h:144
duration
std::chrono::system_clock::duration duration
moveit_ros_benchmarks::BenchmarkExecutor::queriesAndPlannersCompatible
bool queriesAndPlannersCompatible(const std::vector< BenchmarkRequest > &requests, const std::map< std::string, std::vector< std::string >> &planners)
Check that the given requests can be run on the set of planner plugins and algorithms.
Definition: BenchmarkExecutor.cpp:255
boost::shared_ptr< DatabaseConnection >
moveit_ros_benchmarks::BenchmarkOptions::getStartStateRegex
const std::string & getStartStateRegex() const
Get the regex expression for matching the names of all start states to plan from.
Definition: BenchmarkOptions.cpp:119
angle
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
moveit_warehouse::RobotStateStorage
moveit_ros_benchmarks::BenchmarkExecutor::runBenchmarks
virtual bool runBenchmarks(const BenchmarkOptions &opts)
Definition: BenchmarkExecutor.cpp:204
planning_interface::MotionPlanResponse
tf2_eigen.h
tf2::fromMsg
void fromMsg(const A &, B &b)
moveit_ros_benchmarks::BenchmarkExecutor::plannerConfigurationsExist
bool plannerConfigurationsExist(const std::map< std::string, std::vector< std::string >> &planners, const std::string &group_name)
Check that the desired planner plugins and algorithms exist for the given group.
Definition: BenchmarkExecutor.cpp:509
moveit_ros_benchmarks::BenchmarkOptions::getGroupName
const std::string & getGroupName() const
Get the name of the planning group to run the benchmark with.
Definition: BenchmarkOptions.cpp:104
moveit_ros_benchmarks::BenchmarkExecutor::tcs_
moveit_warehouse::TrajectoryConstraintsStorage * tcs_
Definition: BenchmarkExecutor.h:270
s
XmlRpcServer s
moveit_ros_benchmarks::BenchmarkExecutor::writeOutput
virtual void writeOutput(const BenchmarkRequest &brequest, const std::string &start_time, double benchmark_duration)
Definition: BenchmarkExecutor.cpp:1059
moveit_warehouse::PlanningSceneWorldStorage
moveit_warehouse::PlanningSceneWorldStorage::hasPlanningSceneWorld
bool hasPlanningSceneWorld(const std::string &name) const
warehouse_ros::DatabaseLoader::loadDatabase
DatabaseConnection::Ptr loadDatabase()
ROS_DEBUG
#define ROS_DEBUG(...)
moveit_ros_benchmarks::BenchmarkOptions::getHostName
const std::string & getHostName() const
Get the name of the warehouse database host server.
Definition: BenchmarkOptions.cpp:74
moveit_warehouse::TrajectoryConstraintsStorage::getTrajectoryConstraints
bool getTrajectoryConstraints(TrajectoryConstraintsWithMetadata &msg_m, const std::string &name, const std::string &robot="", const std::string &group="") const
planning_scene_monitor::PlanningSceneMonitor::getPlanningScene
const planning_scene::PlanningScenePtr & getPlanningScene()
moveit_ros_benchmarks::BenchmarkExecutor::TrajectoryConstraints::name
std::string name
Definition: BenchmarkExecutor.h:199
moveit_ros_benchmarks::BenchmarkExecutor::computeTrajectoryDistance
bool computeTrajectoryDistance(const robot_trajectory::RobotTrajectory &traj_first, const robot_trajectory::RobotTrajectory &traj_second, double &result_distance)
Definition: BenchmarkExecutor.cpp:989
moveit_warehouse::ConstraintsStorage
moveit_ros_benchmarks::BenchmarkExecutor::options_
BenchmarkOptions options_
Definition: BenchmarkExecutor.h:275
robot_trajectory::RobotTrajectory
planning_interface::PlannerConfigurationMap
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
moveit_warehouse::PlanningSceneWorldStorage::getPlanningSceneWorld
bool getPlanningSceneWorld(PlanningSceneWorldWithMetadata &msg_m, const std::string &name) const
planning_scene_monitor::PlanningSceneMonitor
collision_detection::CollisionRequest
ok
ROSCPP_DECL bool ok()
moveit_warehouse::TrajectoryConstraintsStorage
moveit_ros_benchmarks::BenchmarkExecutor::loadQueries
bool loadQueries(const std::string &regex, const std::string &scene_name, std::vector< BenchmarkRequest > &queries)
Load all motion plan requests matching the given regular expression from the warehouse.
Definition: BenchmarkExecutor.cpp:604
moveit_ros_benchmarks::BenchmarkOptions::getNumRuns
int getNumRuns() const
Get the specified number of benchmark query runs.
Definition: BenchmarkOptions.cpp:89
moveit_ros_benchmarks::BenchmarkExecutor::loadBenchmarkQueryData
virtual bool loadBenchmarkQueryData(const BenchmarkOptions &opts, moveit_msgs::PlanningScene &scene_msg, std::vector< StartState > &start_states, std::vector< PathConstraints > &path_constraints, std::vector< PathConstraints > &goal_constraints, std::vector< TrajectoryConstraints > &traj_constraints, std::vector< BenchmarkRequest > &queries)
Initialize benchmark query data from start states and constraints.
Definition: BenchmarkExecutor.cpp:401
moveit_ros_benchmarks::BenchmarkExecutor::PlannerRunData
std::map< std::string, std::string > PlannerRunData
Structure to hold information for a single run of a planner.
Definition: BenchmarkExecutor.h:129
moveit_ros_benchmarks::BenchmarkExecutor::PlannerBenchmarkData
std::vector< PlannerRunData > PlannerBenchmarkData
Structure to hold information for a single planner's benchmark data.
Definition: BenchmarkExecutor.h:131
moveit_ros_benchmarks::BenchmarkExecutor::addPostRunEvent
void addPostRunEvent(const PostRunEventFunction &func)
Definition: BenchmarkExecutor.cpp:179
moveit_ros_benchmarks::BenchmarkOptions::getWorkspaceParameters
const moveit_msgs::WorkspaceParameters & getWorkspaceParameters() const
Definition: BenchmarkOptions.cpp:172
name
std::string name
moveit_ros_benchmarks::BenchmarkExecutor::loadPlanningScene
bool loadPlanningScene(const std::string &scene_name, moveit_msgs::PlanningScene &scene_msg)
Load the planning scene with the given name from the warehouse.
Definition: BenchmarkExecutor.cpp:568
collision_detection::CollisionResult
ros::WallTime::now
static WallTime now()
moveit_ros_benchmarks::BenchmarkExecutor::benchmark_data_
std::vector< PlannerBenchmarkData > benchmark_data_
Definition: BenchmarkExecutor.h:279
moveit_ros_benchmarks::BenchmarkExecutor::planner_completion_fns_
std::vector< PlannerCompletionEventFunction > planner_completion_fns_
Definition: BenchmarkExecutor.h:284
moveit_ros_benchmarks::BenchmarkOptions::getOutputDirectory
const std::string & getOutputDirectory() const
Get the target directory for the generated benchmark result data.
Definition: BenchmarkOptions.cpp:109
moveit_ros_benchmarks::BenchmarkExecutor::collectMetrics
virtual void collectMetrics(PlannerRunData &metrics, const planning_interface::MotionPlanDetailedResponse &mp_res, bool solved, double total_time)
Definition: BenchmarkExecutor.cpp:846
moveit_ros_benchmarks::BenchmarkExecutor::initialize
void initialize(const std::vector< std::string > &plugin_classes)
Definition: BenchmarkExecutor.cpp:101
planning_interface::MotionPlanDetailedResponse::trajectory_
std::vector< robot_trajectory::RobotTrajectoryPtr > trajectory_
moveit_ros_benchmarks::BenchmarkExecutor::BenchmarkRequest
Definition: BenchmarkExecutor.h:178
moveit_ros_benchmarks::BenchmarkExecutor::PathConstraints
Definition: BenchmarkExecutor.h:190
moveit_ros_benchmarks::BenchmarkExecutor::addPlannerStartEvent
void addPlannerStartEvent(const PlannerStartEventFunction &func)
Definition: BenchmarkExecutor.cpp:184
robot_trajectory::RobotTrajectory::empty
bool empty() const
ROS_ERROR
#define ROS_ERROR(...)
moveit_ros_benchmarks::BenchmarkOptions::getTimeout
double getTimeout() const
Get the maximum timeout per planning attempt.
Definition: BenchmarkOptions.cpp:94
moveit_ros_benchmarks::BenchmarkExecutor::clear
virtual void clear()
Definition: BenchmarkExecutor.cpp:137
moveit_warehouse::RobotStateStorage::getKnownRobotStates
void getKnownRobotStates(const std::string &regex, std::vector< std::string > &names, const std::string &robot="") const
ROS_WARN
#define ROS_WARN(...)
moveit_ros_benchmarks::BenchmarkExecutor::TrajectoryConstraints::constraints
moveit_msgs::TrajectoryConstraints constraints
Definition: BenchmarkExecutor.h:198
d
d
TimeBase< WallTime, WallDuration >::toBoost
boost::posix_time::ptime toBoost() const
moveit_warehouse::PlanningSceneStorage
moveit_ros_benchmarks::BenchmarkExecutor::StartState::state
moveit_msgs::RobotState state
Definition: BenchmarkExecutor.h:186
moveit_ros_benchmarks::BenchmarkExecutor::TrajectoryConstraints
Definition: BenchmarkExecutor.h:196
moveit_ros_benchmarks::BenchmarkExecutor::BenchmarkExecutor
BenchmarkExecutor(const std::string &robot_description_param="robot_description")
Definition: BenchmarkExecutor.cpp:80
moveit_ros_benchmarks::BenchmarkOptions::getPlanningPipelineConfigurations
const std::map< std::string, std::vector< std::string > > & getPlanningPipelineConfigurations() const
Get all planning pipeline names mapped to their parameter configuration.
Definition: BenchmarkOptions.cpp:155
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
moveit_ros_benchmarks::BenchmarkExecutor::cs_
moveit_warehouse::ConstraintsStorage * cs_
Definition: BenchmarkExecutor.h:269
moveit_ros_benchmarks::BenchmarkExecutor::addQueryCompletionEvent
void addQueryCompletionEvent(const QueryCompletionEventFunction &func)
Definition: BenchmarkExecutor.cpp:199
moveit_ros_benchmarks::BenchmarkExecutor::initializeBenchmarks
virtual bool initializeBenchmarks(const BenchmarkOptions &opts, moveit_msgs::PlanningScene &scene_msg, std::vector< BenchmarkRequest > &queries)
Definition: BenchmarkExecutor.cpp:276
ros::WallTime
moveit_ros_benchmarks::BenchmarkExecutor::addPlannerCompletionEvent
void addPlannerCompletionEvent(const PlannerCompletionEventFunction &func)
Definition: BenchmarkExecutor.cpp:189
moveit_ros_benchmarks::BenchmarkOptions::getGoalOffsets
void getGoalOffsets(std::vector< double > &offsets) const
Get the constant position/orientation offset to be used for shifting all goal constraints.
Definition: BenchmarkOptions.cpp:149
moveit_ros_benchmarks::BenchmarkExecutor::planner_start_fns_
std::vector< PlannerStartEventFunction > planner_start_fns_
Definition: BenchmarkExecutor.h:283
moveit_ros_benchmarks::BenchmarkExecutor::dbloader
warehouse_ros::DatabaseLoader dbloader
Definition: BenchmarkExecutor.h:272
moveit_warehouse::PlanningSceneStorage::getPlanningQueriesNames
void getPlanningQueriesNames(const std::string &regex, std::vector< std::string > &query_names, const std::string &scene_name) const
moveit_ros_benchmarks::BenchmarkExecutor::addQueryStartEvent
void addQueryStartEvent(const QueryStartEventFunction &func)
Definition: BenchmarkExecutor.cpp:194
planning_pipeline
moveit_ros_benchmarks::BenchmarkExecutor::addPreRunEvent
void addPreRunEvent(const PreRunEventFunction &func)
Definition: BenchmarkExecutor.cpp:174
start
ROSCPP_DECL void start()
moveit_warehouse::TrajectoryConstraintsStorage::getKnownTrajectoryConstraints
void getKnownTrajectoryConstraints(const std::string &regex, std::vector< std::string > &names, const std::string &robot="", const std::string &group="") const
moveit_ros_benchmarks::BenchmarkExecutor::createRequestCombinations
void createRequestCombinations(const BenchmarkRequest &brequest, const std::vector< StartState > &start_states, const std::vector< PathConstraints > &path_constraints, std::vector< BenchmarkRequest > &combos)
Duplicate the given benchmark request for all combinations of start states and path constraints.
Definition: BenchmarkExecutor.cpp:461
moveit_ros_benchmarks::BenchmarkExecutor::BenchmarkRequest::name
std::string name
Definition: BenchmarkExecutor.h:180
moveit_ros_benchmarks::BenchmarkExecutor::PostRunEventFunction
boost::function< void(const moveit_msgs::MotionPlanRequest &request, const planning_interface::MotionPlanDetailedResponse &response, PlannerRunData &run_data)> PostRunEventFunction
Definition of a post-run benchmark event function. Invoked immediately after each planner calls solve...
Definition: BenchmarkExecutor.h:157
moveit_ros_benchmarks::BenchmarkExecutor::PathConstraints::name
std::string name
Definition: BenchmarkExecutor.h:193
moveit_ros_benchmarks::BenchmarkExecutor::BenchmarkRequest::request
moveit_msgs::MotionPlanRequest request
Definition: BenchmarkExecutor.h:181
moveit_ros_benchmarks::BenchmarkExecutor::psws_
moveit_warehouse::PlanningSceneWorldStorage * psws_
Definition: BenchmarkExecutor.h:267
moveit::core::RobotState::satisfiesBounds
bool satisfiesBounds(double margin=0.0) const
moveit_ros_benchmarks::BenchmarkOptions::getPathConstraintRegex
const std::string & getPathConstraintRegex() const
Get the regex expression for matching the names of all path constraints to plan with.
Definition: BenchmarkOptions.cpp:129
moveit_warehouse::ConstraintsStorage::getKnownConstraints
void getKnownConstraints(const std::string &regex, std::vector< std::string > &names, const std::string &robot="", const std::string &group="") const
moveit_ros_benchmarks::BenchmarkExecutor::computeAveragePathSimilarities
void computeAveragePathSimilarities(PlannerBenchmarkData &planner_data, const std::vector< planning_interface::MotionPlanDetailedResponse > &responses, const std::vector< bool > &solved)
Definition: BenchmarkExecutor.cpp:944
moveit_warehouse::ConstraintsStorage::getConstraints
bool getConstraints(ConstraintsWithMetadata &msg_m, const std::string &name, const std::string &robot="", const std::string &group="") const
moveit_ros_benchmarks::BenchmarkExecutor::StartState
Definition: BenchmarkExecutor.h:184
moveit_ros_benchmarks::BenchmarkExecutor::shiftConstraintsByOffset
void shiftConstraintsByOffset(moveit_msgs::Constraints &constraints, const std::vector< double > &offset)
Definition: BenchmarkExecutor.cpp:439
moveit_warehouse::PlanningSceneStorage::getPlanningQuery
bool getPlanningQuery(MotionPlanRequestWithMetadata &query_m, const std::string &scene_name, const std::string &query_name)
moveit_ros_benchmarks::BenchmarkExecutor::loadTrajectoryConstraints
bool loadTrajectoryConstraints(const std::string &regex, std::vector< TrajectoryConstraints > &constraints)
Load all trajectory constraints from the warehouse that match the given regular expression.
Definition: BenchmarkExecutor.cpp:722
tf2::toMsg
B toMsg(const A &a)
collision_detection::CollisionResult::collision
bool collision
moveit_ros_benchmarks::BenchmarkOptions
Definition: BenchmarkOptions.h:79
moveit_ros_benchmarks::BenchmarkExecutor::pre_event_fns_
std::vector< PreRunEventFunction > pre_event_fns_
Definition: BenchmarkExecutor.h:281
moveit_ros_benchmarks::BenchmarkOptions::getPort
int getPort() const
Get the port of the warehouse database host server.
Definition: BenchmarkOptions.cpp:79
getHostname
static std::string getHostname()
Definition: BenchmarkExecutor.cpp:66
moveit_ros_benchmarks::BenchmarkExecutor::query_end_fns_
std::vector< QueryCompletionEventFunction > query_end_fns_
Definition: BenchmarkExecutor.h:286
moveit_ros_benchmarks::BenchmarkExecutor::PlannerCompletionEventFunction
boost::function< void(const moveit_msgs::MotionPlanRequest &request, PlannerBenchmarkData &benchmark_data)> PlannerCompletionEventFunction
Definition: BenchmarkExecutor.h:149
moveit_ros_benchmarks::BenchmarkExecutor::QueryCompletionEventFunction
boost::function< void(const moveit_msgs::MotionPlanRequest &request, planning_scene::PlanningScenePtr)> QueryCompletionEventFunction
Definition of a query-end benchmark event function. Invoked after a query has finished benchmarking.
Definition: BenchmarkExecutor.h:139
moveit_ros_benchmarks::BenchmarkExecutor::loadStates
bool loadStates(const std::string &regex, std::vector< StartState > &start_states)
Load all states matching the given regular expression from the warehouse.
Definition: BenchmarkExecutor.cpp:649
ROS_INFO
#define ROS_INFO(...)
moveit_ros_benchmarks::BenchmarkExecutor::PathConstraints::constraints
std::vector< moveit_msgs::Constraints > constraints
Definition: BenchmarkExecutor.h:192
moveit_warehouse::RobotStateStorage::getRobotState
bool getRobotState(RobotStateWithMetadata &msg_m, const std::string &name, const std::string &robot="") const
moveit_ros_benchmarks::BenchmarkExecutor::QueryStartEventFunction
boost::function< void(const moveit_msgs::MotionPlanRequest &request, planning_scene::PlanningScenePtr)> QueryStartEventFunction
Definition of a query-start benchmark event function. Invoked before a new query is benchmarked.
Definition: BenchmarkExecutor.h:135
moveit_ros_benchmarks::BenchmarkExecutor::pss_
moveit_warehouse::PlanningSceneStorage * pss_
Definition: BenchmarkExecutor.h:266
moveit_ros_benchmarks::BenchmarkExecutor::PreRunEventFunction
boost::function< void(moveit_msgs::MotionPlanRequest &request)> PreRunEventFunction
Definition of a pre-run benchmark event function. Invoked immediately before each planner calls solve...
Definition: BenchmarkExecutor.h:152
planning_interface::MotionPlanDetailedResponse::description_
std::vector< std::string > description_
moveit_ros_benchmarks::BenchmarkExecutor::~BenchmarkExecutor
virtual ~BenchmarkExecutor()
Definition: BenchmarkExecutor.cpp:91
moveit_ros_benchmarks::BenchmarkOptions::getTrajectoryConstraintRegex
const std::string & getTrajectoryConstraintRegex() const
Get the regex expression for matching the names of all trajectory constraints to plan with.
Definition: BenchmarkOptions.cpp:134
moveit_warehouse::PlanningSceneStorage::hasPlanningScene
bool hasPlanningScene(const std::string &name) const
moveit_ros_benchmarks::BenchmarkOptions::getGoalConstraintRegex
const std::string & getGoalConstraintRegex() const
Get the regex expression for matching the names of all goal constraints to plan to.
Definition: BenchmarkOptions.cpp:124
moveit::core::toString
std::string toString(double d)
planning_pipeline::PlanningPipeline
moveit_ros_benchmarks::BenchmarkExecutor::post_event_fns_
std::vector< PostRunEventFunction > post_event_fns_
Definition: BenchmarkExecutor.h:282
moveit_ros_benchmarks::BenchmarkExecutor::StartState::name
std::string name
Definition: BenchmarkExecutor.h:187
moveit_ros_benchmarks::BenchmarkOptions::getBenchmarkName
const std::string & getBenchmarkName() const
Get the reference name of the benchmark.
Definition: BenchmarkOptions.cpp:99
moveit_ros_benchmarks::BenchmarkExecutor::rs_
moveit_warehouse::RobotStateStorage * rs_
Definition: BenchmarkExecutor.h:268
ros::NodeHandle
moveit_ros_benchmarks::BenchmarkOptions::getQueryRegex
const std::string & getQueryRegex() const
Get the regex expression for matching the names of all queries to run.
Definition: BenchmarkOptions.cpp:114
planning_interface::MotionPlanDetailedResponse
moveit_ros_benchmarks
Definition: BenchmarkExecutor.h:57
BenchmarkExecutor.h
planning_interface::MotionPlanDetailedResponse::processing_time_
std::vector< double > processing_time_
moveit_ros_benchmarks::BenchmarkOptions::getSceneName
const std::string & getSceneName() const
Get the reference name of the planning scene stored inside the warehouse database.
Definition: BenchmarkOptions.cpp:84
moveit_ros_benchmarks::BenchmarkExecutor::loadPathConstraints
bool loadPathConstraints(const std::string &regex, std::vector< PathConstraints > &constraints)
Load all constraints matching the given regular expression from the warehouse.
Definition: BenchmarkExecutor.cpp:687
moveit_ros_benchmarks::BenchmarkExecutor::psm_
planning_scene_monitor::PlanningSceneMonitor * psm_
Definition: BenchmarkExecutor.h:265
robot_trajectory::RobotTrajectory::getWayPoint
const moveit::core::RobotState & getWayPoint(std::size_t index) const


benchmarks
Author(s): Ryan Luna
autogenerated on Sat May 3 2025 02:27:17