moveit2
The MoveIt Motion Planning Framework for ROS 2.
move_group_sequence_action.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 
37 // Modified by Pilz GmbH & Co. KG
38 
40 
41 #include <time.h>
42 
50 
53 
55 {
56 static const rclcpp::Logger LOGGER =
57  rclcpp::get_logger("moveit.pilz_industrial_motion_planner.move_group_sequence_action");
58 
60  : MoveGroupCapability("SequenceAction")
61  , move_feedback_(std::make_shared<moveit_msgs::action::MoveGroupSequence::Feedback>())
62 {
63 }
64 
66 {
67  // start the move action server
68  RCLCPP_INFO_STREAM(LOGGER, "initialize move group sequence action");
69  // Use MutuallyExclusiveCallbackGroup to prevent race conditions in callbacks.
70  // See: https://github.com/moveit/moveit2/issues/3117 for details.
71  action_callback_group_ =
72  context_->moveit_cpp_->getNode()->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
73  move_action_server_ = rclcpp_action::create_server<moveit_msgs::action::MoveGroupSequence>(
74  context_->moveit_cpp_->getNode(), "sequence_move_group",
75  [](const rclcpp_action::GoalUUID& /* unused */,
76  const std::shared_ptr<const moveit_msgs::action::MoveGroupSequence::Goal>& /* unused */) {
77  RCLCPP_DEBUG(LOGGER, "Received action goal");
78  return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
79  },
80  [this](const std::shared_ptr<MoveGroupSequenceGoalHandle>& /* unused goal_handle */) {
81  RCLCPP_DEBUG(LOGGER, "Canceling action goal");
82  preemptMoveCallback();
83  return rclcpp_action::CancelResponse::ACCEPT;
84  },
85  [this](const std::shared_ptr<MoveGroupSequenceGoalHandle>& goal_handle) {
86  RCLCPP_DEBUG(LOGGER, "Accepting new action goal");
87  executeSequenceCallback(goal_handle);
88  },
89  rcl_action_server_get_default_options(), action_callback_group_);
90 
91  command_list_manager_ = std::make_unique<pilz_industrial_motion_planner::CommandListManager>(
92  context_->moveit_cpp_->getNode(), context_->planning_scene_monitor_->getRobotModel());
93 }
94 
95 void MoveGroupSequenceAction::executeSequenceCallback(const std::shared_ptr<MoveGroupSequenceGoalHandle>& goal_handle)
96 {
97  // Notify that goal is being executed
98  goal_handle_ = goal_handle;
99  const auto goal = goal_handle->get_goal();
100 
101  setMoveState(move_group::PLANNING);
102 
103  // Handle empty requests
104  if (goal->request.items.empty())
105  {
106  RCLCPP_WARN(LOGGER, "Received empty request. That's ok but maybe not what you intended.");
107  setMoveState(move_group::IDLE);
108  const auto action_res = std::make_shared<moveit_msgs::action::MoveGroupSequence::Result>();
109  action_res->response.error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
110  goal_handle->succeed(action_res);
111  return;
112  }
113 
114  // before we start planning, ensure that we have the latest robot state
115  // received...
116  auto node = context_->moveit_cpp_->getNode();
117  context_->planning_scene_monitor_->waitForCurrentRobotState(node->get_clock()->now());
118  context_->planning_scene_monitor_->updateFrameTransforms();
119 
120  const auto action_res = std::make_shared<moveit_msgs::action::MoveGroupSequence::Result>();
121  if (goal->planning_options.plan_only || !context_->allow_trajectory_execution_)
122  {
123  if (!goal->planning_options.plan_only)
124  {
125  RCLCPP_WARN(LOGGER, "Only plan will be calculated, although plan_only == false."); // LCOV_EXCL_LINE
126  }
127  executeMoveCallbackPlanOnly(goal, action_res);
128  }
129  else
130  {
131  executeSequenceCallbackPlanAndExecute(goal, action_res);
132  }
133 
134  switch (action_res->response.error_code.val)
135  {
136  case moveit_msgs::msg::MoveItErrorCodes::SUCCESS:
137  goal_handle->succeed(action_res);
138  break;
139  case moveit_msgs::msg::MoveItErrorCodes::PREEMPTED:
140  goal_handle->canceled(action_res);
141  break;
142  default:
143  goal_handle->abort(action_res);
144  break;
145  }
146 
147  setMoveState(move_group::IDLE);
148  goal_handle_.reset();
149 }
150 
151 void MoveGroupSequenceAction::executeSequenceCallbackPlanAndExecute(
152  const moveit_msgs::action::MoveGroupSequence::Goal::ConstSharedPtr& goal,
153  const moveit_msgs::action::MoveGroupSequence::Result::SharedPtr& action_res)
154 {
155  RCLCPP_INFO(LOGGER, "Combined planning and execution request received for MoveGroupSequenceAction.");
156 
158  const moveit_msgs::msg::PlanningScene& planning_scene_diff =
159  moveit::core::isEmpty(goal->planning_options.planning_scene_diff.robot_state) ?
160  goal->planning_options.planning_scene_diff :
161  clearSceneRobotState(goal->planning_options.planning_scene_diff);
162 
163  opt.replan_ = goal->planning_options.replan;
164  opt.replan_attempts_ = goal->planning_options.replan_attempts;
165  opt.replan_delay_ = goal->planning_options.replan_delay;
166  opt.before_execution_callback_ = [this] { startMoveExecutionCallback(); };
167 
168  opt.plan_callback_ = [this, &request = goal->request](plan_execution::ExecutableMotionPlan& plan) {
169  return planUsingSequenceManager(request, plan);
170  };
171 
173  context_->plan_execution_->planAndExecute(plan, planning_scene_diff, opt);
174 
175  StartStatesMsg start_states_msg;
176  convertToMsg(plan.plan_components_, start_states_msg, action_res->response.planned_trajectories);
177  try
178  {
179  action_res->response.sequence_start = start_states_msg.at(0);
180  }
181  catch (std::out_of_range&)
182  {
183  RCLCPP_WARN(LOGGER, "Can not determine start state from empty sequence.");
184  }
185  action_res->response.error_code = plan.error_code_;
186 }
187 
188 void MoveGroupSequenceAction::convertToMsg(const ExecutableTrajs& trajs, StartStatesMsg& start_states_msg,
189  PlannedTrajMsgs& planned_trajs_msgs)
190 {
191  start_states_msg.resize(trajs.size());
192  planned_trajs_msgs.resize(trajs.size());
193  for (size_t i = 0; i < trajs.size(); ++i)
194  {
195  moveit::core::robotStateToRobotStateMsg(trajs.at(i).trajectory_->getFirstWayPoint(), start_states_msg.at(i));
196  trajs.at(i).trajectory_->getRobotTrajectoryMsg(planned_trajs_msgs.at(i));
197  }
198 }
199 
200 void MoveGroupSequenceAction::executeMoveCallbackPlanOnly(
201  const moveit_msgs::action::MoveGroupSequence::Goal::ConstSharedPtr& goal,
202  const moveit_msgs::action::MoveGroupSequence::Result::SharedPtr& action_res)
203 {
204  RCLCPP_INFO(LOGGER, "Planning request received for MoveGroupSequenceAction action.");
205 
206  // lock the scene so that it does not modify the world representation while
207  // diff() is called
208  planning_scene_monitor::LockedPlanningSceneRO lscene(context_->planning_scene_monitor_);
209 
210  const planning_scene::PlanningSceneConstPtr& the_scene =
211  (moveit::core::isEmpty(goal->planning_options.planning_scene_diff)) ?
212  static_cast<const planning_scene::PlanningSceneConstPtr&>(lscene) :
213  lscene->diff(goal->planning_options.planning_scene_diff);
214 
215  rclcpp::Time planning_start = context_->moveit_cpp_->getNode()->now();
216  RobotTrajCont traj_vec;
217  try
218  {
219  // Select planning_pipeline to handle request
220  // All motions in the SequenceRequest need to use the same planning pipeline (but can use different planners)
221  const planning_pipeline::PlanningPipelinePtr planning_pipeline =
222  resolvePlanningPipeline(goal->request.items[0].req.pipeline_id);
223  if (!planning_pipeline)
224  {
225  RCLCPP_ERROR_STREAM(LOGGER, "Could not load planning pipeline " << goal->request.items[0].req.pipeline_id);
226  action_res->response.error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
227  return;
228  }
229 
230  traj_vec = command_list_manager_->solve(the_scene, planning_pipeline, goal->request);
231  }
232  catch (const MoveItErrorCodeException& ex)
233  {
234  RCLCPP_ERROR_STREAM(LOGGER, "> Planning pipeline threw an exception (error code: " << ex.getErrorCode()
235  << "): " << ex.what());
236  action_res->response.error_code.val = ex.getErrorCode();
237  return;
238  }
239  // LCOV_EXCL_START // Keep moveit up even if lower parts throw
240  catch (const std::exception& ex)
241  {
242  RCLCPP_ERROR(LOGGER, "Planning pipeline threw an exception: %s", ex.what());
243  action_res->response.error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
244  return;
245  }
246  // LCOV_EXCL_STOP
247 
248  StartStatesMsg start_states_msg;
249  start_states_msg.resize(traj_vec.size());
250  action_res->response.planned_trajectories.resize(traj_vec.size());
251  for (RobotTrajCont::size_type i = 0; i < traj_vec.size(); ++i)
252  {
253  move_group::MoveGroupCapability::convertToMsg(traj_vec.at(i), start_states_msg.at(i),
254  action_res->response.planned_trajectories.at(i));
255  }
256  try
257  {
258  action_res->response.sequence_start = start_states_msg.at(0);
259  }
260  catch (std::out_of_range&)
261  {
262  RCLCPP_WARN(LOGGER, "Can not determine start state from empty sequence.");
263  }
264 
265  action_res->response.error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
266  action_res->response.planning_time = (context_->moveit_cpp_->getNode()->now() - planning_start).seconds();
267 }
268 
269 bool MoveGroupSequenceAction::planUsingSequenceManager(const moveit_msgs::msg::MotionSequenceRequest& req,
271 {
272  setMoveState(move_group::PLANNING);
273 
274  planning_scene_monitor::LockedPlanningSceneRO lscene(plan.planning_scene_monitor_);
275  RobotTrajCont traj_vec;
276  try
277  {
278  // Select planning_pipeline to handle request
279  // All motions in the SequenceRequest need to use the same planning pipeline (but can use different planners)
280  const planning_pipeline::PlanningPipelinePtr planning_pipeline =
281  resolvePlanningPipeline(req.items[0].req.pipeline_id);
282  if (!planning_pipeline)
283  {
284  RCLCPP_ERROR_STREAM(LOGGER, "Could not load planning pipeline " << req.items[0].req.pipeline_id);
285  return false;
286  }
287 
288  traj_vec = command_list_manager_->solve(plan.planning_scene_, planning_pipeline, req);
289  }
290  catch (const MoveItErrorCodeException& ex)
291  {
292  RCLCPP_ERROR_STREAM(LOGGER, "Planning pipeline threw an exception (error code: " << ex.getErrorCode()
293  << "): " << ex.what());
294  plan.error_code_.val = ex.getErrorCode();
295  return false;
296  }
297  // LCOV_EXCL_START // Keep MoveIt up even if lower parts throw
298  catch (const std::exception& ex)
299  {
300  RCLCPP_ERROR_STREAM(LOGGER, "Planning pipeline threw an exception: " << ex.what());
301  plan.error_code_.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
302  return false;
303  }
304  // LCOV_EXCL_STOP
305 
306  if (!traj_vec.empty())
307  {
308  plan.plan_components_.resize(traj_vec.size());
309  for (size_t i = 0; i < traj_vec.size(); ++i)
310  {
311  plan.plan_components_.at(i).trajectory_ = traj_vec.at(i);
312  plan.plan_components_.at(i).description_ = "plan";
313  }
314  }
315  plan.error_code_.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
316  return true;
317 }
318 
319 void MoveGroupSequenceAction::startMoveExecutionCallback()
320 {
321  setMoveState(move_group::MONITOR);
322 }
323 
324 void MoveGroupSequenceAction::preemptMoveCallback()
325 {
326  context_->plan_execution_->stop();
327 }
328 
329 void MoveGroupSequenceAction::setMoveState(move_group::MoveGroupState state)
330 {
331  move_state_ = state;
332  move_feedback_->state = stateToStr(state);
333  goal_handle_->publish_feedback(move_feedback_);
334 }
335 
336 } // namespace pilz_industrial_motion_planner
337 
338 #include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
moveit_msgs::msg::PlanningScene clearSceneRobotState(const moveit_msgs::msg::PlanningScene &scene) 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
std::string stateToStr(MoveGroupState state) const
planning_pipeline::PlanningPipelinePtr resolvePlanningPipeline(const std::string &pipeline_id) const
Provide action to handle multiple trajectories and execute the result in the form of a MoveGroup capa...
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
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.
bool isEmpty(const moveit_msgs::msg::PlanningScene &msg)
Check if a message includes any information about a planning scene, or whether it is empty.
std::vector< robot_trajectory::RobotTrajectoryPtr > RobotTrajCont
Definition: plan.py:1
Planning pipeline.
A generic representation on what a computed motion plan looks like.