| addPlannerCompletionEvent(const PlannerCompletionEventFunction &func) | moveit_ros_benchmarks::BenchmarkExecutor | |
| addPlannerStartEvent(const PlannerStartEventFunction &func) | moveit_ros_benchmarks::BenchmarkExecutor | |
| addPostRunEvent(const PostRunEventFunction &func) | moveit_ros_benchmarks::BenchmarkExecutor | |
| addPreRunEvent(const PreRunEventFunction &func) | moveit_ros_benchmarks::BenchmarkExecutor | |
| addQueryCompletionEvent(const QueryCompletionEventFunction &func) | moveit_ros_benchmarks::BenchmarkExecutor | |
| addQueryStartEvent(const QueryStartEventFunction &func) | moveit_ros_benchmarks::BenchmarkExecutor | |
| benchmark_data_ | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| BenchmarkExecutor(const rclcpp::Node::SharedPtr &node, const std::string &robot_description_param="robot_description") | moveit_ros_benchmarks::BenchmarkExecutor | |
| clear() | moveit_ros_benchmarks::BenchmarkExecutor | virtual |
| collectMetrics(PlannerRunData &metrics, const planning_interface::MotionPlanDetailedResponse &mp_res, bool solved, double total_time) | moveit_ros_benchmarks::BenchmarkExecutor | protectedvirtual |
| CombinePredefinedPosesBenchmark(const rclcpp::Node::SharedPtr &node) | moveit_ros_benchmarks::CombinePredefinedPosesBenchmark | inline |
| computeAveragePathSimilarities(PlannerBenchmarkData &planner_data, const std::vector< planning_interface::MotionPlanDetailedResponse > &responses, const std::vector< bool > &solved) | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| computeTrajectoryDistance(const robot_trajectory::RobotTrajectory &traj_first, const robot_trajectory::RobotTrajectory &traj_second, double &result_distance) | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| createRequestCombinations(const BenchmarkRequest &brequest, const std::vector< StartState > &start_states, const std::vector< PathConstraints > &path_constraints, std::vector< BenchmarkRequest > &combos) | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| cs_ | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| dbloader | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| initialize(const std::vector< std::string > &plugin_classes) | moveit_ros_benchmarks::BenchmarkExecutor | |
| initializeBenchmarks(const BenchmarkOptions &opts, moveit_msgs::msg::PlanningScene &scene_msg, std::vector< BenchmarkRequest > &queries) | moveit_ros_benchmarks::BenchmarkExecutor | protectedvirtual |
| loadBenchmarkQueryData(const BenchmarkOptions &opts, 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) override | moveit_ros_benchmarks::CombinePredefinedPosesBenchmark | inlinevirtual |
| loadPathConstraints(const std::string ®ex, std::vector< PathConstraints > &constraints) | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| loadPlanningScene(const std::string &scene_name, moveit_msgs::msg::PlanningScene &scene_msg) | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| loadQueries(const std::string ®ex, const std::string &scene_name, std::vector< BenchmarkRequest > &queries) | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| loadStates(const std::string ®ex, std::vector< StartState > &start_states) | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| loadTrajectoryConstraints(const std::string ®ex, std::vector< TrajectoryConstraints > &constraints) | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| node_ | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| options_ | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| planner_completion_fns_ | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| planner_start_fns_ | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| PlannerBenchmarkData typedef | moveit_ros_benchmarks::BenchmarkExecutor | |
| PlannerCompletionEventFunction typedef | moveit_ros_benchmarks::BenchmarkExecutor | |
| plannerConfigurationsExist(const std::map< std::string, std::vector< std::string >> &planners, const std::string &group_name) | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| PlannerRunData typedef | moveit_ros_benchmarks::BenchmarkExecutor | |
| PlannerStartEventFunction typedef | moveit_ros_benchmarks::BenchmarkExecutor | |
| planning_pipelines_ | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| planning_scene_ | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| post_event_fns_ | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| PostRunEventFunction typedef | moveit_ros_benchmarks::BenchmarkExecutor | |
| pre_event_fns_ | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| PreRunEventFunction typedef | moveit_ros_benchmarks::BenchmarkExecutor | |
| pss_ | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| psws_ | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| queriesAndPlannersCompatible(const std::vector< BenchmarkRequest > &requests, const std::map< std::string, std::vector< std::string >> &planners) | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| query_end_fns_ | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| query_start_fns_ | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| QueryCompletionEventFunction typedef | moveit_ros_benchmarks::BenchmarkExecutor | |
| QueryStartEventFunction typedef | moveit_ros_benchmarks::BenchmarkExecutor | |
| rs_ | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| runBenchmark(moveit_msgs::msg::MotionPlanRequest request, const std::map< std::string, std::vector< std::string >> &planners, int runs) | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| runBenchmarks(const BenchmarkOptions &opts) | moveit_ros_benchmarks::BenchmarkExecutor | virtual |
| shiftConstraintsByOffset(moveit_msgs::msg::Constraints &constraints, const std::vector< double > &offset) | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| tcs_ | moveit_ros_benchmarks::BenchmarkExecutor | protected |
| writeOutput(const BenchmarkRequest &brequest, const std::string &start_time, double benchmark_duration) | moveit_ros_benchmarks::BenchmarkExecutor | protectedvirtual |
| ~BenchmarkExecutor() | moveit_ros_benchmarks::BenchmarkExecutor | virtual |