moveit2
The MoveIt Motion Planning Framework for ROS 2.
move_group_capability.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, 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 Willow Garage 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: Ioan Sucan */
36 
40 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
41 
42 #include <sstream>
43 #include <string>
44 
45 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_move_group_capabilities_base.move_group_capability");
46 
47 void move_group::MoveGroupCapability::setContext(const MoveGroupContextPtr& context)
48 {
49  context_ = context;
50 }
51 
52 void move_group::MoveGroupCapability::convertToMsg(const std::vector<plan_execution::ExecutableTrajectory>& trajectory,
53  moveit_msgs::msg::RobotState& first_state_msg,
54  std::vector<moveit_msgs::msg::RobotTrajectory>& trajectory_msg) const
55 {
56  if (!trajectory.empty())
57  {
58  bool first = true;
59  trajectory_msg.resize(trajectory.size());
60  for (std::size_t i = 0; i < trajectory.size(); ++i)
61  {
62  if (trajectory[i].trajectory_)
63  {
64  if (first && !trajectory[i].trajectory_->empty())
65  {
66  moveit::core::robotStateToRobotStateMsg(trajectory[i].trajectory_->getFirstWayPoint(), first_state_msg);
67  first = false;
68  }
69  trajectory[i].trajectory_->getRobotTrajectoryMsg(trajectory_msg[i]);
70  }
71  }
72  }
73 }
74 
75 void move_group::MoveGroupCapability::convertToMsg(const robot_trajectory::RobotTrajectoryPtr& trajectory,
76  moveit_msgs::msg::RobotState& first_state_msg,
77  moveit_msgs::msg::RobotTrajectory& trajectory_msg) const
78 {
79  if (trajectory && !trajectory->empty())
80  {
81  moveit::core::robotStateToRobotStateMsg(trajectory->getFirstWayPoint(), first_state_msg);
82  trajectory->getRobotTrajectoryMsg(trajectory_msg);
83  }
84 }
85 
86 void move_group::MoveGroupCapability::convertToMsg(const std::vector<plan_execution::ExecutableTrajectory>& trajectory,
87  moveit_msgs::msg::RobotState& first_state_msg,
88  moveit_msgs::msg::RobotTrajectory& trajectory_msg) const
89 {
90  if (trajectory.size() > 1)
91  RCLCPP_ERROR_STREAM(LOGGER, "Internal logic error: trajectory component ignored. !!! THIS IS A SERIOUS ERROR !!!");
92  if (!trajectory.empty())
93  convertToMsg(trajectory[0].trajectory_, first_state_msg, trajectory_msg);
94 }
95 
98 {
100  r.start_state = moveit_msgs::msg::RobotState();
101  r.start_state.is_diff = true;
102  RCLCPP_WARN(LOGGER,
103  "Execution of motions should always start at the robot's current state. Ignoring the state supplied as "
104  "start state in the motion planning request");
105  return r;
106 }
107 
108 moveit_msgs::msg::PlanningScene
109 move_group::MoveGroupCapability::clearSceneRobotState(const moveit_msgs::msg::PlanningScene& scene) const
110 {
111  moveit_msgs::msg::PlanningScene r = scene;
112  r.robot_state = moveit_msgs::msg::RobotState();
113  r.robot_state.is_diff = true;
114  RCLCPP_WARN(LOGGER,
115  "Execution of motions should always start at the robot's current state. Ignoring the state supplied as "
116  "difference in the planning scene diff");
117  return r;
118 }
119 
120 std::string move_group::MoveGroupCapability::getActionResultString(const moveit_msgs::msg::MoveItErrorCodes& error_code,
121  bool planned_trajectory_empty, bool plan_only)
122 {
123  if (error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
124  {
125  if (planned_trajectory_empty)
126  return "Requested path and goal constraints are already met.";
127  else
128  {
129  if (plan_only)
130  return "Motion plan was computed successfully.";
131  else
132  return "Solution was found and executed.";
133  }
134  }
135  else if (error_code.val == moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME)
136  return "Must specify group in motion plan request";
137  else if (error_code.val == moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED ||
138  error_code.val == moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN)
139  {
140  if (planned_trajectory_empty)
141  return "No motion plan found. No execution attempted.";
142  else
143  return "Motion plan was found but it seems to be invalid (possibly due to postprocessing). Not executing.";
144  }
145  else if (error_code.val == moveit_msgs::msg::MoveItErrorCodes::UNABLE_TO_AQUIRE_SENSOR_DATA)
146  return "Motion plan was found but it seems to be too costly and looking around did not help.";
147  else if (error_code.val == moveit_msgs::msg::MoveItErrorCodes::MOTION_PLAN_INVALIDATED_BY_ENVIRONMENT_CHANGE)
148  return "Solution found but the environment changed during execution and the path was aborted";
149  else if (error_code.val == moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED)
150  return "Solution found but controller failed during execution";
151  else if (error_code.val == moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT)
152  return "Timeout reached";
153  else if (error_code.val == moveit_msgs::msg::MoveItErrorCodes::PREEMPTED)
154  return "Preempted";
155  else if (error_code.val == moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
156  return "Invalid goal constraints";
157  else if (error_code.val == moveit_msgs::msg::MoveItErrorCodes::INVALID_OBJECT_NAME)
158  return "Invalid object name";
159  else if (error_code.val == moveit_msgs::msg::MoveItErrorCodes::FAILURE)
160  return "Catastrophic failure";
161  return "Unknown event";
162 }
163 
165 {
166  switch (state)
167  {
168  case IDLE:
169  return "IDLE";
170  case PLANNING:
171  return "PLANNING";
172  case MONITOR:
173  return "MONITOR";
174  case LOOK:
175  return "LOOK";
176  default:
177  return "UNKNOWN";
178  }
179 }
180 
181 bool move_group::MoveGroupCapability::performTransform(geometry_msgs::msg::PoseStamped& pose_msg,
182  const std::string& target_frame) const
183 {
184  if (!context_ || !context_->planning_scene_monitor_->getTFClient())
185  return false;
186  if (pose_msg.header.frame_id == target_frame)
187  return true;
188  if (pose_msg.header.frame_id.empty())
189  {
190  pose_msg.header.frame_id = target_frame;
191  return true;
192  }
193 
194  try
195  {
196  geometry_msgs::msg::TransformStamped common_tf = context_->planning_scene_monitor_->getTFClient()->lookupTransform(
197  pose_msg.header.frame_id, target_frame, rclcpp::Time(0.0));
198  geometry_msgs::msg::PoseStamped pose_msg_in(pose_msg);
199  pose_msg_in.header.stamp = common_tf.header.stamp;
200  context_->planning_scene_monitor_->getTFClient()->transform(pose_msg_in, pose_msg, target_frame);
201  }
202  catch (tf2::TransformException& ex)
203  {
204  RCLCPP_ERROR(LOGGER, "TF Problem: %s", ex.what());
205  return false;
206  }
207  return true;
208 }
209 
210 planning_pipeline::PlanningPipelinePtr
211 move_group::MoveGroupCapability::resolvePlanningPipeline(const std::string& pipeline_id) const
212 {
213  if (pipeline_id.empty())
214  {
215  // Without specified planning pipeline we use the default
216  return context_->planning_pipeline_;
217  }
218  else
219  {
220  // Attempt to get the planning pipeline for the specified identifier
221  try
222  {
223  auto pipeline = context_->moveit_cpp_->getPlanningPipelines().at(pipeline_id);
224  RCLCPP_INFO(LOGGER, "Using planning pipeline '%s'", pipeline_id.c_str());
225  return pipeline;
226  }
227  catch (const std::out_of_range&)
228  {
229  RCLCPP_WARN(LOGGER, "Couldn't find requested planning pipeline '%s'", pipeline_id.c_str());
230  }
231  }
232 
233  return planning_pipeline::PlanningPipelinePtr();
234 }
void setContext(const MoveGroupContextPtr &context)
moveit_msgs::msg::PlanningScene clearSceneRobotState(const moveit_msgs::msg::PlanningScene &scene) const
planning_interface::MotionPlanRequest clearRequestStartState(const planning_interface::MotionPlanRequest &request) const
void convertToMsg(const std::vector< plan_execution::ExecutableTrajectory > &trajectory, moveit_msgs::msg::RobotState &first_state_msg, std::vector< moveit_msgs::msg::RobotTrajectory > &trajectory_msg) const
bool performTransform(geometry_msgs::msg::PoseStamped &pose_msg, const std::string &target_frame) const
std::string getActionResultString(const moveit_msgs::msg::MoveItErrorCodes &error_code, bool planned_trajectory_empty, bool plan_only)
std::string stateToStr(MoveGroupState state) const
planning_pipeline::PlanningPipelinePtr resolvePlanningPipeline(const std::string &pipeline_id) const
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.
scene
Definition: pick.py:52
r
Definition: plan.py:56
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
const rclcpp::Logger LOGGER
Definition: async_test.h:31