42#include <moveit/version.h>
43#include <tf2_eigen/tf2_eigen.hpp>
46#include <boost/regex.hpp>
48#if __has_include(<boost/timer/progress_display.hpp>)
49#include <boost/timer/progress_display.hpp>
53#define BOOST_TIMER_ENABLE_DEPRECATED 1
54#include <boost/progress.hpp>
55#undef BOOST_TIMER_ENABLE_DEPRECATED
59#include <boost/math/constants/constants.hpp>
60#include <boost/filesystem.hpp>
61#include <boost/date_time/posix_time/posix_time.hpp>
77rclcpp::Logger getLogger()
83template <
class Clock,
class Duration>
84boost::posix_time::ptime
toBoost(
const std::chrono::time_point<Clock, Duration>& from)
86 typedef std::chrono::nanoseconds duration_t;
88 rep_t d = std::chrono::duration_cast<duration_t>(from.time_since_epoch()).count();
89 rep_t sec = d / 1000000000;
90 rep_t nsec = d % 1000000000;
91 namespace pt = boost::posix_time;
92#ifdef BOOST_DATE_TIME_HAS_NANOSECONDS
93 return pt::from_time_t(sec) + pt::nanoseconds(nsec)
95 return pt::from_time_t(sec) + pt::microseconds(nsec / 1000);
101 robot_descriptionparam) }
102 , planning_scene_storage_{ nullptr }
103 , planning_scene_world_storage_{ nullptr }
104 , robot_state_storage_{ nullptr }
105 , constraints_storage_{ nullptr }
106 , trajectory_constraints_storage_{ nullptr }
122 for (
const std::string& planning_pipeline_name : planning_pipeline_names)
124 if (
moveit_cpp_->getPlanningPipelines().find(planning_pipeline_name) ==
moveit_cpp_->getPlanningPipelines().end())
126 RCLCPP_ERROR(getLogger(),
"Cannot find pipeline '%s'", planning_pipeline_name.c_str());
130 const auto& pipeline =
moveit_cpp_->getPlanningPipelines().at(planning_pipeline_name);
134 RCLCPP_ERROR(getLogger(),
"Failed to initialize planning pipeline '%s'", planning_pipeline_name.c_str());
142 RCLCPP_ERROR(getLogger(),
"No planning pipelines have been loaded. Nothing to do for the benchmarking service.");
146 RCLCPP_INFO(getLogger(),
"Available planning pipelines:");
147 for (
const std::pair<const std::string, planning_pipeline::PlanningPipelinePtr>& entry :
150 RCLCPP_INFO_STREAM(getLogger(), entry.first);
222 RCLCPP_ERROR(getLogger(),
"No planning pipelines configured. Did you call BenchmarkExecutor::initialize?");
226 std::vector<BenchmarkRequest> queries;
227 moveit_msgs::msg::PlanningScene scene_msg;
231 for (std::size_t i = 0; i < queries.size(); ++i)
234 if (scene_msg.robot_model_name !=
planning_scene_->getRobotModel()->getName())
254 RCLCPP_INFO(getLogger(),
"Benchmarking query '%s' (%lu of %lu)", queries[i].name.c_str(), i + 1, queries.size());
255 std::chrono::system_clock::time_point start_time = std::chrono::system_clock::now();
257 std::chrono::duration<double> dt = std::chrono::system_clock::now() - start_time;
258 double duration = dt.count();
265 writeOutput(queries[i], boost::posix_time::to_iso_extended_string(
toBoost(start_time)), duration, options);
274 moveit_msgs::msg::PlanningScene& scene_msg,
275 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(options, scene_msg, start_states, path_constraints, goal_constraints, traj_constraints,
291 RCLCPP_ERROR(getLogger(),
"Failed to load benchmark query data");
297 "Benchmark loaded %lu starts, %lu goals, %lu path constraints, %lu trajectory constraints, and %lu queries",
298 start_states.size(), goal_constraints.size(), path_constraints.size(), traj_constraints.size(), queries.size());
300 moveit_msgs::msg::WorkspaceParameters workspace_parameters = options.workspace;
302 if (workspace_parameters.min_corner.x == workspace_parameters.max_corner.x &&
303 workspace_parameters.min_corner.x == 0.0 &&
304 workspace_parameters.min_corner.y == workspace_parameters.max_corner.y &&
305 workspace_parameters.min_corner.y == 0.0 &&
306 workspace_parameters.min_corner.z == workspace_parameters.max_corner.z &&
307 workspace_parameters.min_corner.z == 0.0)
309 workspace_parameters.min_corner.x = workspace_parameters.min_corner.y = workspace_parameters.min_corner.z = -5.0;
311 workspace_parameters.max_corner.x = workspace_parameters.max_corner.y = workspace_parameters.max_corner.z = 5.0;
322 benchmark_request.
name = goal_constraint.name;
323 benchmark_request.
request.workspace_parameters = workspace_parameters;
324 benchmark_request.
request.goal_constraints = goal_constraint.constraints;
325 benchmark_request.
request.group_name = options.group_name;
326 benchmark_request.
request.allowed_planning_time = options.timeout;
327 benchmark_request.
request.num_planning_attempts = 1;
329 if (benchmark_request.
request.goal_constraints.size() == 1 &&
330 benchmark_request.
request.goal_constraints.at(0).position_constraints.size() == 1 &&
331 benchmark_request.
request.goal_constraints.at(0).orientation_constraints.size() == 1 &&
332 benchmark_request.
request.goal_constraints.at(0).visibility_constraints.empty() &&
333 benchmark_request.
request.goal_constraints.at(0).joint_constraints.empty())
338 std::vector<BenchmarkRequest> request_combos;
340 requests.insert(requests.end(), request_combos.begin(), request_combos.end());
349 benchmark_request.
name = query.name;
350 benchmark_request.
request = query.request;
351 benchmark_request.
request.group_name = options.group_name;
352 benchmark_request.
request.allowed_planning_time = options.timeout;
353 benchmark_request.
request.num_planning_attempts = 1;
356 if (benchmark_request.
request.workspace_parameters.min_corner.x ==
357 benchmark_request.
request.workspace_parameters.max_corner.x &&
358 benchmark_request.
request.workspace_parameters.min_corner.x == 0.0 &&
359 benchmark_request.
request.workspace_parameters.min_corner.y ==
360 benchmark_request.
request.workspace_parameters.max_corner.y &&
361 benchmark_request.
request.workspace_parameters.min_corner.y == 0.0 &&
362 benchmark_request.
request.workspace_parameters.min_corner.z ==
363 benchmark_request.
request.workspace_parameters.max_corner.z &&
364 benchmark_request.
request.workspace_parameters.min_corner.z == 0.0)
367 benchmark_request.
request.workspace_parameters = workspace_parameters;
371 std::vector<BenchmarkRequest> request_combos;
373 requests.insert(requests.end(), request_combos.begin(), request_combos.end());
381 benchmark_request.
name = traj_constraint.name;
382 benchmark_request.
request.trajectory_constraints = traj_constraint.constraints;
383 benchmark_request.
request.group_name = options.group_name;
384 benchmark_request.
request.allowed_planning_time = options.timeout;
385 benchmark_request.
request.num_planning_attempts = 1;
387 if (benchmark_request.
request.trajectory_constraints.constraints.size() == 1 &&
388 benchmark_request.
request.trajectory_constraints.constraints.at(0).position_constraints.size() == 1 &&
389 benchmark_request.
request.trajectory_constraints.constraints.at(0).orientation_constraints.size() == 1 &&
390 benchmark_request.
request.trajectory_constraints.constraints.at(0).visibility_constraints.empty() &&
391 benchmark_request.
request.trajectory_constraints.constraints.at(0).joint_constraints.empty())
396 std::vector<BenchmarkRequest> request_combos;
397 std::vector<PathConstraints> no_path_constraints;
399 requests.insert(requests.end(), request_combos.begin(), request_combos.end());
405 const BenchmarkOptions& options, moveit_msgs::msg::PlanningScene& scene_msg, std::vector<StartState>& start_states,
406 std::vector<PathConstraints>& path_constraints, std::vector<PathConstraints>& goal_constraints,
407 std::vector<TrajectoryConstraints>& traj_constraints, std::vector<BenchmarkRequest>& queries)
411 warehouse_ros::DatabaseConnection::Ptr warehouse_connection =
db_loader_.loadDatabase();
412 warehouse_connection->setParams(options.hostname, options.port, 20);
413 if (warehouse_connection->connect())
417 std::make_shared<moveit_warehouse::PlanningSceneWorldStorage>(warehouse_connection);
418 robot_state_storage_ = std::make_shared<moveit_warehouse::RobotStateStorage>(warehouse_connection);
419 constraints_storage_ = std::make_shared<moveit_warehouse::ConstraintsStorage>(warehouse_connection);
421 std::make_shared<moveit_warehouse::TrajectoryConstraintsStorage>(warehouse_connection);
422 RCLCPP_INFO(getLogger(),
"Connected to DB");
426 RCLCPP_ERROR(getLogger(),
"Failed to connect to DB");
430 catch (std::exception& e)
432 RCLCPP_ERROR(getLogger(),
"Failed to initialize benchmark server: '%s'", e.what());
438 RCLCPP_ERROR(getLogger(),
"Failed to load the planning scene");
441 if (!
loadStates(options.start_state_regex, start_states))
443 RCLCPP_ERROR(getLogger(),
"Failed to load the states");
448 RCLCPP_ERROR(getLogger(),
"Failed to load the goal constraints");
452 RCLCPP_ERROR(getLogger(),
"Failed to load the path constraints");
456 RCLCPP_ERROR(getLogger(),
"Failed to load the trajectory constraints");
458 if (!
loadQueries(options.query_regex, options.scene_name, queries))
460 RCLCPP_ERROR(getLogger(),
"Failed to get a query regex");
466 const std::vector<double>& offset)
468 Eigen::Isometry3d offset_tf(Eigen::AngleAxis<double>(offset.at(3), Eigen::Vector3d::UnitX()) *
469 Eigen::AngleAxis<double>(offset.at(4), Eigen::Vector3d::UnitY()) *
470 Eigen::AngleAxis<double>(offset.at(5), Eigen::Vector3d::UnitZ()));
471 offset_tf.translation() = Eigen::Vector3d(offset.at(0), offset.at(1), offset.at(2));
473 geometry_msgs::msg::Pose constraint_pose_msg;
474 constraint_pose_msg.position =
475 constraints.position_constraints.at(0).constraint_region.primitive_poses.at(0).position;
476 constraint_pose_msg.orientation = constraints.orientation_constraints.at(0).orientation;
477 Eigen::Isometry3d constraint_pose;
478 tf2::fromMsg(constraint_pose_msg, constraint_pose);
480 Eigen::Isometry3d new_pose = constraint_pose * offset_tf;
481 geometry_msgs::msg::Pose new_pose_msg;
482 new_pose_msg = tf2::toMsg(new_pose);
484 constraints.position_constraints.at(0).constraint_region.primitive_poses.at(0).position = new_pose_msg.position;
485 constraints.orientation_constraints.at(0).orientation = new_pose_msg.orientation;
489 const std::vector<StartState>& start_states,
490 const std::vector<PathConstraints>& path_constraints,
491 std::vector<BenchmarkRequest>& requests)
494 if (start_states.empty())
500 new_benchmark_request.
request.path_constraints = path_constraint.constraints.at(0);
501 new_benchmark_request.
name = benchmark_request.
name +
"_" + path_constraint.name;
502 requests.push_back(new_benchmark_request);
505 if (path_constraints.empty())
507 requests.push_back(benchmark_request);
512 for (
const StartState& start_state : start_states)
515 if (start_state.name == benchmark_request.
name)
519 new_benchmark_request.
request.start_state = start_state.state;
524 new_benchmark_request.
request.path_constraints = path_constraint.constraints.at(0);
525 new_benchmark_request.
name = start_state.name +
"_" + new_benchmark_request.
name +
"_" + path_constraint.name;
526 requests.push_back(new_benchmark_request);
529 if (path_constraints.empty())
531 new_benchmark_request.
name = start_state.name +
"_" + benchmark_request.
name;
532 requests.push_back(new_benchmark_request);
541 for (
const std::pair<
const std::string, std::vector<std::string>>& pipeline_config_entry : pipeline_configurations)
543 bool pipeline_exists =
false;
544 for (
const std::pair<const std::string, planning_pipeline::PlanningPipelinePtr>& pipeline_entry :
547 pipeline_exists = pipeline_entry.first == pipeline_config_entry.first;
552 if (!pipeline_exists)
554 RCLCPP_ERROR(getLogger(),
"Planning pipeline '%s' does NOT exist", pipeline_config_entry.first.c_str());
571 RCLCPP_ERROR(getLogger(),
"Failed to load planning scene '%s'", scene_name.c_str());
574 scene_msg =
static_cast<moveit_msgs::msg::PlanningScene
>(*planning_scene_w_metadata);
581 RCLCPP_ERROR(getLogger(),
"Failed to load planning scene world '%s'", scene_name.c_str());
584 scene_msg.world =
static_cast<moveit_msgs::msg::PlanningSceneWorld
>(*pswwm);
585 scene_msg.robot_model_name =
586 "NO ROBOT INFORMATION. ONLY WORLD GEOMETRY";
590 RCLCPP_ERROR(getLogger(),
"Failed to find planning scene '%s'", scene_name.c_str());
594 catch (std::exception& ex)
596 RCLCPP_ERROR(getLogger(),
"Error loading planning scene: %s", ex.what());
599 RCLCPP_INFO(getLogger(),
"Loaded planning scene successfully");
604 std::vector<BenchmarkRequest>& queries)
608 RCLCPP_WARN(getLogger(),
"No query regex provided, don't load any queries from the database");
612 std::vector<std::string> query_names;
617 catch (std::exception& ex)
619 RCLCPP_ERROR(getLogger(),
"Error loading motion planning queries: %s", ex.what());
623 if (query_names.empty())
625 RCLCPP_ERROR(getLogger(),
"Scene '%s' has no associated queries", scene_name.c_str());
629 for (
const std::string& query_name : query_names)
636 catch (std::exception& ex)
638 RCLCPP_ERROR(getLogger(),
"Error loading motion planning query '%s': %s", query_name.c_str(), ex.what());
643 query.
name = query_name;
644 query.
request =
static_cast<moveit_msgs::msg::MotionPlanRequest
>(*planning_query);
645 queries.push_back(query);
647 RCLCPP_INFO(getLogger(),
"Loaded queries successfully");
655 std::regex start_regex(regex);
656 std::vector<std::string> state_names;
659 if (state_names.empty())
661 RCLCPP_WARN(getLogger(),
"Database does not contain any named states");
664 for (
const std::string& state_name : state_names)
667 if (std::regex_match(state_name, match, start_regex))
675 start_state.
state = moveit_msgs::msg::RobotState(*robot_state);
676 start_state.
name = state_name;
677 start_states.push_back(start_state);
680 catch (std::exception& ex)
682 RCLCPP_ERROR(getLogger(),
"Runtime error when loading state '%s': %s", state_name.c_str(), ex.what());
688 if (start_states.empty())
690 RCLCPP_WARN(getLogger(),
"No stored states matched the provided start state regex: '%s'", regex.c_str());
693 RCLCPP_INFO(getLogger(),
"Loaded states successfully");
701 std::vector<std::string> cnames;
704 for (
const std::string& cname : cnames)
713 constraint.
name = cname;
714 constraints.push_back(constraint);
717 catch (std::exception& ex)
719 RCLCPP_ERROR(getLogger(),
"Runtime error when loading path constraint '%s': %s", cname.c_str(), ex.what());
724 if (constraints.empty())
726 RCLCPP_WARN(getLogger(),
"No path constraints found that match regex: '%s'", regex.c_str());
730 RCLCPP_INFO(getLogger(),
"Loaded path constraints successfully");
737 std::vector<TrajectoryConstraints>& constraints)
741 std::vector<std::string> cnames;
744 for (
const std::string& cname : cnames)
753 constraint.
name = cname;
754 constraints.push_back(constraint);
757 catch (std::exception& ex)
759 RCLCPP_ERROR(getLogger(),
"Runtime error when loading trajectory constraint '%s': %s", cname.c_str(), ex.what());
764 if (constraints.empty())
766 RCLCPP_WARN(getLogger(),
"No trajectory constraints found that match regex: '%s'", regex.c_str());
770 RCLCPP_INFO(getLogger(),
"Loaded trajectory constraints successfully");
780 auto num_planners = 0;
781 for (
const std::pair<
const std::string, std::vector<std::string>>& pipeline_entry : options.planning_pipelines)
783 num_planners += pipeline_entry.second.size();
785 num_planners += options.parallel_planning_pipelines.size();
790 auto planning_pipelines =
moveit_cpp_->getPlanningPipelines();
791 for (
const std::pair<
const std::string, std::vector<std::string>>& pipeline_entry : options.planning_pipelines)
794 for (
const std::string& planner_id : pipeline_entry.second)
799 std::vector<planning_interface::MotionPlanDetailedResponse> responses(options.runs);
800 std::vector<bool> solved(options.runs);
802 request.planner_id = planner_id;
807 planner_start_function(request, planner_data);
812 .planning_pipeline = pipeline_entry.first,
813 .planning_attempts = request.num_planning_attempts,
814 .planning_time = request.allowed_planning_time,
815 .max_velocity_scaling_factor = request.max_velocity_scaling_factor,
816 .max_acceleration_scaling_factor = request.max_acceleration_scaling_factor
820 for (
int j = 0; j < options.runs; ++j)
824 pre_event_function(request);
827 auto planning_component = std::make_shared<moveit_cpp::PlanningComponent>(request.group_name,
moveit_cpp_);
831 planning_component->setStartState(start_state);
832 planning_component->setGoal(request.goal_constraints);
833 planning_component->setPathConstraints(request.path_constraints);
834 planning_component->setTrajectoryConstraints(request.trajectory_constraints);
837 std::chrono::system_clock::time_point start = std::chrono::system_clock::now();
840 const auto response = planning_component->plan(plan_req_params,
planning_scene_);
842 solved[j] = bool(response.error_code);
844 responses[j].error_code = response.error_code;
845 if (response.trajectory)
847 responses[j].description.push_back(
"plan");
848 responses[j].trajectory.push_back(response.trajectory);
849 responses[j].processing_time.push_back(response.planning_time);
852 std::chrono::duration<double> dt = std::chrono::system_clock::now() - start;
853 double total_time = dt.count();
856 start = std::chrono::system_clock::now();
861 post_event_fn(request, responses[j], planner_data[j]);
863 collectMetrics(planner_data[j], responses[j], solved[j], total_time);
864 dt = std::chrono::system_clock::now() - start;
865 double metriconstraints_storage_time = dt.count();
866 RCLCPP_DEBUG(getLogger(),
"Spent %lf seconds collecting metrics", metriconstraints_storage_time);
876 planner_completion_fn(request, planner_data);
883 if (!options.parallel_planning_pipelines.empty())
886 for (
const std::pair<
const std::string, std::vector<std::pair<std::string, std::string>>>& parallel_pipeline_entry :
887 options.parallel_planning_pipelines)
892 std::vector<planning_interface::MotionPlanDetailedResponse> responses(options.runs);
893 std::vector<bool> solved(options.runs);
898 planner_start_function(request, planner_data);
903 for (
const auto& pipeline_planner_id_pair : parallel_pipeline_entry.second)
906 .
planner_id = pipeline_planner_id_pair.second,
907 .planning_pipeline = pipeline_planner_id_pair.first,
908 .planning_attempts = request.num_planning_attempts,
909 .planning_time = request.allowed_planning_time,
910 .max_velocity_scaling_factor = request.max_velocity_scaling_factor,
911 .max_acceleration_scaling_factor = request.max_acceleration_scaling_factor
917 for (
int j = 0; j < options.runs; ++j)
922 pre_event_function(request);
926 auto planning_component = std::make_shared<moveit_cpp::PlanningComponent>(request.group_name,
moveit_cpp_);
930 planning_component->setStartState(start_state);
931 planning_component->setGoal(request.goal_constraints);
932 planning_component->setPathConstraints(request.path_constraints);
933 planning_component->setTrajectoryConstraints(request.trajectory_constraints);
936 std::chrono::system_clock::time_point start = std::chrono::system_clock::now();
938 const auto t1 = std::chrono::system_clock::now();
939 const auto response = planning_component->plan(multi_pipeline_plan_request,
942 const auto t2 = std::chrono::system_clock::now();
944 solved[j] = bool(response.error_code);
946 responses[j].error_code = response.error_code;
947 if (response.trajectory)
949 responses[j].description.push_back(
"plan");
950 responses[j].trajectory.push_back(response.trajectory);
951 responses[j].processing_time.push_back(std::chrono::duration_cast<std::chrono::milliseconds>(t2 - t1).count());
954 std::chrono::duration<double> dt = std::chrono::system_clock::now() - start;
955 double total_time = dt.count();
958 start = std::chrono::system_clock::now();
962 post_event_fn(request, responses[j], planner_data[j]);
965 collectMetrics(planner_data[j], responses[j], solved[j], total_time);
966 dt = std::chrono::system_clock::now() - start;
967 double metriconstraints_storage_time = dt.count();
968 RCLCPP_DEBUG(getLogger(),
"Spent %lf seconds collecting metrics", metriconstraints_storage_time);
978 planner_completion_fn(request, planner_data);
988 bool solved,
double total_time)
991 metrics[
"solved BOOLEAN"] = solved ?
"true" :
"false";
996 double traj_len = 0.0;
997 double clearance = 0.0;
1000 double process_time = total_time;
1001 for (std::size_t j = 0; j < motion_plan_response.
trajectory.size(); ++j)
1029 const auto smoothness = [&]() {
1031 return s.has_value() ? s.value() : 0.0;
1034 metrics[
"path_" + motion_plan_response.
description[j] +
"_correct BOOLEAN"] = correct ?
"true" :
"false";
1038 metrics[
"path_" + motion_plan_response.
description[j] +
"_time REAL"] =
1041 if (j == motion_plan_response.
trajectory.size() - 1)
1043 metrics[
"final_path_correct BOOLEAN"] = correct ?
"true" :
"false";
1051 if (process_time <= 0.0)
1058 PlannerBenchmarkData& planner_data,
const std::vector<planning_interface::MotionPlanDetailedResponse>& responses,
1059 const std::vector<bool>& solved)
1061 RCLCPP_INFO(getLogger(),
"Computing result path similarity");
1062 const size_t result_count = planner_data.size();
1063 size_t unsolved = std::count_if(solved.begin(), solved.end(), [](
bool s) { return !s; });
1064 std::vector<double> average_distances(responses.size());
1065 for (
size_t first_traj_i = 0; first_traj_i < result_count; ++first_traj_i)
1068 if (!solved[first_traj_i])
1070 average_distances[first_traj_i] = std::numeric_limits<double>::max();
1074 for (
size_t second_traj_i = first_traj_i + 1; second_traj_i < result_count; ++second_traj_i)
1077 if (!solved[second_traj_i])
1085 double trajectory_distance;
1090 average_distances[first_traj_i] += trajectory_distance;
1091 average_distances[second_traj_i] += trajectory_distance;
1094 average_distances[first_traj_i] /= result_count - unsolved - 1;
1098 for (
size_t i = 0; i < result_count; ++i)
1104 double& result_distance)
1107 if (traj_first.
empty() || traj_second.
empty())
1111 size_t pos_first = 0;
1112 size_t pos_second = 0;
1122 double total_distance = 0;
1128 total_distance += current_distance;
1130 if (pos_first == max_pos_first && pos_second == max_pos_second)
1134 bool can_up_first = pos_first < max_pos_first;
1135 bool can_up_second = pos_second < max_pos_second;
1136 bool can_up_both = can_up_first && can_up_second;
1139 double up_both = std::numeric_limits<double>::max();
1140 double up_first = std::numeric_limits<double>::max();
1141 double up_second = std::numeric_limits<double>::max();
1150 if (can_up_both && up_both < up_first && up_both < up_second)
1154 current_distance = up_both;
1156 else if ((can_up_first && up_first < up_second) || !can_up_second)
1159 current_distance = up_first;
1161 else if (can_up_second)
1164 current_distance = up_second;
1168 result_distance = total_distance /
static_cast<double>(steps);
1176 size_t num_planners = 0;
1177 for (
const std::pair<
const std::string, std::vector<std::string>>& pipeline : options.planning_pipelines)
1179 num_planners += pipeline.second.size();
1181 num_planners += options.parallel_planning_pipelines.size();
1183 std::string hostname = [&]() {
1184 static const int BUF_SIZE = 1024;
1185 char buffer[BUF_SIZE];
1186 int err = gethostname(buffer,
sizeof(buffer));
1189 return std::string();
1193 buffer[BUF_SIZE - 1] =
'\0';
1194 return std::string(buffer);
1197 if (hostname.empty())
1199 hostname =
"UNKNOWN";
1203 std::string filename = options.output_directory;
1204 if (!filename.empty() && filename[filename.size() - 1] !=
'/')
1206 filename.append(
"/");
1210 std::filesystem::create_directories(filename);
1213 filename += (options.benchmark_name.empty() ?
"" : options.benchmark_name +
"_") + benchmark_request.
name +
"_" +
1214 hostname +
"_" + start_time +
".log";
1217 std::ofstream out(filename.c_str());
1220 RCLCPP_ERROR(getLogger(),
"Failed to open '%s' for benchmark output", filename.c_str());
1225 out <<
"MoveIt version " << MOVEIT_VERSION_STR <<
'\n';
1226 out <<
"Experiment " << benchmark_request.
name <<
'\n';
1227 out <<
"Running on " << hostname <<
'\n';
1228 out <<
"Starting at " << start_time <<
'\n';
1231 moveit_msgs::msg::PlanningScene scene_msg;
1233 out <<
"<<<|" <<
'\n';
1234 out <<
"Motion plan request:" <<
'\n'
1235 <<
" planner_id: " << benchmark_request.
request.planner_id <<
'\n'
1236 <<
" group_name: " << benchmark_request.
request.group_name <<
'\n'
1237 <<
" num_planning_attempts: " << benchmark_request.
request.num_planning_attempts <<
'\n'
1238 <<
" allowed_planning_time: " << benchmark_request.
request.allowed_planning_time <<
'\n';
1239 out <<
"Planning scene:" <<
'\n'
1240 <<
" scene_name: " << scene_msg.name <<
'\n'
1241 <<
" robot_model_name: " << scene_msg.robot_model_name <<
'\n'
1245 out <<
"0 is the random seed" <<
'\n';
1246 out << benchmark_request.
request.allowed_planning_time <<
" seconds per run" <<
'\n';
1248 out <<
"-1 MB per run" <<
'\n';
1249 out << options.runs <<
" runs per planner" <<
'\n';
1250 out << benchmark_duration <<
" seconds spent to collect the data" <<
'\n';
1253 out <<
"0 enum types" <<
'\n';
1255 out << num_planners <<
" planners" <<
'\n';
1261 for (
const std::pair<
const std::string, std::vector<std::string>>& pipeline : options.planning_pipelines)
1263 for (std::size_t i = 0; i < pipeline.second.size(); ++i, ++run_id)
1266 out << pipeline.second[i] <<
" (" << pipeline.first <<
')' <<
'\n';
1270 out <<
"0 common properties" <<
'\n';
1273 std::set<std::string> properties_set;
1276 for (PlannerRunData::const_iterator pit = planner_run_data.begin(); pit != planner_run_data.end();
1278 properties_set.insert(pit->first);
1282 out << properties_set.size() <<
" properties for each run" <<
'\n';
1283 for (
const std::string& property : properties_set)
1284 out << property <<
'\n';
1293 for (
const std::string& property : properties_set)
1296 PlannerRunData::const_iterator runit = planner_run_data.find(property);
1297 if (runit != planner_run_data.end())
1298 out << runit->second;
1308 for (
const std::pair<
const std::string, std::vector<std::pair<std::string, std::string>>>& parallel_pipeline :
1309 options.parallel_planning_pipelines)
1312 out << parallel_pipeline.first <<
" (" << parallel_pipeline.first <<
")" <<
'\n';
1316 out <<
"0 common properties" <<
'\n';
1319 std::set<std::string> properties_set;
1323 for (PlannerRunData::const_iterator pit = planner_run_data.begin(); pit != planner_run_data.end(); ++pit)
1325 properties_set.insert(pit->first);
1330 out << properties_set.size() <<
" properties for each run" <<
'\n';
1331 for (
const std::string& property : properties_set)
1332 out << property <<
'\n';
1341 for (
const std::string& property : properties_set)
1344 PlannerRunData::const_iterator runit = planner_run_data.find(property);
1345 if (runit != planner_run_data.end())
1346 out << runit->second;
1358 RCLCPP_INFO(getLogger(),
"Benchmark results saved to '%s'", filename.c_str());
boost::progress_display boost_progress_display
boost::posix_time::ptime toBoost(const std::chrono::time_point< Clock, Duration > &from)
Representation of a robot's state. This includes position, velocity, acceleration and effort.
double distance(const RobotState &other) const
Return the sum of joint distances to "other" state. An L1 norm. Only considers active joints.
bool satisfiesBounds(double margin=0.0) const
bool loadPlanningScene(const std::string &scene_name, moveit_msgs::msg::PlanningScene &scene_msg)
Load the planning scene with the given name from the warehouse.
void computeAveragePathSimilarities(PlannerBenchmarkData &planner_data, const std::vector< planning_interface::MotionPlanDetailedResponse > &responses, const std::vector< bool > &solved)
bool pipelinesExist(const std::map< std::string, std::vector< std::string > > &planners)
Check that the desired planning pipelines exist.
bool loadQueries(const std::string ®ex, const std::string &scene_name, std::vector< BenchmarkRequest > &queries)
Load all motion plan requests matching the given regular expression from the warehouse.
void createRequestCombinations(const BenchmarkRequest &benchmark_request, 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.
std::vector< PlannerRunData > PlannerBenchmarkData
Structure to hold information for a single planner's benchmark data.
rclcpp::Node::SharedPtr node_
planning_scene::PlanningScenePtr planning_scene_
std::vector< PlannerStartEventFunction > planner_start_functions_
warehouse_ros::DatabaseLoader db_loader_
bool computeTrajectoryDistance(const robot_trajectory::RobotTrajectory &traj_first, const robot_trajectory::RobotTrajectory &traj_second, double &result_distance)
void addQueryStartEvent(const QueryStartEventFunction &func)
std::shared_ptr< moveit_warehouse::ConstraintsStorage > constraints_storage_
std::shared_ptr< moveit_warehouse::PlanningSceneStorage > planning_scene_storage_
std::function< void(const moveit_msgs::msg::MotionPlanRequest &request, PlannerBenchmarkData &benchmark_data)> PlannerCompletionEventFunction
std::vector< QueryCompletionEventFunction > query_end_functions_
std::shared_ptr< moveit_warehouse::TrajectoryConstraintsStorage > trajectory_constraints_storage_
std::function< void(const moveit_msgs::msg::MotionPlanRequest &request, planning_scene::PlanningScenePtr)> QueryCompletionEventFunction
Definition of a query-end benchmark event function. Invoked after a query has finished benchmarking.
std::shared_ptr< moveit_cpp::MoveItCpp > moveit_cpp_
virtual void collectMetrics(PlannerRunData &metrics, const planning_interface::MotionPlanDetailedResponse &motion_plan_response, bool solved, double total_time)
std::vector< QueryStartEventFunction > query_start_functions_
bool loadPathConstraints(const std::string ®ex, std::vector< PathConstraints > &constraints)
Load all constraints matching the given regular expression from the warehouse.
std::vector< PreRunEventFunction > pre_event_functions_
void runBenchmark(moveit_msgs::msg::MotionPlanRequest request, const BenchmarkOptions &options)
Execute the given motion plan request on the set of planners for the set number of runs.
void addPreRunEvent(const PreRunEventFunction &func)
BenchmarkExecutor(const rclcpp::Node::SharedPtr &node, const std::string &robot_description_param="robot_description")
virtual bool runBenchmarks(const BenchmarkOptions &options)
std::vector< PlannerBenchmarkData > benchmark_data_
virtual bool loadBenchmarkQueryData(const BenchmarkOptions &options, moveit_msgs::msg::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.
std::vector< PostRunEventFunction > post_event_functions_
virtual bool initializeBenchmarks(const BenchmarkOptions &options, moveit_msgs::msg::PlanningScene &scene_msg, std::vector< BenchmarkRequest > &queries)
void addPlannerCompletionEvent(const PlannerCompletionEventFunction &func)
std::shared_ptr< planning_scene_monitor::PlanningSceneMonitor > planning_scene_monitor_
void addPlannerStartEvent(const PlannerStartEventFunction &func)
void addQueryCompletionEvent(const QueryCompletionEventFunction &func)
bool loadStates(const std::string ®ex, std::vector< StartState > &start_states)
Load all states matching the given regular expression from the warehouse.
std::function< void(const moveit_msgs::msg::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...
std::function< void(moveit_msgs::msg::MotionPlanRequest &request)> PreRunEventFunction
Definition of a pre-run benchmark event function. Invoked immediately before each planner calls solve...
std::vector< PlannerCompletionEventFunction > planner_completion_functions_
std::shared_ptr< moveit_warehouse::RobotStateStorage > robot_state_storage_
virtual ~BenchmarkExecutor()
std::function< void(const moveit_msgs::msg::MotionPlanRequest &request, planning_scene::PlanningScenePtr)> QueryStartEventFunction
Definition of a query-start benchmark event function. Invoked before a new query is benchmarked.
virtual void writeOutput(const BenchmarkRequest &benchmark_request, const std::string &start_time, double benchmark_duration, const BenchmarkOptions &options)
bool initialize(const std::vector< std::string > &plugin_classes)
std::shared_ptr< moveit_warehouse::PlanningSceneWorldStorage > planning_scene_world_storage_
std::function< void(const moveit_msgs::msg::MotionPlanRequest &request, PlannerBenchmarkData &benchmark_data)> PlannerStartEventFunction
bool loadTrajectoryConstraints(const std::string ®ex, std::vector< TrajectoryConstraints > &constraints)
Load all trajectory constraints from the warehouse that match the given regular expression.
void addPostRunEvent(const PostRunEventFunction &func)
void shiftConstraintsByOffset(moveit_msgs::msg::Constraints &constraints, const std::vector< double > &offset)
std::map< std::string, std::string > PlannerRunData
Structure to hold information for a single run of a planner.
Maintain a sequence of waypoints and the time durations between these waypoints.
std::size_t getWayPointCount() const
const moveit::core::RobotState & getWayPoint(std::size_t index) const
locale-agnostic conversion functions from floating point numbers to strings
std::string toString(double d)
Convert a double to std::string using the classic C locale.
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
::planning_interface::MotionPlanResponse getShortestSolution(const std::vector<::planning_interface::MotionPlanResponse > &solutions)
Function that returns the shortest solution out of a vector of solutions based on robot_trajectory::p...
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotState >::ConstPtr RobotStateWithMetadata
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::PlanningScene >::ConstPtr PlanningSceneWithMetadata
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::TrajectoryConstraints >::ConstPtr TrajectoryConstraintsWithMetadata
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::PlanningSceneWorld >::ConstPtr PlanningSceneWorldWithMetadata
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::MotionPlanRequest >::ConstPtr MotionPlanRequestWithMetadata
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::Constraints >::ConstPtr ConstraintsWithMetadata
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
std::optional< double > smoothness(const RobotTrajectory &trajectory)
Calculate the smoothness of a given trajectory.
double pathLength(const RobotTrajectory &trajectory)
Calculate the path length of a given trajectory based on the accumulated robot state distances....
Representation of a collision checking request.
bool pad_environment_collisions
If true, use padded collision environment.
Representation of a collision checking result.
bool collision
True if collision was found, false otherwise.
Planner parameters provided with the MotionPlanRequest.
std::vector< PlanRequestParameters > plan_request_parameter_vector
Planner parameters provided with the MotionPlanRequest.
moveit_msgs::msg::MotionPlanRequest request
std::vector< moveit_msgs::msg::Constraints > constraints
moveit_msgs::msg::RobotState state
moveit_msgs::msg::TrajectoryConstraints constraints
Options to configure a benchmark experiment. The configuration is provided via ROS2 parameters.
std::vector< std::string > description
std::vector< double > processing_time
std::vector< robot_trajectory::RobotTrajectoryPtr > trajectory