object_manipulation_msgs/Grasp Message

File: object_manipulation_msgs/Grasp.msg


# The internal posture of the hand for the pre-grasp
# only positions are used
sensor_msgs/JointState pre_grasp_posture

# The internal posture of the hand for the grasp
# positions and efforts are used
sensor_msgs/JointState grasp_posture

# The position of the end-effector for the grasp relative to the object
geometry_msgs/Pose grasp_pose

# The estimated probability of success for this grasp
float64 success_probability

# Debug flag to indicate that this grasp would be the best in its cluster
bool cluster_rep

Expanded Definition

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