BenchmarkOptions.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2015, Rice University
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Rice University nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 /* Author: Ryan Luna */
36 
37 #ifndef MOVEIT_ROS_BENCHMARK_BENCHMARK_OPTIONS_
38 #define MOVEIT_ROS_BENCHMARK_BENCHMARK_OPTIONS_
39 
40 #include <string>
41 #include <map>
42 #include <vector>
43 #include <ros/ros.h>
44 #include <moveit_msgs/WorkspaceParameters.h>
45 
46 namespace moveit_ros_benchmarks
47 {
49 {
50 public:
52  BenchmarkOptions(const std::string& ros_namespace);
53  virtual ~BenchmarkOptions();
54 
55  void setNamespace(const std::string& ros_namespace);
56 
57  const std::string& getHostName() const;
58  int getPort() const;
59  const std::string& getSceneName() const;
60 
61  int getNumRuns() const;
62  double getTimeout() const;
63  const std::string& getBenchmarkName() const;
64  const std::string& getGroupName() const;
65  const std::string& getOutputDirectory() const;
66  const std::string& getQueryRegex() const;
67  const std::string& getStartStateRegex() const;
68  const std::string& getGoalConstraintRegex() const;
69  const std::string& getPathConstraintRegex() const;
70  const std::string& getTrajectoryConstraintRegex() const;
71  void getGoalOffsets(std::vector<double>& offsets) const;
72  const std::map<std::string, std::vector<std::string>>& getPlannerConfigurations() const;
73  void getPlannerPluginList(std::vector<std::string>& plugin_list) const;
74 
75  const std::string& getWorkspaceFrameID() const;
76  const moveit_msgs::WorkspaceParameters& getWorkspaceParameters() const;
77 
78 protected:
79  void readBenchmarkOptions(const std::string& ros_namespace);
80 
84 
87 
89  std::string hostname_;
90  int port_;
91  std::string scene_name_;
92 
94  int runs_;
95  double timeout_;
96  std::string benchmark_name_;
97  std::string group_name_;
98  std::string output_directory_;
99  std::string query_regex_;
100  std::string start_state_regex_;
104  double goal_offsets[6];
105 
107  std::map<std::string, std::vector<std::string>> planners_;
108 
109  moveit_msgs::WorkspaceParameters workspace_;
110 };
111 }
112 
113 #endif
const std::string & getSceneName() const
std::string hostname_
warehouse parameters
const std::string & getOutputDirectory() 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_
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)
void setNamespace(const std::string &ros_namespace)
const std::string & getTrajectoryConstraintRegex() const
const std::string & getQueryRegex() const
const std::string & getBenchmarkName() const
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


benchmarks
Author(s): Ryan Luna
autogenerated on Wed Jul 10 2019 04:04:08