#include <BenchmarkOptions.h>
Public Member Functions | |
BenchmarkOptions () | |
Constructor. More... | |
BenchmarkOptions (const std::string &ros_namespace) | |
Constructor accepting a custom namespace for parameter lookup. More... | |
const std::string & | getBenchmarkName () const |
Get the reference name of the benchmark. More... | |
const std::string & | getGoalConstraintRegex () const |
Get the regex expression for matching the names of all goal constraints to plan to. More... | |
void | getGoalOffsets (std::vector< double > &offsets) const |
Get the constant position/orientation offset to be used for shifting all goal constraints. More... | |
const std::string & | getGroupName () const |
Get the name of the planning group to run the benchmark with. More... | |
const std::string & | getHostName () const |
Get the name of the warehouse database host server. More... | |
int | getNumRuns () const |
Get the specified number of benchmark query runs. More... | |
const std::string & | getOutputDirectory () const |
Get the target directory for the generated benchmark result data. More... | |
const std::string & | getPathConstraintRegex () const |
Get the regex expression for matching the names of all path constraints to plan with. More... | |
const std::map< std::string, std::vector< std::string > > & | getPlanningPipelineConfigurations () const |
Get all planning pipeline names mapped to their parameter configuration. More... | |
void | getPlanningPipelineNames (std::vector< std::string > &planning_pipeline_names) const |
Get all planning pipeline names. More... | |
int | getPort () const |
Get the port of the warehouse database host server. More... | |
const std::vector< std::string > & | getPredefinedPoses () const |
Get the names of all predefined poses to consider for planning. More... | |
const std::string & | getPredefinedPosesGroup () const |
Get the name of the planning group for which the predefined poses are defined. More... | |
const std::string & | getQueryRegex () const |
Get the regex expression for matching the names of all queries to run. More... | |
const std::string & | getSceneName () const |
Get the reference name of the planning scene stored inside the warehouse database. More... | |
const std::string & | getStartStateRegex () const |
Get the regex expression for matching the names of all start states to plan from. More... | |
double | getTimeout () const |
Get the maximum timeout per planning attempt. More... | |
const std::string & | getTrajectoryConstraintRegex () const |
Get the regex expression for matching the names of all trajectory constraints to plan with. More... | |
const std::string & | getWorkspaceFrameID () const |
const moveit_msgs::WorkspaceParameters & | getWorkspaceParameters () const |
void | setNamespace (const std::string &ros_namespace) |
Set the ROS namespace the node handle should use for parameter lookup. More... | |
virtual | ~BenchmarkOptions () |
Destructor. More... | |
Protected Member Functions | |
void | readBenchmarkOptions (const std::string &ros_namespace) |
void | readBenchmarkParameters (ros::NodeHandle &nh) |
void | readGoalOffset (ros::NodeHandle &nh) |
void | readPlannerConfigs (ros::NodeHandle &nh) |
void | readWarehouseOptions (ros::NodeHandle &nh) |
void | readWorkspaceParameters (ros::NodeHandle &nh) |
Protected Attributes | |
std::string | benchmark_name_ |
std::string | goal_constraint_regex_ |
double | goal_offsets [6] |
std::string | group_name_ |
std::string | hostname_ |
warehouse parameters More... | |
std::string | output_directory_ |
std::string | path_constraint_regex_ |
std::map< std::string, std::vector< std::string > > | planning_pipelines_ |
planner configurations More... | |
int | port_ |
std::vector< std::string > | predefined_poses_ |
std::string | predefined_poses_group_ |
std::string | query_regex_ |
int | runs_ |
benchmark parameters More... | |
std::string | scene_name_ |
std::string | start_state_regex_ |
double | timeout_ |
std::string | trajectory_constraint_regex_ |
moveit_msgs::WorkspaceParameters | workspace_ |
Definition at line 79 of file BenchmarkOptions.h.
BenchmarkOptions::BenchmarkOptions | ( | ) |
Constructor.
Definition at line 41 of file BenchmarkOptions.cpp.
BenchmarkOptions::BenchmarkOptions | ( | const std::string & | ros_namespace | ) |
Constructor accepting a custom namespace for parameter lookup.
Definition at line 45 of file BenchmarkOptions.cpp.
|
virtualdefault |
Destructor.
const std::string & BenchmarkOptions::getBenchmarkName | ( | ) | const |
Get the reference name of the benchmark.
Definition at line 99 of file BenchmarkOptions.cpp.
const std::string & BenchmarkOptions::getGoalConstraintRegex | ( | ) | const |
Get the regex expression for matching the names of all goal constraints to plan to.
Definition at line 124 of file BenchmarkOptions.cpp.
void BenchmarkOptions::getGoalOffsets | ( | std::vector< double > & | offsets | ) | const |
Get the constant position/orientation offset to be used for shifting all goal constraints.
Definition at line 149 of file BenchmarkOptions.cpp.
const std::string & BenchmarkOptions::getGroupName | ( | ) | const |
Get the name of the planning group to run the benchmark with.
Definition at line 104 of file BenchmarkOptions.cpp.
const std::string & BenchmarkOptions::getHostName | ( | ) | const |
Get the name of the warehouse database host server.
Definition at line 74 of file BenchmarkOptions.cpp.
int BenchmarkOptions::getNumRuns | ( | ) | const |
Get the specified number of benchmark query runs.
Definition at line 89 of file BenchmarkOptions.cpp.
const std::string & BenchmarkOptions::getOutputDirectory | ( | ) | const |
Get the target directory for the generated benchmark result data.
Definition at line 109 of file BenchmarkOptions.cpp.
const std::string & BenchmarkOptions::getPathConstraintRegex | ( | ) | const |
Get the regex expression for matching the names of all path constraints to plan with.
Definition at line 129 of file BenchmarkOptions.cpp.
const std::map< std::string, std::vector< std::string > > & BenchmarkOptions::getPlanningPipelineConfigurations | ( | ) | const |
Get all planning pipeline names mapped to their parameter configuration.
Definition at line 155 of file BenchmarkOptions.cpp.
void BenchmarkOptions::getPlanningPipelineNames | ( | std::vector< std::string > & | planning_pipeline_names | ) | const |
Get all planning pipeline names.
Definition at line 160 of file BenchmarkOptions.cpp.
int BenchmarkOptions::getPort | ( | ) | const |
Get the port of the warehouse database host server.
Definition at line 79 of file BenchmarkOptions.cpp.
const std::vector< std::string > & BenchmarkOptions::getPredefinedPoses | ( | ) | const |
Get the names of all predefined poses to consider for planning.
Definition at line 139 of file BenchmarkOptions.cpp.
const std::string & BenchmarkOptions::getPredefinedPosesGroup | ( | ) | const |
Get the name of the planning group for which the predefined poses are defined.
Definition at line 144 of file BenchmarkOptions.cpp.
const std::string & BenchmarkOptions::getQueryRegex | ( | ) | const |
Get the regex expression for matching the names of all queries to run.
Definition at line 114 of file BenchmarkOptions.cpp.
const std::string & BenchmarkOptions::getSceneName | ( | ) | const |
Get the reference name of the planning scene stored inside the warehouse database.
Definition at line 84 of file BenchmarkOptions.cpp.
const std::string & BenchmarkOptions::getStartStateRegex | ( | ) | const |
Get the regex expression for matching the names of all start states to plan from.
Definition at line 119 of file BenchmarkOptions.cpp.
double BenchmarkOptions::getTimeout | ( | ) | const |
Get the maximum timeout per planning attempt.
Definition at line 94 of file BenchmarkOptions.cpp.
const std::string & BenchmarkOptions::getTrajectoryConstraintRegex | ( | ) | const |
Get the regex expression for matching the names of all trajectory constraints to plan with.
Definition at line 134 of file BenchmarkOptions.cpp.
const std::string & BenchmarkOptions::getWorkspaceFrameID | ( | ) | const |
Definition at line 167 of file BenchmarkOptions.cpp.
const moveit_msgs::WorkspaceParameters & BenchmarkOptions::getWorkspaceParameters | ( | ) | const |
Definition at line 172 of file BenchmarkOptions.cpp.
|
protected |
Definition at line 57 of file BenchmarkOptions.cpp.
|
protected |
Definition at line 190 of file BenchmarkOptions.cpp.
|
protected |
|
protected |
Definition at line 250 of file BenchmarkOptions.cpp.
|
protected |
Definition at line 177 of file BenchmarkOptions.cpp.
|
protected |
Definition at line 233 of file BenchmarkOptions.cpp.
void BenchmarkOptions::setNamespace | ( | const std::string & | ros_namespace | ) |
Set the ROS namespace the node handle should use for parameter lookup.
Definition at line 52 of file BenchmarkOptions.cpp.
|
protected |
Definition at line 185 of file BenchmarkOptions.h.
|
protected |
Definition at line 190 of file BenchmarkOptions.h.
|
protected |
Definition at line 195 of file BenchmarkOptions.h.
|
protected |
Definition at line 186 of file BenchmarkOptions.h.
|
protected |
warehouse parameters
Definition at line 178 of file BenchmarkOptions.h.
|
protected |
Definition at line 187 of file BenchmarkOptions.h.
|
protected |
Definition at line 191 of file BenchmarkOptions.h.
|
protected |
planner configurations
Definition at line 198 of file BenchmarkOptions.h.
|
protected |
Definition at line 179 of file BenchmarkOptions.h.
|
protected |
Definition at line 193 of file BenchmarkOptions.h.
|
protected |
Definition at line 194 of file BenchmarkOptions.h.
|
protected |
Definition at line 188 of file BenchmarkOptions.h.
|
protected |
benchmark parameters
Definition at line 183 of file BenchmarkOptions.h.
|
protected |
Definition at line 180 of file BenchmarkOptions.h.
|
protected |
Definition at line 189 of file BenchmarkOptions.h.
|
protected |
Definition at line 184 of file BenchmarkOptions.h.
|
protected |
Definition at line 192 of file BenchmarkOptions.h.
|
protected |
Definition at line 200 of file BenchmarkOptions.h.