39 #include <moveit/version.h>
42 #include <boost/regex.hpp>
44 #if __has_include(<boost/timer/progress_display.hpp>)
45 #include <boost/timer/progress_display.hpp>
49 #define BOOST_TIMER_ENABLE_DEPRECATED 1
50 #include <boost/progress.hpp>
51 #undef BOOST_TIMER_ENABLE_DEPRECATED
55 #include <boost/math/constants/constants.hpp>
56 #include <boost/filesystem.hpp>
57 #include <boost/date_time/posix_time/posix_time.hpp>
68 static const int BUF_SIZE = 1024;
69 char buffer[BUF_SIZE];
70 int err = gethostname(buffer,
sizeof(buffer));
75 buffer[BUF_SIZE - 1] =
'\0';
76 return std::string(buffer);
106 for (
const std::string& planning_pipeline_name : planning_pipeline_names)
111 planning_scene_->getRobotModel(), child_nh,
"planning_plugin",
"request_adapters"));
114 if (!pipeline->getPlannerManager())
116 ROS_ERROR(
"Failed to initialize planning pipeline '%s'", planning_pipeline_name.c_str());
121 pipeline->displayComputedMotionPlans(
false);
122 pipeline->checkSolutionPaths(
false);
128 ROS_ERROR(
"No planning pipelines have been loaded. Nothing to do for the benchmarking service.");
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());
208 ROS_ERROR(
"No planning pipelines configured. Did you call BenchmarkExecutor::initialize?");
212 std::vector<BenchmarkRequest> queries;
213 moveit_msgs::PlanningScene scene_msg;
220 for (std::size_t i = 0; i < queries.size(); ++i)
223 if (scene_msg.robot_model_name !=
planning_scene_->getRobotModel()->getName())
239 ROS_INFO(
"Benchmarking query '%s' (%lu of %lu)", queries[i].
name.c_str(), i + 1, queries.size());
256 const std::map<std::string, std::vector<std::string>>& )
259 for (
const std::pair<const std::string, planning_pipeline::PlanningPipelinePtr>& pipeline_entry :
planning_pipelines_)
263 if (!pipeline_entry.second->getPlannerManager()->canServiceRequest(request.request))
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());
277 std::vector<BenchmarkRequest>& requests)
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;
288 if (!
loadBenchmarkQueryData(opts, scene_msg, start_states, path_constraints, goal_constraints, traj_constraints,
291 ROS_ERROR(
"Failed to load benchmark query data");
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(),
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)
308 workspace_parameters.min_corner.x = workspace_parameters.min_corner.y = workspace_parameters.min_corner.z = -5.0;
310 workspace_parameters.max_corner.x = workspace_parameters.max_corner.y = workspace_parameters.max_corner.z = 5.0;
313 std::vector<double> goal_offset;
324 brequest.
name = goal_constraint.name;
325 brequest.
request.workspace_parameters = workspace_parameters;
326 brequest.
request.goal_constraints = goal_constraint.constraints;
329 brequest.
request.num_planning_attempts = 1;
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())
338 std::vector<BenchmarkRequest> request_combos;
340 requests.insert(requests.end(), request_combos.begin(), request_combos.end());
349 brequest.
name = query.name;
350 brequest.
request = query.request;
353 brequest.
request.num_planning_attempts = 1;
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)
364 brequest.
request.workspace_parameters = workspace_parameters;
368 std::vector<BenchmarkRequest> request_combos;
370 requests.insert(requests.end(), request_combos.begin(), request_combos.end());
378 brequest.
name = traj_constraint.name;
379 brequest.
request.trajectory_constraints = traj_constraint.constraints;
382 brequest.
request.num_planning_attempts = 1;
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())
391 std::vector<BenchmarkRequest> request_combos;
392 std::vector<PathConstraints> no_path_constraints;
394 requests.insert(requests.end(), request_combos.begin(), request_combos.end());
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)
412 if (warehouse_connection->connect())
426 catch (std::exception& e)
428 ROS_ERROR(
"Failed to initialize benchmark server: '%s'", e.what());
440 const std::vector<double>& offset)
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]);
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;
453 Eigen::Isometry3d new_pose = constraint_pose * offset_tf;
454 geometry_msgs::Pose new_pose_msg;
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;
462 const std::vector<StartState>& start_states,
463 const std::vector<PathConstraints>& path_constraints,
464 std::vector<BenchmarkRequest>& requests)
467 if (start_states.empty())
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);
478 if (path_constraints.empty())
479 requests.push_back(brequest);
483 for (
const StartState& start_state : start_states)
486 if (start_state.name == brequest.
name)
490 new_brequest.
request.start_state = start_state.state;
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);
500 if (path_constraints.empty())
502 new_brequest.
name = start_state.name +
"_" + brequest.
name;
503 requests.push_back(new_brequest);
510 const std::map<std::string, std::vector<std::string>>& pipeline_configurations,
const std::string& group_name)
513 for (
const std::pair<
const std::string, std::vector<std::string>>& pipeline_config_entry : pipeline_configurations)
515 bool pipeline_exists =
false;
516 for (
const std::pair<const std::string, planning_pipeline::PlanningPipelinePtr>& pipeline_entry :
519 pipeline_exists = pipeline_entry.first == pipeline_config_entry.first;
524 if (!pipeline_exists)
526 ROS_ERROR(
"Planning pipeline '%s' does NOT exist", pipeline_config_entry.first.c_str());
532 for (
const std::pair<
const std::string, std::vector<std::string>>& entry : pipeline_configurations)
534 planning_interface::PlannerManagerPtr pm =
planning_pipelines_[entry.first]->getPlannerManager();
540 if (pm->getDescription().compare(
"stomp") || pm->getDescription().compare(
"chomp"))
543 for (std::size_t i = 0; i < entry.second.size(); ++i)
545 bool planner_exists =
false;
546 for (
const std::pair<const std::string, planning_interface::PlannerConfigurationSettings>& config_entry :
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);
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;
577 scene_msg =
static_cast<moveit_msgs::PlanningScene
>(*pswm);
580 ROS_ERROR(
"Failed to load planning scene '%s'", scene_name.c_str());
586 scene_msg.world =
static_cast<moveit_msgs::PlanningSceneWorld
>(*pswwm);
587 scene_msg.robot_model_name =
588 "NO ROBOT INFORMATION. ONLY WORLD GEOMETRY";
591 ROS_ERROR(
"Failed to load planning scene '%s'", scene_name.c_str());
594 ROS_ERROR(
"Failed to find planning scene '%s'", scene_name.c_str());
596 catch (std::exception& ex)
598 ROS_ERROR(
"Error loading planning scene: %s", ex.what());
600 ROS_INFO(
"Loaded planning scene successfully");
605 std::vector<BenchmarkRequest>& queries)
610 std::vector<std::string> query_names;
615 catch (std::exception& ex)
617 ROS_ERROR(
"Error loading motion planning queries: %s", ex.what());
621 if (query_names.empty())
623 ROS_ERROR(
"Scene '%s' has no associated queries", scene_name.c_str());
627 for (
const std::string& query_name : query_names)
634 catch (std::exception& ex)
636 ROS_ERROR(
"Error loading motion planning query '%s': %s", query_name.c_str(), ex.what());
641 query.
name = query_name;
642 query.
request =
static_cast<moveit_msgs::MotionPlanRequest
>(*planning_query);
643 queries.push_back(query);
645 ROS_INFO(
"Loaded queries successfully");
653 boost::regex start_regex(regex);
654 std::vector<std::string> state_names;
656 for (
const std::string& state_name : state_names)
659 if (boost::regex_match(state_name.c_str(), match, start_regex))
667 start_state.
state = moveit_msgs::RobotState(*robot_state);
668 start_state.
name = state_name;
669 start_states.push_back(start_state);
672 catch (std::exception& ex)
674 ROS_ERROR(
"Runtime error when loading state '%s': %s", state_name.c_str(), ex.what());
680 if (start_states.empty())
681 ROS_WARN(
"No stored states matched the provided start state regex: '%s'", regex.c_str());
683 ROS_INFO(
"Loaded states successfully");
691 std::vector<std::string> cnames;
694 for (
const std::string& cname : cnames)
703 constraint.
name = cname;
704 constraints.push_back(constraint);
707 catch (std::exception& ex)
709 ROS_ERROR(
"Runtime error when loading path constraint '%s': %s", cname.c_str(), ex.what());
714 if (constraints.empty())
715 ROS_WARN(
"No path constraints found that match regex: '%s'", regex.c_str());
717 ROS_INFO(
"Loaded path constraints successfully");
723 std::vector<TrajectoryConstraints>& constraints)
727 std::vector<std::string> cnames;
730 for (
const std::string& cname : cnames)
739 constraint.
name = cname;
740 constraints.push_back(constraint);
743 catch (std::exception& ex)
745 ROS_ERROR(
"Runtime error when loading trajectory constraint '%s': %s", cname.c_str(), ex.what());
750 if (constraints.empty())
751 ROS_WARN(
"No trajectory constraints found that match regex: '%s'", regex.c_str());
753 ROS_INFO(
"Loaded trajectory constraints successfully");
759 const std::map<std::string, std::vector<std::string>>& pipeline_map,
int runs)
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();
770 for (
const std::pair<
const std::string, std::vector<std::string>>& pipeline_entry : pipeline_map)
776 for (
const std::string& planner_id : pipeline_entry.second)
781 std::vector<planning_interface::MotionPlanDetailedResponse> responses(runs);
782 std::vector<bool> solved(runs);
784 request.planner_id = planner_id;
788 planner_start_fn(request, planner_data);
790 planning_interface::PlanningContextPtr planning_context;
791 if (use_planning_context)
795 for (
int j = 0; j < runs; ++j)
799 pre_event_fn(request);
803 if (use_planning_context)
805 solved[j] = planning_context->solve(responses[j]);
812 responses[j].error_code_ =
response.error_code_;
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_);
827 post_event_fn(request, responses[j], planner_data[j]);
828 collectMetrics(planner_data[j], responses[j], solved[j], total_time);
830 ROS_DEBUG(
"Spent %lf seconds collecting metrics", metrics_time);
839 planner_completion_fn(request, planner_data);
851 metrics[
"solved BOOLEAN"] = boost::lexical_cast<std::string>(solved);
856 double traj_len = 0.0;
857 double clearance = 0.0;
858 double smoothness = 0.0;
861 double process_time = total_time;
862 for (std::size_t j = 0; j < mp_res.
trajectory_.size(); ++j)
908 double acos_value = (a * a + b * b - cdist * cdist) / (2.0 * a * b);
909 if (acos_value > -1.0 && acos_value < 1.0)
912 double angle = (boost::math::constants::pi<double>() - acos(acos_value));
915 double u = 2.0 *
angle;
922 metrics[
"path_" + mp_res.
description_[j] +
"_correct BOOLEAN"] = boost::lexical_cast<std::string>(correct);
930 metrics[
"final_path_correct BOOLEAN"] = boost::lexical_cast<std::string>(correct);
938 if (process_time <= 0.0)
945 PlannerBenchmarkData& planner_data,
const std::vector<planning_interface::MotionPlanDetailedResponse>& responses,
946 const std::vector<bool>& solved)
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)
955 if (!solved[first_traj_i])
957 average_distances[first_traj_i] = std::numeric_limits<double>::max();
961 for (
size_t second_traj_i = first_traj_i + 1; second_traj_i < result_count; ++second_traj_i)
964 if (!solved[second_traj_i])
972 double trajectory_distance;
977 average_distances[first_traj_i] += trajectory_distance;
978 average_distances[second_traj_i] += trajectory_distance;
981 average_distances[first_traj_i] /= result_count - unsolved - 1;
985 for (
size_t i = 0; i < result_count; ++i)
991 double& result_distance)
994 if (traj_first.
empty() || traj_second.
empty())
998 size_t pos_first = 0;
999 size_t pos_second = 0;
1009 double total_distance = 0;
1015 total_distance += current_distance;
1017 if (pos_first == max_pos_first && pos_second == max_pos_second)
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;
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();
1037 if (can_up_both && up_both < up_first && up_both < up_second)
1041 current_distance = up_both;
1043 else if ((can_up_first && up_first < up_second) || !can_up_second)
1046 current_distance = up_first;
1048 else if (can_up_second)
1051 current_distance = up_second;
1055 result_distance = total_distance /
static_cast<double>(steps);
1060 double benchmark_duration)
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();
1069 if (hostname.empty())
1070 hostname =
"UNKNOWN";
1073 if (!filename.empty() && filename[filename.size() - 1] !=
'/')
1074 filename.append(
"/");
1077 boost::filesystem::create_directories(filename);
1081 std::ofstream out(filename.c_str());
1084 ROS_ERROR(
"Failed to open '%s' for benchmark output", filename.c_str());
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;
1094 moveit_msgs::PlanningScene 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;
1103 out <<
"0 is the random seed" << std::endl;
1104 out << brequest.
request.allowed_planning_time <<
" seconds per run" << std::endl;
1106 out <<
"-1 MB per run" << std::endl;
1108 out << benchmark_duration <<
" seconds spent to collect the data" << std::endl;
1111 out <<
"0 enum types" << std::endl;
1113 out << num_planners <<
" planners" << std::endl;
1116 for (
const std::pair<
const std::string, std::vector<std::string>>& pipeline : pipelines)
1118 for (std::size_t i = 0; i < pipeline.second.size(); ++i, ++run_id)
1121 out << pipeline.second[i] <<
" (" << pipeline.first <<
")" << std::endl;
1125 out <<
"0 common properties" << std::endl;
1128 std::set<std::string> properties_set;
1130 for (PlannerRunData::const_iterator pit = planner_run_data.begin(); pit != planner_run_data.end();
1132 properties_set.insert(pit->first);
1135 out << properties_set.size() <<
" properties for each run" << std::endl;
1136 for (
const std::string& property : properties_set)
1137 out <<
property << std::endl;
1146 for (
const std::string& property : properties_set)
1149 PlannerRunData::const_iterator runit = planner_run_data.find(property);
1150 if (runit != planner_run_data.end())
1151 out << runit->second;
1156 out <<
"." << std::endl;
1161 ROS_INFO(
"Benchmark results saved to '%s'", filename.c_str());