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