moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Options to configure a benchmark experiment. The configuration is provided via ROS2 parameters. More...
#include <BenchmarkOptions.h>
Public Member Functions | |
BenchmarkOptions (const rclcpp::Node::SharedPtr &node) | |
Constructor. | |
void | getPlanningPipelineNames (std::vector< std::string > &planning_pipeline_names) const |
Get all planning pipeline names. | |
const std::string & | getWorkspaceFrameID () const |
const moveit_msgs::msg::WorkspaceParameters & | getWorkspaceParameters () const |
bool | readBenchmarkOptions (const rclcpp::Node::SharedPtr &node) |
bool | readPlannerConfigs (const rclcpp::Node::SharedPtr &node) |
void | readWorkspaceParameters (const rclcpp::Node::SharedPtr &node) |
void | readGoalOffset (const rclcpp::Node::SharedPtr &node) |
Public Attributes | |
std::string | hostname |
Warehouse parameters. | |
int | port |
std::string | scene_name |
int | runs |
Benchmark parameters. | |
double | timeout |
std::string | benchmark_name |
std::string | group_name |
std::string | output_directory |
std::string | query_regex |
std::string | start_state_regex |
std::string | goal_constraint_regex |
std::string | path_constraint_regex |
std::string | trajectory_constraint_regex |
std::vector< std::string > | predefined_poses |
std::string | predefined_poses_group |
std::vector< double > | goal_offsets |
std::map< std::string, std::vector< std::string > > | planning_pipelines |
planner configurations | |
std::map< std::string, std::vector< std::pair< std::string, std::string > > > | parallel_planning_pipelines |
moveit_msgs::msg::WorkspaceParameters | workspace |
Options to configure a benchmark experiment. The configuration is provided via ROS2 parameters.
TODO(sjahr): Replace with generate_parameter_library config
Parameter configuration example: benchmark_config: # Benchmark param namespace warehouse: host: # Host address for warehouse port: # Port name for warehouse scene_name: # Scene name to load for this experiment parameters: name: # Experiment name runs: # Number of experiment runs group: # Joint group name timeout: # Experiment timeout output_directory: # Output directory for results file queries_regex: # Number of queries start_states_regex: # Start states goal_constraints_regex: # Goal constrains path_constraints_regex trajectory_constraints_regex predefined_poses_group: # Group where the predefined poses are specified predefined_poses: # List of named targets planning_pipelines: pipeline_names: # List of pipeline names to be loaded by moveit_cpp pipelines: # List of pipeline names to be used by the benchmark tool my_pipeline: # Example pipeline definition name: # Pipeline name planners: # List of planners of the pipeline to be tested parallel_pipelines: # List of parallel planning pipelines to be tested my_parallel_planning_pipeline: pipelines: # List of parallel planning pipelines planner_ids: # Ordered! list planner_ids used by the individual pipelines listed in 'pipeline'
Definition at line 80 of file BenchmarkOptions.h.
BenchmarkOptions::BenchmarkOptions | ( | const rclcpp::Node::SharedPtr & | node | ) |
Constructor.
Definition at line 51 of file BenchmarkOptions.cpp.
void BenchmarkOptions::getPlanningPipelineNames | ( | std::vector< std::string > & | planning_pipeline_names | ) | const |
Get all planning pipeline names.
Definition at line 163 of file BenchmarkOptions.cpp.
const std::string & moveit_ros_benchmarks::BenchmarkOptions::getWorkspaceFrameID | ( | ) | const |
const moveit_msgs::msg::WorkspaceParameters & moveit_ros_benchmarks::BenchmarkOptions::getWorkspaceParameters | ( | ) | const |
bool BenchmarkOptions::readBenchmarkOptions | ( | const rclcpp::Node::SharedPtr & | node | ) |
Definition at line 59 of file BenchmarkOptions.cpp.
void moveit_ros_benchmarks::BenchmarkOptions::readGoalOffset | ( | const rclcpp::Node::SharedPtr & | node | ) |
bool BenchmarkOptions::readPlannerConfigs | ( | const rclcpp::Node::SharedPtr & | node | ) |
void moveit_ros_benchmarks::BenchmarkOptions::readWorkspaceParameters | ( | const rclcpp::Node::SharedPtr & | node | ) |
std::string moveit_ros_benchmarks::BenchmarkOptions::benchmark_name |
Definition at line 107 of file BenchmarkOptions.h.
std::string moveit_ros_benchmarks::BenchmarkOptions::goal_constraint_regex |
Definition at line 112 of file BenchmarkOptions.h.
std::vector<double> moveit_ros_benchmarks::BenchmarkOptions::goal_offsets |
Definition at line 117 of file BenchmarkOptions.h.
std::string moveit_ros_benchmarks::BenchmarkOptions::group_name |
Definition at line 108 of file BenchmarkOptions.h.
std::string moveit_ros_benchmarks::BenchmarkOptions::hostname |
Warehouse parameters.
Definition at line 100 of file BenchmarkOptions.h.
std::string moveit_ros_benchmarks::BenchmarkOptions::output_directory |
Definition at line 109 of file BenchmarkOptions.h.
std::map<std::string, std::vector<std::pair<std::string, std::string> > > moveit_ros_benchmarks::BenchmarkOptions::parallel_planning_pipelines |
Definition at line 122 of file BenchmarkOptions.h.
std::string moveit_ros_benchmarks::BenchmarkOptions::path_constraint_regex |
Definition at line 113 of file BenchmarkOptions.h.
std::map<std::string, std::vector<std::string> > moveit_ros_benchmarks::BenchmarkOptions::planning_pipelines |
planner configurations
Definition at line 121 of file BenchmarkOptions.h.
int moveit_ros_benchmarks::BenchmarkOptions::port |
Definition at line 101 of file BenchmarkOptions.h.
std::vector<std::string> moveit_ros_benchmarks::BenchmarkOptions::predefined_poses |
Definition at line 115 of file BenchmarkOptions.h.
std::string moveit_ros_benchmarks::BenchmarkOptions::predefined_poses_group |
Definition at line 116 of file BenchmarkOptions.h.
std::string moveit_ros_benchmarks::BenchmarkOptions::query_regex |
Definition at line 110 of file BenchmarkOptions.h.
int moveit_ros_benchmarks::BenchmarkOptions::runs |
Benchmark parameters.
Definition at line 105 of file BenchmarkOptions.h.
std::string moveit_ros_benchmarks::BenchmarkOptions::scene_name |
Definition at line 102 of file BenchmarkOptions.h.
std::string moveit_ros_benchmarks::BenchmarkOptions::start_state_regex |
Definition at line 111 of file BenchmarkOptions.h.
double moveit_ros_benchmarks::BenchmarkOptions::timeout |
Definition at line 106 of file BenchmarkOptions.h.
std::string moveit_ros_benchmarks::BenchmarkOptions::trajectory_constraint_regex |
Definition at line 114 of file BenchmarkOptions.h.
moveit_msgs::msg::WorkspaceParameters moveit_ros_benchmarks::BenchmarkOptions::workspace |
Definition at line 124 of file BenchmarkOptions.h.