moveit2
The MoveIt Motion Planning Framework for ROS 2.
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 #pragma once
38 
39 #include <rclcpp/node.hpp>
40 #include <string>
41 #include <map>
42 #include <vector>
43 #include <moveit_msgs/msg/workspace_parameters.hpp>
44 
45 namespace moveit_ros_benchmarks
46 {
48 {
49 public:
53  BenchmarkOptions(const rclcpp::Node::SharedPtr& node);
55  virtual ~BenchmarkOptions();
56 
58  // void setNamespace(const std::string& ros_namespace);
59 
61  const std::string& getHostName() const;
63  int getPort() const;
65  const std::string& getSceneName() const;
66 
68  int getNumRuns() const;
70  double getTimeout() const;
72  const std::string& getBenchmarkName() const;
74  const std::string& getGroupName() const;
76  const std::string& getOutputDirectory() const;
78  const std::string& getQueryRegex() const;
80  const std::string& getStartStateRegex() const;
82  const std::string& getGoalConstraintRegex() const;
84  const std::string& getPathConstraintRegex() const;
86  const std::string& getTrajectoryConstraintRegex() const;
88  const std::vector<std::string>& getPredefinedPoses() const;
90  const std::string& getPredefinedPosesGroup() const;
92  void getGoalOffsets(std::vector<double>& offsets) const;
94  const std::map<std::string, std::vector<std::string>>& getPlanningPipelineConfigurations() const;
96  void getPlanningPipelineNames(std::vector<std::string>& planning_pipeline_names) const;
97 
98  /* \brief Get the frame id of the planning workspace */
99  const std::string& getWorkspaceFrameID() const;
100  /* \brief Get the parameter set of the planning workspace */
101  const moveit_msgs::msg::WorkspaceParameters& getWorkspaceParameters() const;
102 
103 protected:
104  void readBenchmarkOptions(const rclcpp::Node::SharedPtr& node);
105 
106  void readWarehouseOptions(const rclcpp::Node::SharedPtr& node);
107  void readBenchmarkParameters(const rclcpp::Node::SharedPtr& node);
108  void readPlannerConfigs(const rclcpp::Node::SharedPtr& node);
109 
110  void readWorkspaceParameters(const rclcpp::Node::SharedPtr& node);
111  void readGoalOffset(const rclcpp::Node::SharedPtr& node);
112 
114  std::string hostname_;
115  int port_;
116  std::string scene_name_;
117 
119  int runs_;
120  double timeout_;
121  std::string benchmark_name_;
122  std::string group_name_;
123  std::string output_directory_;
124  std::string query_regex_;
125  std::string start_state_regex_;
129  std::vector<std::string> predefined_poses_;
131  double goal_offsets[6];
132 
134  std::map<std::string, std::vector<std::string>> planning_pipelines_;
135 
136  moveit_msgs::msg::WorkspaceParameters workspace_;
137 };
138 } // namespace moveit_ros_benchmarks
const moveit_msgs::msg::WorkspaceParameters & getWorkspaceParameters() const
const std::string & getPathConstraintRegex() const
Get the regex expression for matching the names of all path constraints to plan with.
const std::map< std::string, std::vector< std::string > > & getPlanningPipelineConfigurations() const
Get all planning pipeline names mapped to their parameter configuration.
std::vector< std::string > predefined_poses_
const std::string & getBenchmarkName() const
Get the reference name of the benchmark.
void readGoalOffset(const rclcpp::Node::SharedPtr &node)
int getNumRuns() const
Get the specified number of benchmark query runs.
double getTimeout() const
Get the maximum timeout per planning attempt.
const std::string & getHostName() const
Set the ROS namespace the node handle should use for parameter lookup.
void readWorkspaceParameters(const rclcpp::Node::SharedPtr &node)
void readBenchmarkParameters(const rclcpp::Node::SharedPtr &node)
void readBenchmarkOptions(const rclcpp::Node::SharedPtr &node)
moveit_msgs::msg::WorkspaceParameters workspace_
void getPlanningPipelineNames(std::vector< std::string > &planning_pipeline_names) const
Get all planning pipeline names.
int getPort() const
Get the port of the warehouse database host server.
void getGoalOffsets(std::vector< double > &offsets) const
Get the constant position/orientation offset to be used for shifting all goal constraints.
const std::string & getQueryRegex() const
Get the regex expression for matching the names of all queries to run.
const std::vector< std::string > & getPredefinedPoses() const
Get the names of all predefined poses to consider for planning.
std::map< std::string, std::vector< std::string > > planning_pipelines_
planner configurations
const std::string & getGroupName() const
Get the name of the planning group to run the benchmark with.
const std::string & getWorkspaceFrameID() const
const std::string & getPredefinedPosesGroup() const
Get the name of the planning group for which the predefined poses are defined.
const std::string & getGoalConstraintRegex() const
Get the regex expression for matching the names of all goal constraints to plan to.
void readWarehouseOptions(const rclcpp::Node::SharedPtr &node)
const std::string & getStartStateRegex() const
Get the regex expression for matching the names of all start states to plan from.
const std::string & getSceneName() const
Get the reference name of the planning scene stored inside the warehouse database.
void readPlannerConfigs(const rclcpp::Node::SharedPtr &node)
std::string hostname_
warehouse parameters
const std::string & getOutputDirectory() const
Get the target directory for the generated benchmark result data.
const std::string & getTrajectoryConstraintRegex() const
Get the regex expression for matching the names of all trajectory constraints to plan with.