Struct BenchmarkOptions

Struct Documentation

struct BenchmarkOptions

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’

Public 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 Members

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::vector<double>(CARTESIAN_DOF)
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