37 #ifndef MOVEIT_MOVE_GROUP_MOVE_ACTION_CAPABILITY_ 38 #define MOVEIT_MOVE_GROUP_MOVE_ACTION_CAPABILITY_ 42 #include <moveit_msgs/MoveGroupAction.h> 57 moveit_msgs::MoveGroupResult& action_res);
59 moveit_msgs::MoveGroupResult& action_res);
void preemptMoveCallback()
void executeMoveCallback_PlanAndExecute(const moveit_msgs::MoveGroupGoalConstPtr &goal, moveit_msgs::MoveGroupResult &action_res)
moveit_msgs::MoveGroupFeedback move_feedback_
MoveGroupState move_state_
void executeMoveCallback_PlanOnly(const moveit_msgs::MoveGroupGoalConstPtr &goal, moveit_msgs::MoveGroupResult &action_res)
void executeMoveCallback(const moveit_msgs::MoveGroupGoalConstPtr &goal)
moveit_msgs::MotionPlanRequest MotionPlanRequest
virtual void initialize()
std::unique_ptr< actionlib::SimpleActionServer< moveit_msgs::MoveGroupAction > > move_action_server_
void setMoveState(MoveGroupState state)
bool planUsingPlanningPipeline(const planning_interface::MotionPlanRequest &req, plan_execution::ExecutableMotionPlan &plan)
void startMoveExecutionCallback()
void startMoveLookCallback()