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