moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <BenchmarkOptions.h>
Public Member Functions | |
BenchmarkOptions () | |
Constructor. More... | |
BenchmarkOptions (const rclcpp::Node::SharedPtr &node) | |
Constructor accepting a custom namespace for parameter lookup. More... | |
virtual | ~BenchmarkOptions () |
Destructor. More... | |
const std::string & | getHostName () const |
Set the ROS namespace the node handle should use for parameter lookup. More... | |
int | getPort () const |
Get the port of the warehouse database host server. More... | |
const std::string & | getSceneName () const |
Get the reference name of the planning scene stored inside the warehouse database. More... | |
int | getNumRuns () const |
Get the specified number of benchmark query runs. More... | |
double | getTimeout () const |
Get the maximum timeout per planning attempt. More... | |
const std::string & | getBenchmarkName () const |
Get the reference name of the benchmark. More... | |
const std::string & | getGroupName () const |
Get the name of the planning group to run the benchmark with. More... | |
const std::string & | getOutputDirectory () const |
Get the target directory for the generated benchmark result data. More... | |
const std::string & | getQueryRegex () const |
Get the regex expression for matching the names of all queries to run. More... | |
const std::string & | getStartStateRegex () const |
Get the regex expression for matching the names of all start states to plan from. More... | |
const std::string & | getGoalConstraintRegex () const |
Get the regex expression for matching the names of all goal constraints to plan to. More... | |
const std::string & | getPathConstraintRegex () const |
Get the regex expression for matching the names of all path constraints to plan with. More... | |
const std::string & | getTrajectoryConstraintRegex () const |
Get the regex expression for matching the names of all trajectory constraints to plan with. 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... | |
void | getGoalOffsets (std::vector< double > &offsets) const |
Get the constant position/orientation offset to be used for shifting all goal constraints. 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... | |
const std::string & | getWorkspaceFrameID () const |
const moveit_msgs::msg::WorkspaceParameters & | getWorkspaceParameters () const |
Protected Member Functions | |
void | readBenchmarkOptions (const rclcpp::Node::SharedPtr &node) |
void | readWarehouseOptions (const rclcpp::Node::SharedPtr &node) |
void | readBenchmarkParameters (const rclcpp::Node::SharedPtr &node) |
void | readPlannerConfigs (const rclcpp::Node::SharedPtr &node) |
void | readWorkspaceParameters (const rclcpp::Node::SharedPtr &node) |
void | readGoalOffset (const rclcpp::Node::SharedPtr &node) |
Protected Attributes | |
std::string | hostname_ |
warehouse parameters More... | |
int | port_ |
std::string | scene_name_ |
int | runs_ |
benchmark parameters More... | |
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_ |
double | goal_offsets [6] |
std::map< std::string, std::vector< std::string > > | planning_pipelines_ |
planner configurations More... | |
moveit_msgs::msg::WorkspaceParameters | workspace_ |
Definition at line 47 of file BenchmarkOptions.h.
BenchmarkOptions::BenchmarkOptions | ( | ) |
Constructor.
Definition at line 43 of file BenchmarkOptions.cpp.
BenchmarkOptions::BenchmarkOptions | ( | const rclcpp::Node::SharedPtr & | node | ) |
Constructor accepting a custom namespace for parameter lookup.
Definition at line 47 of file BenchmarkOptions.cpp.
|
virtualdefault |
Destructor.
const std::string & BenchmarkOptions::getBenchmarkName | ( | ) | const |
Get the reference name of the benchmark.
Definition at line 98 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 123 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 148 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 103 of file BenchmarkOptions.cpp.
const std::string & BenchmarkOptions::getHostName | ( | ) | const |
Set the ROS namespace the node handle should use for parameter lookup.
Get the name of the warehouse database host server
Definition at line 73 of file BenchmarkOptions.cpp.
int BenchmarkOptions::getNumRuns | ( | ) | const |
Get the specified number of benchmark query runs.
Definition at line 88 of file BenchmarkOptions.cpp.
const std::string & BenchmarkOptions::getOutputDirectory | ( | ) | const |
Get the target directory for the generated benchmark result data.
Definition at line 108 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 128 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 154 of file BenchmarkOptions.cpp.
void BenchmarkOptions::getPlanningPipelineNames | ( | std::vector< std::string > & | planning_pipeline_names | ) | const |
Get all planning pipeline names.
Definition at line 159 of file BenchmarkOptions.cpp.
int BenchmarkOptions::getPort | ( | ) | const |
Get the port of the warehouse database host server.
Definition at line 78 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 138 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 143 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 113 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 83 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 118 of file BenchmarkOptions.cpp.
double BenchmarkOptions::getTimeout | ( | ) | const |
Get the maximum timeout per planning attempt.
Definition at line 93 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 133 of file BenchmarkOptions.cpp.
const std::string & BenchmarkOptions::getWorkspaceFrameID | ( | ) | const |
Definition at line 166 of file BenchmarkOptions.cpp.
const moveit_msgs::msg::WorkspaceParameters & BenchmarkOptions::getWorkspaceParameters | ( | ) | const |
Definition at line 171 of file BenchmarkOptions.cpp.
|
protected |
Definition at line 59 of file BenchmarkOptions.cpp.
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
Definition at line 240 of file BenchmarkOptions.cpp.
|
protected |
Definition at line 121 of file BenchmarkOptions.h.
|
protected |
Definition at line 126 of file BenchmarkOptions.h.
|
protected |
Definition at line 131 of file BenchmarkOptions.h.
|
protected |
Definition at line 122 of file BenchmarkOptions.h.
|
protected |
warehouse parameters
Definition at line 114 of file BenchmarkOptions.h.
|
protected |
Definition at line 123 of file BenchmarkOptions.h.
|
protected |
Definition at line 127 of file BenchmarkOptions.h.
|
protected |
planner configurations
Definition at line 134 of file BenchmarkOptions.h.
|
protected |
Definition at line 115 of file BenchmarkOptions.h.
|
protected |
Definition at line 129 of file BenchmarkOptions.h.
|
protected |
Definition at line 130 of file BenchmarkOptions.h.
|
protected |
Definition at line 124 of file BenchmarkOptions.h.
|
protected |
benchmark parameters
Definition at line 119 of file BenchmarkOptions.h.
|
protected |
Definition at line 116 of file BenchmarkOptions.h.
|
protected |
Definition at line 125 of file BenchmarkOptions.h.
|
protected |
Definition at line 120 of file BenchmarkOptions.h.
|
protected |
Definition at line 128 of file BenchmarkOptions.h.
|
protected |
Definition at line 136 of file BenchmarkOptions.h.