39 #include <rclcpp/node.hpp>
43 #include <moveit_msgs/msg/workspace_parameters.hpp>
45 static constexpr
int CARTESIAN_DOF = 6;
118 std::vector<double>(CARTESIAN_DOF);
Options to configure a benchmark experiment. The configuration is provided via ROS2 parameters.
BenchmarkOptions(const rclcpp::Node::SharedPtr &node)
Constructor.
std::string output_directory
const moveit_msgs::msg::WorkspaceParameters & getWorkspaceParameters() const
void readGoalOffset(const rclcpp::Node::SharedPtr &node)
std::string benchmark_name
void readWorkspaceParameters(const rclcpp::Node::SharedPtr &node)
std::string goal_constraint_regex
std::string path_constraint_regex
std::map< std::string, std::vector< std::string > > planning_pipelines
planner configurations
std::string trajectory_constraint_regex
moveit_msgs::msg::WorkspaceParameters workspace
std::map< std::string, std::vector< std::pair< std::string, std::string > > > parallel_planning_pipelines
std::string start_state_regex
std::string predefined_poses_group
void getPlanningPipelineNames(std::vector< std::string > &planning_pipeline_names) const
Get all planning pipeline names.
int runs
Benchmark parameters.
bool readBenchmarkOptions(const rclcpp::Node::SharedPtr &node)
std::string hostname
Warehouse parameters.
const std::string & getWorkspaceFrameID() const
bool readPlannerConfigs(const rclcpp::Node::SharedPtr &node)
std::vector< double > goal_offsets
std::vector< std::string > predefined_poses