56 static const rclcpp::Logger LOGGER =
 
   57     rclcpp::get_logger(
"moveit.pilz_industrial_motion_planner.move_group_sequence_action");
 
   60   : MoveGroupCapability(
"SequenceAction")
 
   61   , move_feedback_(std::make_shared<moveit_msgs::
action::MoveGroupSequence::Feedback>())
 
   68   RCLCPP_INFO_STREAM(LOGGER, 
"initialize move group sequence action");
 
   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& ,
 
   76          const std::shared_ptr<const moveit_msgs::action::MoveGroupSequence::Goal>& ) {
 
   77         RCLCPP_DEBUG(LOGGER, 
"Received action goal");
 
   78         return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
 
   80       [
this](
const std::shared_ptr<MoveGroupSequenceGoalHandle>& ) {
 
   81         RCLCPP_DEBUG(LOGGER, 
"Canceling action goal");
 
   82         preemptMoveCallback();
 
   83         return rclcpp_action::CancelResponse::ACCEPT;
 
   85       [
this](
const std::shared_ptr<MoveGroupSequenceGoalHandle>& goal_handle) {
 
   86         RCLCPP_DEBUG(LOGGER, 
"Accepting new action goal");
 
   87         executeSequenceCallback(goal_handle);
 
   89       rcl_action_server_get_default_options(), action_callback_group_);
 
   91   command_list_manager_ = std::make_unique<pilz_industrial_motion_planner::CommandListManager>(
 
   92       context_->moveit_cpp_->getNode(), 
context_->planning_scene_monitor_->getRobotModel());
 
   95 void MoveGroupSequenceAction::executeSequenceCallback(
const std::shared_ptr<MoveGroupSequenceGoalHandle>& goal_handle)
 
   98   goal_handle_ = goal_handle;
 
   99   const auto goal = goal_handle->get_goal();
 
  104   if (goal->request.items.empty())
 
  106     RCLCPP_WARN(LOGGER, 
"Received empty request. That's ok but maybe not what you intended.");
 
  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);
 
  116   auto node = 
context_->moveit_cpp_->getNode();
 
  117   context_->planning_scene_monitor_->waitForCurrentRobotState(node->get_clock()->now());
 
  118   context_->planning_scene_monitor_->updateFrameTransforms();
 
  120   const auto action_res = std::make_shared<moveit_msgs::action::MoveGroupSequence::Result>();
 
  121   if (goal->planning_options.plan_only || !
context_->allow_trajectory_execution_)
 
  123     if (!goal->planning_options.plan_only)
 
  125       RCLCPP_WARN(LOGGER, 
"Only plan will be calculated, although plan_only == false.");  
 
  127     executeMoveCallbackPlanOnly(goal, action_res);
 
  131     executeSequenceCallbackPlanAndExecute(goal, action_res);
 
  134   switch (action_res->response.error_code.val)
 
  136     case moveit_msgs::msg::MoveItErrorCodes::SUCCESS:
 
  137       goal_handle->succeed(action_res);
 
  139     case moveit_msgs::msg::MoveItErrorCodes::PREEMPTED:
 
  140       goal_handle->canceled(action_res);
 
  143       goal_handle->abort(action_res);
 
  148   goal_handle_.reset();
 
  151 void MoveGroupSequenceAction::executeSequenceCallbackPlanAndExecute(
 
  152     const moveit_msgs::action::MoveGroupSequence::Goal::ConstSharedPtr& goal,
 
  153     const moveit_msgs::action::MoveGroupSequence::Result::SharedPtr& action_res)
 
  155   RCLCPP_INFO(LOGGER, 
"Combined planning and execution request received for MoveGroupSequenceAction.");
 
  158   const moveit_msgs::msg::PlanningScene& planning_scene_diff =
 
  160           goal->planning_options.planning_scene_diff :
 
  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(); };
 
  169     return planUsingSequenceManager(request, 
plan);
 
  173   context_->plan_execution_->planAndExecute(
plan, planning_scene_diff, 
opt);
 
  175   StartStatesMsg start_states_msg;
 
  176   convertToMsg(
plan.plan_components_, start_states_msg, action_res->response.planned_trajectories);
 
  179     action_res->response.sequence_start = start_states_msg.at(0);
 
  181   catch (std::out_of_range&)
 
  183     RCLCPP_WARN(LOGGER, 
"Can not determine start state from empty sequence.");
 
  185   action_res->response.error_code = 
plan.error_code_;
 
  188 void MoveGroupSequenceAction::convertToMsg(
const ExecutableTrajs& trajs, StartStatesMsg& start_states_msg,
 
  189                                            PlannedTrajMsgs& planned_trajs_msgs)
 
  191   start_states_msg.resize(trajs.size());
 
  192   planned_trajs_msgs.resize(trajs.size());
 
  193   for (
size_t i = 0; i < trajs.size(); ++i)
 
  196     trajs.at(i).trajectory_->getRobotTrajectoryMsg(planned_trajs_msgs.at(i));
 
  200 void MoveGroupSequenceAction::executeMoveCallbackPlanOnly(
 
  201     const moveit_msgs::action::MoveGroupSequence::Goal::ConstSharedPtr& goal,
 
  202     const moveit_msgs::action::MoveGroupSequence::Result::SharedPtr& action_res)
 
  204   RCLCPP_INFO(LOGGER, 
"Planning request received for MoveGroupSequenceAction action.");
 
  206   rclcpp::Time planning_start = 
context_->moveit_cpp_->getNode()->now();
 
  216       RCLCPP_ERROR_STREAM(LOGGER, 
"Could not load planning pipeline " << goal->request.items[0].req.pipeline_id);
 
  217       action_res->response.error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
 
  221     auto scene = 
context_->planning_scene_monitor_->copyPlanningScene(goal->planning_options.planning_scene_diff);
 
  224   catch (
const MoveItErrorCodeException& ex)
 
  226     RCLCPP_ERROR_STREAM(LOGGER, 
"> Planning pipeline threw an exception (error code: " << ex.getErrorCode()
 
  227                                                                                        << 
"): " << ex.what());
 
  228     action_res->response.error_code.val = ex.getErrorCode();
 
  232   catch (
const std::exception& ex)
 
  234     RCLCPP_ERROR(LOGGER, 
"Planning pipeline threw an exception: %s", ex.what());
 
  235     action_res->response.error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
 
  240   StartStatesMsg start_states_msg;
 
  241   start_states_msg.resize(traj_vec.size());
 
  242   action_res->response.planned_trajectories.resize(traj_vec.size());
 
  243   for (RobotTrajCont::size_type i = 0; i < traj_vec.size(); ++i)
 
  246                                                   action_res->response.planned_trajectories.at(i));
 
  250     action_res->response.sequence_start = start_states_msg.at(0);
 
  252   catch (std::out_of_range&)
 
  254     RCLCPP_WARN(LOGGER, 
"Can not determine start state from empty sequence.");
 
  257   action_res->response.error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
 
  258   action_res->response.planning_time = (
context_->moveit_cpp_->getNode()->now() - planning_start).seconds();
 
  261 bool MoveGroupSequenceAction::planUsingSequenceManager(
const moveit_msgs::msg::MotionSequenceRequest& req,
 
  275       RCLCPP_ERROR_STREAM(LOGGER, 
"Could not load planning pipeline " << req.items[0].req.pipeline_id);
 
  281   catch (
const MoveItErrorCodeException& ex)
 
  283     RCLCPP_ERROR_STREAM(LOGGER, 
"Planning pipeline threw an exception (error code: " << ex.getErrorCode()
 
  284                                                                                      << 
"): " << ex.what());
 
  285     plan.error_code_.val = ex.getErrorCode();
 
  289   catch (
const std::exception& ex)
 
  291     RCLCPP_ERROR_STREAM(LOGGER, 
"Planning pipeline threw an exception: " << ex.what());
 
  292     plan.error_code_.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
 
  297   if (!traj_vec.empty())
 
  299     plan.plan_components_.resize(traj_vec.size());
 
  300     for (
size_t i = 0; i < traj_vec.size(); ++i)
 
  302       plan.plan_components_.at(i).trajectory_ = traj_vec.at(i);
 
  303       plan.plan_components_.at(i).description_ = 
"plan";
 
  306   plan.error_code_.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
 
  310 void MoveGroupSequenceAction::startMoveExecutionCallback()
 
  315 void MoveGroupSequenceAction::preemptMoveCallback()
 
  324   goal_handle_->publish_feedback(move_feedback_);
 
  329 #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
 
MoveGroupContextPtr context_
 
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...
 
void initialize() override
 
MoveGroupSequenceAction()
 
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
 
A generic representation on what a computed motion plan looks like.