37 #ifndef MOVEIT_ROS_BENCHMARK_BENCHMARK_OPTIONS_ 38 #define MOVEIT_ROS_BENCHMARK_BENCHMARK_OPTIONS_ 44 #include <moveit_msgs/WorkspaceParameters.h> 107 std::map<std::string, std::vector<std::string>>
planners_;
std::string path_constraint_regex_
const std::string & getSceneName() const
std::string hostname_
warehouse parameters
const std::string & getOutputDirectory() const
double getTimeout() const
const std::string & getGroupName() const
const std::string & getPathConstraintRegex() const
void readWarehouseOptions(ros::NodeHandle &nh)
const std::string & getHostName() const
void readBenchmarkParameters(ros::NodeHandle &nh)
moveit_msgs::WorkspaceParameters workspace_
std::string trajectory_constraint_regex_
const std::string & getWorkspaceFrameID() const
void readPlannerConfigs(ros::NodeHandle &nh)
const std::string & getGoalConstraintRegex() const
void readBenchmarkOptions(const std::string &ros_namespace)
const std::string & getStartStateRegex() const
void getGoalOffsets(std::vector< double > &offsets) const
void readGoalOffset(ros::NodeHandle &nh)
std::string goal_constraint_regex_
void setNamespace(const std::string &ros_namespace)
std::string benchmark_name_
std::string output_directory_
virtual ~BenchmarkOptions()
const std::string & getTrajectoryConstraintRegex() const
const std::string & getQueryRegex() const
const std::string & getBenchmarkName() const
int runs_
benchmark parameters
std::string start_state_regex_
const moveit_msgs::WorkspaceParameters & getWorkspaceParameters() const
void readWorkspaceParameters(ros::NodeHandle &nh)
const std::map< std::string, std::vector< std::string > > & getPlannerConfigurations() const
std::map< std::string, std::vector< std::string > > planners_
planner configurations
void getPlannerPluginList(std::vector< std::string > &plugin_list) const