43 #ifndef MOVEIT_MOVE_GROUP_EXECUTE_TRAJECTORY_ACTION_CAPABILITY_ 44 #define MOVEIT_MOVE_GROUP_EXECUTE_TRAJECTORY_ACTION_CAPABILITY_ 48 #include <moveit_msgs/ExecuteTrajectoryAction.h> 62 void executePath(
const moveit_msgs::ExecuteTrajectoryGoalConstPtr& goal,
63 moveit_msgs::ExecuteTrajectoryResult& action_res);
72 #endif // MOVEIT_MOVE_GROUP_EXECUTE_TRAJECTORY_ACTION_CAPABILITY_ void executePathCallback(const moveit_msgs::ExecuteTrajectoryGoalConstPtr &goal)
MoveGroupExecuteTrajectoryAction()
std::unique_ptr< actionlib::SimpleActionServer< moveit_msgs::ExecuteTrajectoryAction > > execute_action_server_
void preemptExecuteTrajectoryCallback()
void setExecuteTrajectoryState(MoveGroupState state)
virtual void initialize()
void executePath(const moveit_msgs::ExecuteTrajectoryGoalConstPtr &goal, moveit_msgs::ExecuteTrajectoryResult &action_res)