61 using ExecutableTrajs = std::vector<plan_execution::ExecutableTrajectory>;
63 using StartStateMsg = moveit_msgs::msg::MotionSequenceResponse::_sequence_start_type;
64 using StartStatesMsg = std::vector<moveit_msgs::msg::MotionSequenceResponse::_sequence_start_type>;
65 using PlannedTrajMsgs = moveit_msgs::msg::MotionSequenceResponse::_planned_trajectories_type;
68 void executeSequenceCallback(
const std::shared_ptr<MoveGroupSequenceGoalHandle>& goal_handle);
70 executeSequenceCallbackPlanAndExecute(
const moveit_msgs::action::MoveGroupSequence::Goal::ConstSharedPtr& goal,
71 const moveit_msgs::action::MoveGroupSequence::Result::SharedPtr& action_res);
72 void executeMoveCallbackPlanOnly(
const moveit_msgs::action::MoveGroupSequence::Goal::ConstSharedPtr& goal,
73 const moveit_msgs::action::MoveGroupSequence::Result::SharedPtr& res);
74 void startMoveExecutionCallback();
75 void startMoveLookCallback();
76 void preemptMoveCallback();
78 bool planUsingSequenceManager(
const moveit_msgs::msg::MotionSequenceRequest& req,
82 static void convertToMsg(
const ExecutableTrajs& trajs, StartStatesMsg& startStatesMsg,
83 PlannedTrajMsgs& plannedTrajsMsgs);
86 rclcpp::CallbackGroup::SharedPtr action_callback_group_;
87 std::shared_ptr<rclcpp_action::Server<moveit_msgs::action::MoveGroupSequence>> move_action_server_;
88 std::shared_ptr<MoveGroupSequenceGoalHandle> goal_handle_;
89 moveit_msgs::action::MoveGroupSequence::Feedback::SharedPtr move_feedback_;
92 std::unique_ptr<pilz_industrial_motion_planner::CommandListManager> command_list_manager_;