object_manipulation_msgs/PickupActionResult Message

File: object_manipulation_msgs/PickupActionResult.msg

Header header
actionlib_msgs/GoalStatus status
PickupResult result

Expanded Definition

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
PickupResult result
    object_manipulation_msgs/ManipulationResult manipulation_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
    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
    object_manipulation_msgs/Grasp[] attempted_grasps
        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
    object_manipulation_msgs/GraspResult[] attempted_grasp_results
        int32 SUCCESS=1
        int32 GRASP_OUT_OF_REACH=2
        int32 GRASP_IN_COLLISION=3
        int32 GRASP_UNFEASIBLE=4
        int32 PREGRASP_OUT_OF_REACH=5
        int32 PREGRASP_IN_COLLISION=6
        int32 PREGRASP_UNFEASIBLE=7
        int32 LIFT_OUT_OF_REACH=8
        int32 LIFT_IN_COLLISION=9
        int32 LIFT_UNFEASIBLE=10
        int32 MOVE_ARM_FAILED=11
        int32 GRASP_FAILED=12
        int32 LIFT_FAILED=13
        int32 RETREAT_FAILED=14
        int32 result_code
        bool continuation_possible