40 #include <rclcpp_action/rclcpp_action.hpp>
41 #include <moveit_msgs/action/move_group.hpp>
46 using MGAction = moveit_msgs::action::MoveGroup;
57 void executeMoveCallback(
const std::shared_ptr<MGActionGoal>& goal);
58 void executeMoveCallbackPlanAndExecute(
const std::shared_ptr<MGActionGoal>& goal,
59 std::shared_ptr<MGAction::Result>& action_res);
60 void executeMoveCallbackPlanOnly(
const std::shared_ptr<MGActionGoal>& goal,
61 std::shared_ptr<MGAction::Result>& action_res);
63 void startMoveExecutionCallback();
64 void startMoveLookCallback();
65 void preemptMoveCallback();
66 void setMoveState(
MoveGroupState state,
const std::shared_ptr<MGActionGoal>& goal);
71 std::shared_ptr<rclcpp_action::Server<MGAction>> execute_action_server_;
74 bool preempt_requested_;
void initialize() override
moveit_msgs::action::MoveGroup MGAction
rclcpp_action::ServerGoalHandle< MGAction > MGActionGoal
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
A generic representation on what a computed motion plan looks like.