39 #include <rclcpp/node.hpp>
43 #include <moveit_msgs/msg/workspace_parameters.hpp>
const moveit_msgs::msg::WorkspaceParameters & getWorkspaceParameters() const
const std::string & getPathConstraintRegex() const
Get the regex expression for matching the names of all path constraints to plan with.
const std::map< std::string, std::vector< std::string > > & getPlanningPipelineConfigurations() const
Get all planning pipeline names mapped to their parameter configuration.
std::vector< std::string > predefined_poses_
virtual ~BenchmarkOptions()
Destructor.
const std::string & getBenchmarkName() const
Get the reference name of the benchmark.
void readGoalOffset(const rclcpp::Node::SharedPtr &node)
int getNumRuns() const
Get the specified number of benchmark query runs.
double getTimeout() const
Get the maximum timeout per planning attempt.
std::string predefined_poses_group_
std::string path_constraint_regex_
const std::string & getHostName() const
Set the ROS namespace the node handle should use for parameter lookup.
void readWorkspaceParameters(const rclcpp::Node::SharedPtr &node)
void readBenchmarkParameters(const rclcpp::Node::SharedPtr &node)
std::string output_directory_
std::string start_state_regex_
void readBenchmarkOptions(const rclcpp::Node::SharedPtr &node)
std::string goal_constraint_regex_
moveit_msgs::msg::WorkspaceParameters workspace_
void getPlanningPipelineNames(std::vector< std::string > &planning_pipeline_names) const
Get all planning pipeline names.
int getPort() const
Get the port of the warehouse database host server.
void getGoalOffsets(std::vector< double > &offsets) const
Get the constant position/orientation offset to be used for shifting all goal constraints.
const std::string & getQueryRegex() const
Get the regex expression for matching the names of all queries to run.
std::string trajectory_constraint_regex_
const std::vector< std::string > & getPredefinedPoses() const
Get the names of all predefined poses to consider for planning.
BenchmarkOptions()
Constructor.
std::map< std::string, std::vector< std::string > > planning_pipelines_
planner configurations
const std::string & getGroupName() const
Get the name of the planning group to run the benchmark with.
const std::string & getWorkspaceFrameID() const
const std::string & getPredefinedPosesGroup() const
Get the name of the planning group for which the predefined poses are defined.
const std::string & getGoalConstraintRegex() const
Get the regex expression for matching the names of all goal constraints to plan to.
void readWarehouseOptions(const rclcpp::Node::SharedPtr &node)
int runs_
benchmark parameters
const std::string & getStartStateRegex() const
Get the regex expression for matching the names of all start states to plan from.
const std::string & getSceneName() const
Get the reference name of the planning scene stored inside the warehouse database.
std::string benchmark_name_
void readPlannerConfigs(const rclcpp::Node::SharedPtr &node)
std::string hostname_
warehouse parameters
const std::string & getOutputDirectory() const
Get the target directory for the generated benchmark result data.
const std::string & getTrajectoryConstraintRegex() const
Get the regex expression for matching the names of all trajectory constraints to plan with.