object_manipulation_msgs/GraspHandPostureExecutionAction Message

File: object_manipulation_msgs/GraspHandPostureExecutionAction.msg

# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======

GraspHandPostureExecutionActionGoal action_goal
GraspHandPostureExecutionActionResult action_result
GraspHandPostureExecutionActionFeedback action_feedback

Expanded Definition

GraspHandPostureExecutionActionGoal action_goal
    Header header
        uint32 seq
        time stamp
        string frame_id
    actionlib_msgs/GoalID goal_id
        time stamp
        string id
    object_manipulation_msgs/GraspHandPostureExecutionGoal goal
        int32 PRE_GRASP=1
        int32 GRASP=2
        int32 RELEASE=3
        object_manipulation_msgs/Grasp grasp
            sensor_msgs/JointState pre_grasp_posture
                Header header
                    uint32 seq
                    time stamp
                    string frame_id
                string[] name
                float64[] position
                float64[] velocity
                float64[] effort
            sensor_msgs/JointState grasp_posture
                Header header
                    uint32 seq
                    time stamp
                    string frame_id
                string[] name
                float64[] position
                float64[] velocity
                float64[] effort
            geometry_msgs/Pose grasp_pose
                geometry_msgs/Point position
                    float64 x
                    float64 y
                    float64 z
                geometry_msgs/Quaternion orientation
                    float64 x
                    float64 y
                    float64 z
                    float64 w
            float64 success_probability
            bool cluster_rep
        int32 goal
GraspHandPostureExecutionActionResult action_result
    Header header
        uint32 seq
        time stamp
        string frame_id
    actionlib_msgs/GoalStatus status
        uint8 PENDING=0
        uint8 ACTIVE=1
        uint8 PREEMPTED=2
        uint8 SUCCEEDED=3
        uint8 ABORTED=4
        uint8 REJECTED=5
        uint8 PREEMPTING=6
        uint8 RECALLING=7
        uint8 RECALLED=8
        uint8 LOST=9
        actionlib_msgs/GoalID goal_id
            time stamp
            string id
        uint8 status
        string text
    object_manipulation_msgs/GraspHandPostureExecutionResult result
        object_manipulation_msgs/ManipulationResult result
            int32 SUCCESS=1
            int32 UNFEASIBLE=-1
            int32 FAILED=-2
            int32 ERROR=-3
            int32 ARM_MOVEMENT_PREVENTED=-4
            int32 LIFT_FAILED=-5
            int32 RETREAT_FAILED=-6
            int32 CANCELLED=-7
            int32 value
GraspHandPostureExecutionActionFeedback action_feedback
    Header header
        uint32 seq
        time stamp
        string frame_id
    actionlib_msgs/GoalStatus status
        uint8 PENDING=0
        uint8 ACTIVE=1
        uint8 PREEMPTED=2
        uint8 SUCCEEDED=3
        uint8 ABORTED=4
        uint8 REJECTED=5
        uint8 PREEMPTING=6
        uint8 RECALLING=7
        uint8 RECALLED=8
        uint8 LOST=9
        actionlib_msgs/GoalID goal_id
            time stamp
            string id
        uint8 status
        string text
    object_manipulation_msgs/GraspHandPostureExecutionFeedback feedback