Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
moveit_ros_benchmarks::BenchmarkOptions Class Reference

#include <BenchmarkOptions.h>

Public Member Functions

 BenchmarkOptions ()
 
 BenchmarkOptions (const std::string &ros_namespace)
 
const std::string & getBenchmarkName () const
 
const std::string & getGoalConstraintRegex () const
 
void getGoalOffsets (std::vector< double > &offsets) const
 
const std::string & getGroupName () const
 
const std::string & getHostName () const
 
int getNumRuns () const
 
const std::string & getOutputDirectory () const
 
const std::string & getPathConstraintRegex () const
 
const std::map< std::string, std::vector< std::string > > & getPlannerConfigurations () const
 
void getPlannerPluginList (std::vector< std::string > &plugin_list) const
 
int getPort () const
 
const std::string & getQueryRegex () const
 
const std::string & getSceneName () const
 
const std::string & getStartStateRegex () const
 
double getTimeout () const
 
const std::string & getTrajectoryConstraintRegex () const
 
const std::string & getWorkspaceFrameID () const
 
const moveit_msgs::WorkspaceParameters & getWorkspaceParameters () const
 
void setNamespace (const std::string &ros_namespace)
 
virtual ~BenchmarkOptions ()
 

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 > > planners_
 planner configurations More...
 
int port_
 
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_
 

Detailed Description

Definition at line 48 of file BenchmarkOptions.h.

Constructor & Destructor Documentation

BenchmarkOptions::BenchmarkOptions ( )

Definition at line 41 of file BenchmarkOptions.cpp.

BenchmarkOptions::BenchmarkOptions ( const std::string &  ros_namespace)

Definition at line 45 of file BenchmarkOptions.cpp.

BenchmarkOptions::~BenchmarkOptions ( )
virtual

Definition at line 50 of file BenchmarkOptions.cpp.

Member Function Documentation

const std::string & BenchmarkOptions::getBenchmarkName ( ) const

Definition at line 101 of file BenchmarkOptions.cpp.

const std::string & BenchmarkOptions::getGoalConstraintRegex ( ) const

Definition at line 126 of file BenchmarkOptions.cpp.

void BenchmarkOptions::getGoalOffsets ( std::vector< double > &  offsets) const

Definition at line 141 of file BenchmarkOptions.cpp.

const std::string & BenchmarkOptions::getGroupName ( ) const

Definition at line 106 of file BenchmarkOptions.cpp.

const std::string & BenchmarkOptions::getHostName ( ) const

Definition at line 76 of file BenchmarkOptions.cpp.

int BenchmarkOptions::getNumRuns ( ) const

Definition at line 91 of file BenchmarkOptions.cpp.

const std::string & BenchmarkOptions::getOutputDirectory ( ) const

Definition at line 111 of file BenchmarkOptions.cpp.

const std::string & BenchmarkOptions::getPathConstraintRegex ( ) const

Definition at line 131 of file BenchmarkOptions.cpp.

const std::map< std::string, std::vector< std::string > > & BenchmarkOptions::getPlannerConfigurations ( ) const

Definition at line 147 of file BenchmarkOptions.cpp.

void BenchmarkOptions::getPlannerPluginList ( std::vector< std::string > &  plugin_list) const

Definition at line 152 of file BenchmarkOptions.cpp.

int BenchmarkOptions::getPort ( ) const

Definition at line 81 of file BenchmarkOptions.cpp.

const std::string & BenchmarkOptions::getQueryRegex ( ) const

Definition at line 116 of file BenchmarkOptions.cpp.

const std::string & BenchmarkOptions::getSceneName ( ) const

Definition at line 86 of file BenchmarkOptions.cpp.

const std::string & BenchmarkOptions::getStartStateRegex ( ) const

Definition at line 121 of file BenchmarkOptions.cpp.

double BenchmarkOptions::getTimeout ( ) const

Definition at line 96 of file BenchmarkOptions.cpp.

const std::string & BenchmarkOptions::getTrajectoryConstraintRegex ( ) const

Definition at line 136 of file BenchmarkOptions.cpp.

const std::string & BenchmarkOptions::getWorkspaceFrameID ( ) const

Definition at line 160 of file BenchmarkOptions.cpp.

const moveit_msgs::WorkspaceParameters & BenchmarkOptions::getWorkspaceParameters ( ) const

Definition at line 165 of file BenchmarkOptions.cpp.

void BenchmarkOptions::readBenchmarkOptions ( const std::string &  ros_namespace)
protected

Definition at line 59 of file BenchmarkOptions.cpp.

void BenchmarkOptions::readBenchmarkParameters ( ros::NodeHandle nh)
protected

Definition at line 183 of file BenchmarkOptions.cpp.

void moveit_ros_benchmarks::BenchmarkOptions::readGoalOffset ( ros::NodeHandle nh)
protected
void BenchmarkOptions::readPlannerConfigs ( ros::NodeHandle nh)
protected

Definition at line 241 of file BenchmarkOptions.cpp.

void BenchmarkOptions::readWarehouseOptions ( ros::NodeHandle nh)
protected

Definition at line 170 of file BenchmarkOptions.cpp.

void BenchmarkOptions::readWorkspaceParameters ( ros::NodeHandle nh)
protected

Definition at line 224 of file BenchmarkOptions.cpp.

void BenchmarkOptions::setNamespace ( const std::string &  ros_namespace)

Definition at line 54 of file BenchmarkOptions.cpp.

Member Data Documentation

std::string moveit_ros_benchmarks::BenchmarkOptions::benchmark_name_
protected

Definition at line 96 of file BenchmarkOptions.h.

std::string moveit_ros_benchmarks::BenchmarkOptions::goal_constraint_regex_
protected

Definition at line 101 of file BenchmarkOptions.h.

double moveit_ros_benchmarks::BenchmarkOptions::goal_offsets[6]
protected

Definition at line 104 of file BenchmarkOptions.h.

std::string moveit_ros_benchmarks::BenchmarkOptions::group_name_
protected

Definition at line 97 of file BenchmarkOptions.h.

std::string moveit_ros_benchmarks::BenchmarkOptions::hostname_
protected

warehouse parameters

Definition at line 89 of file BenchmarkOptions.h.

std::string moveit_ros_benchmarks::BenchmarkOptions::output_directory_
protected

Definition at line 98 of file BenchmarkOptions.h.

std::string moveit_ros_benchmarks::BenchmarkOptions::path_constraint_regex_
protected

Definition at line 102 of file BenchmarkOptions.h.

std::map<std::string, std::vector<std::string> > moveit_ros_benchmarks::BenchmarkOptions::planners_
protected

planner configurations

Definition at line 107 of file BenchmarkOptions.h.

int moveit_ros_benchmarks::BenchmarkOptions::port_
protected

Definition at line 90 of file BenchmarkOptions.h.

std::string moveit_ros_benchmarks::BenchmarkOptions::query_regex_
protected

Definition at line 99 of file BenchmarkOptions.h.

int moveit_ros_benchmarks::BenchmarkOptions::runs_
protected

benchmark parameters

Definition at line 94 of file BenchmarkOptions.h.

std::string moveit_ros_benchmarks::BenchmarkOptions::scene_name_
protected

Definition at line 91 of file BenchmarkOptions.h.

std::string moveit_ros_benchmarks::BenchmarkOptions::start_state_regex_
protected

Definition at line 100 of file BenchmarkOptions.h.

double moveit_ros_benchmarks::BenchmarkOptions::timeout_
protected

Definition at line 95 of file BenchmarkOptions.h.

std::string moveit_ros_benchmarks::BenchmarkOptions::trajectory_constraint_regex_
protected

Definition at line 103 of file BenchmarkOptions.h.

moveit_msgs::WorkspaceParameters moveit_ros_benchmarks::BenchmarkOptions::workspace_
protected

Definition at line 109 of file BenchmarkOptions.h.


The documentation for this class was generated from the following files:


benchmarks
Author(s): Ryan Luna
autogenerated on Sun Oct 18 2020 13:18:44