moveit2
The MoveIt Motion Planning Framework for ROS 2.
CombinePredefinedPosesBenchmark.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2019, PickNik Inc.
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 PickNik Inc. 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: Henning Kayser */
36 /* Description: A simple benchmark that plans trajectories for all combinations of specified predefined poses */
37 
38 // MoveIt Benchmark
41 
42 // MoveIt
46 
47 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.benchmarks.combine_predefined_poses_benchmark");
48 
49 namespace moveit_ros_benchmarks
50 {
52 {
53 public:
54  CombinePredefinedPosesBenchmark(const rclcpp::Node::SharedPtr& node) : BenchmarkExecutor(node)
55  {
56  }
57 
58  bool loadBenchmarkQueryData(const BenchmarkOptions& opts, moveit_msgs::msg::PlanningScene& scene_msg,
59  std::vector<StartState>& start_states, std::vector<PathConstraints>& path_constraints,
60  std::vector<PathConstraints>& goal_constraints,
61  std::vector<TrajectoryConstraints>& traj_constraints,
62  std::vector<BenchmarkRequest>& queries) override
63  {
64  // Load planning scene
65  if (!psm_)
66  psm_ = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>(node_, "robot_description");
67  if (!psm_->newPlanningSceneMessage(scene_msg))
68  {
69  RCLCPP_ERROR(LOGGER, "Failed to load planning scene");
70  return false;
71  }
72 
73  // Load robot model
74  if (!psm_->getRobotModel())
75  {
76  RCLCPP_ERROR(LOGGER, "Failed to load robot model");
77  return false;
78  }
79 
80  // Select planning group to use for predefined poses
81  std::string predefined_poses_group = opts.getPredefinedPosesGroup();
82  if (predefined_poses_group.empty())
83  {
84  RCLCPP_WARN(LOGGER, "Parameter predefined_poses_group is not set, using default planning group instead");
85  predefined_poses_group = opts.getGroupName();
86  }
87  const auto& joint_model_group = psm_->getRobotModel()->getJointModelGroup(predefined_poses_group);
88  if (!joint_model_group)
89  {
90  RCLCPP_ERROR_STREAM(LOGGER, "Robot model has no joint model group named '" << predefined_poses_group << "'");
91  return false;
92  }
93 
94  // Iterate over all predefined poses and use each as start and goal states
95  moveit::core::RobotState robot_state(psm_->getRobotModel());
96  start_states.clear();
97  goal_constraints.clear();
98  for (const auto& pose_id : opts.getPredefinedPoses())
99  {
100  if (!robot_state.setToDefaultValues(joint_model_group, pose_id))
101  {
102  RCLCPP_WARN_STREAM(LOGGER, "Failed to set robot state to named target '" << pose_id << "'");
103  continue;
104  }
105  // Create start state
106  start_states.emplace_back();
107  start_states.back().name = pose_id;
108  moveit::core::robotStateToRobotStateMsg(robot_state, start_states.back().state);
109 
110  // Create goal constraints
111  goal_constraints.emplace_back();
112  goal_constraints.back().name = pose_id;
113  goal_constraints.back().constraints.push_back(
114  kinematic_constraints::constructGoalConstraints(robot_state, joint_model_group));
115  }
116  if (start_states.empty() || goal_constraints.empty())
117  {
118  RCLCPP_ERROR_STREAM(LOGGER, "Failed to init start and goal states from predefined_poses");
119  return false;
120  }
121 
122  // We don't use path/trajectory constraints or custom queries
123  path_constraints.clear();
124  traj_constraints.clear();
125  queries.clear();
126  return true;
127  }
128 
129 private:
130  planning_scene_monitor::PlanningSceneMonitorPtr psm_;
131 };
132 } // namespace moveit_ros_benchmarks
133 
134 int main(int argc, char** argv)
135 {
136  rclcpp::init(argc, argv);
137  rclcpp::NodeOptions node_options;
138  node_options.allow_undeclared_parameters(true);
139  node_options.automatically_declare_parameters_from_overrides(true);
140  rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("moveit_run_benchmark", node_options);
141 
142  // Read benchmark options from param server
144  // Setup benchmark server
146 
147  std::vector<std::string> planning_pipelines;
148  opts.getPlanningPipelineNames(planning_pipelines);
149  server.initialize(planning_pipelines);
150 
151  // Running benchmarks
152  if (!server.runBenchmarks(opts))
153  RCLCPP_ERROR(LOGGER, "Failed to run all benchmarks");
154 
155  rclcpp::spin(node);
156 }
int main(int argc, char **argv)
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
virtual bool runBenchmarks(const BenchmarkOptions &opts)
void initialize(const std::vector< std::string > &plugin_classes)
void getPlanningPipelineNames(std::vector< std::string > &planning_pipeline_names) const
Get all planning pipeline names.
const std::vector< std::string > & getPredefinedPoses() const
Get the names of all predefined poses to consider for planning.
const std::string & getGroupName() const
Get the name of the planning group to run the benchmark with.
const std::string & getPredefinedPosesGroup() const
Get the name of the planning group for which the predefined poses are defined.
bool loadBenchmarkQueryData(const BenchmarkOptions &opts, moveit_msgs::msg::PlanningScene &scene_msg, std::vector< StartState > &start_states, std::vector< PathConstraints > &path_constraints, std::vector< PathConstraints > &goal_constraints, std::vector< TrajectoryConstraints > &traj_constraints, std::vector< BenchmarkRequest > &queries) override
Initialize benchmark query data from start states and constraints.
moveit_msgs::msg::Constraints constructGoalConstraints(const moveit::core::RobotState &state, const moveit::core::JointModelGroup *jmg, double tolerance_below, double tolerance_above)
Generates a constraint message intended to be used as a goal constraint for a joint group....
Definition: utils.cpp:144
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
const rclcpp::Logger LOGGER
Definition: async_test.h:31