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_;
75 std::shared_ptr<MGActionGoal> goal_;
void initialize() override
moveit_msgs::action::MoveGroup MGAction
rclcpp_action::ServerGoalHandle< MGAction > MGActionGoal
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)
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
A generic representation on what a computed motion plan looks like.