37 #ifndef MOVEIT_MOVE_GROUP_PICK_PLACE_ACTION_CAPABILITY_ 38 #define MOVEIT_MOVE_GROUP_PICK_PLACE_ACTION_CAPABILITY_ 43 #include <moveit_msgs/PickupAction.h> 44 #include <moveit_msgs/PlaceAction.h> 61 moveit_msgs::PickupResult& action_res);
63 moveit_msgs::PickupResult& action_res);
67 moveit_msgs::PlaceResult& action_res);
86 void fillGrasps(moveit_msgs::PickupGoal& goal);
std::unique_ptr< actionlib::SimpleActionServer< moveit_msgs::PickupAction > > pickup_action_server_
void executePlaceCallback(const moveit_msgs::PlaceGoalConstPtr &goal)
void executePickupCallback_PlanAndExecute(const moveit_msgs::PickupGoalConstPtr &goal, moveit_msgs::PickupResult &action_res)
moveit_msgs::PlaceFeedback place_feedback_
bool planUsingPickPlace_Place(const moveit_msgs::PlaceGoal &goal, moveit_msgs::PlaceResult *action_res, plan_execution::ExecutableMotionPlan &plan)
void setPickupState(MoveGroupState state)
void executePickupCallback_PlanOnly(const moveit_msgs::PickupGoalConstPtr &goal, moveit_msgs::PickupResult &action_res)
MoveGroupState pickup_state_
void preemptPickupCallback()
void executePlaceCallback_PlanAndExecute(const moveit_msgs::PlaceGoalConstPtr &goal, moveit_msgs::PlaceResult &action_res)
void startPickupExecutionCallback()
virtual void initialize()
MoveGroupPickPlaceAction()
bool planUsingPickPlace_Pickup(const moveit_msgs::PickupGoal &goal, moveit_msgs::PickupResult *action_res, plan_execution::ExecutableMotionPlan &plan)
void setPlaceState(MoveGroupState state)
moveit_msgs::PickupFeedback pickup_feedback_
void executePlaceCallback_PlanOnly(const moveit_msgs::PlaceGoalConstPtr &goal, moveit_msgs::PlaceResult &action_res)
void executePickupCallback(const moveit_msgs::PickupGoalConstPtr &goal)
std::unique_ptr< moveit_msgs::AttachedCollisionObject > diff_attached_object_
MoveGroupState place_state_
void preemptPlaceCallback()
void startPickupLookCallback()
std::unique_ptr< actionlib::SimpleActionServer< moveit_msgs::PlaceAction > > place_action_server_
void fillGrasps(moveit_msgs::PickupGoal &goal)
ros::ServiceClient grasp_planning_service_
void startPlaceLookCallback()
pick_place::PickPlacePtr pick_place_
void startPlaceExecutionCallback()