object_manipulation_msgs/PickupResult Message

File: object_manipulation_msgs/PickupResult.msg

# The overall result of the pickup attempt
ManipulationResult manipulation_result

# The performed grasp, if attempt was successful
Grasp grasp

# the complete list of attempted grasp, in the order in which they have been attempted
# the successful one should be the last one in this list
Grasp[] attempted_grasps

# the outcomes of the attempted grasps, in the same order as attempted_grasps
GraspResult[] attempted_grasp_results

Expanded Definition

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
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
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
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