Go to the documentation of this file.
41 #include <moveit_msgs/MoveGroupAction.h>
46 class MoveGroupMoveAction :
public MoveGroupCapability
56 moveit_msgs::MoveGroupResult& action_res);
58 moveit_msgs::MoveGroupResult& action_res);
66 std::unique_ptr<actionlib::SimpleActionServer<moveit_msgs::MoveGroupAction> >
move_action_server_;
void executeMoveCallback(const moveit_msgs::MoveGroupGoalConstPtr &goal)
void executeMoveCallbackPlanAndExecute(const moveit_msgs::MoveGroupGoalConstPtr &goal, moveit_msgs::MoveGroupResult &action_res)
void startMoveLookCallback()
void setMoveState(MoveGroupState state)
bool planUsingPlanningPipeline(const planning_interface::MotionPlanRequest &req, plan_execution::ExecutableMotionPlan &plan)
void initialize() override
void preemptMoveCallback()
moveit_msgs::MoveGroupFeedback move_feedback_
MoveGroupState move_state_
moveit_msgs::MotionPlanRequest MotionPlanRequest
void executeMoveCallbackPlanOnly(const moveit_msgs::MoveGroupGoalConstPtr &goal, moveit_msgs::MoveGroupResult &action_res)
std::unique_ptr< actionlib::SimpleActionServer< moveit_msgs::MoveGroupAction > > move_action_server_
void startMoveExecutionCallback()
move_group
Author(s): Ioan Sucan
, Sachin Chitta
autogenerated on Tue Dec 24 2024 03:28:16