object_manipulation_msgs/GraspPlanning Service

File: object_manipulation_msgs/GraspPlanning.srv

# Requests that grasp planning be performed on the object to be grasped
# returns a list of grasps to be tested and executed

# the arm being used
string arm_name

# the object to be grasped
GraspableObject target

# the name that the target object has in the collision environment
# can be left empty if no name is available
string collision_object_name

# the name that the support surface (e.g. table) has in the collision map
# can be left empty if no name is available
string collision_support_surface_name

# an optional list of grasps to be evaluated by the planner
Grasp[] grasps_to_evaluate

---

# the list of planned grasps
Grasp[] grasps

# whether an error occurred
GraspPlanningErrorCode error_code

Expanded Definition

string arm_name
GraspableObject target
    string reference_frame_id
    household_objects_database_msgs/DatabaseModelPose[] potential_models
        int32 model_id
        geometry_msgs/PoseStamped pose
            Header header
                uint32 seq
                time stamp
                string frame_id
            geometry_msgs/Pose pose
                geometry_msgs/Point position
                    float64 x
                    float64 y
                    float64 z
                geometry_msgs/Quaternion orientation
                    float64 x
                    float64 y
                    float64 z
                    float64 w
        float32 confidence
    sensor_msgs/PointCloud cluster
        Header header
            uint32 seq
            time stamp
            string frame_id
        geometry_msgs/Point32[] points
            float32 x
            float32 y
            float32 z
        sensor_msgs/ChannelFloat32[] channels
            string name
            float32[] values
    object_manipulation_msgs/SceneRegion region
        sensor_msgs/PointCloud2 cloud
            Header header
                uint32 seq
                time stamp
                string frame_id
            uint32 height
            uint32 width
            sensor_msgs/PointField[] fields
                uint8 INT8=1
                uint8 UINT8=2
                uint8 INT16=3
                uint8 UINT16=4
                uint8 INT32=5
                uint8 UINT32=6
                uint8 FLOAT32=7
                uint8 FLOAT64=8
                string name
                uint32 offset
                uint8 datatype
                uint32 count
            bool is_bigendian
            uint32 point_step
            uint32 row_step
            uint8[] data
            bool is_dense
        int32[] mask
        sensor_msgs/Image image
            Header header
                uint32 seq
                time stamp
                string frame_id
            uint32 height
            uint32 width
            string encoding
            uint8 is_bigendian
            uint32 step
            uint8[] data
        sensor_msgs/Image disparity_image
            Header header
                uint32 seq
                time stamp
                string frame_id
            uint32 height
            uint32 width
            string encoding
            uint8 is_bigendian
            uint32 step
            uint8[] data
        sensor_msgs/CameraInfo cam_info
            Header header
                uint32 seq
                time stamp
                string frame_id
            uint32 height
            uint32 width
            string distortion_model
            float64[] D
            float64[9] K
            float64[9] R
            float64[12] P
            uint32 binning_x
            uint32 binning_y
            sensor_msgs/RegionOfInterest roi
                uint32 x_offset
                uint32 y_offset
                uint32 height
                uint32 width
                bool do_rectify
string collision_object_name
string collision_support_surface_name
Grasp[] grasps_to_evaluate
    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[] 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
GraspPlanningErrorCode error_code
    int32 SUCCESS=0
    int32 TF_ERROR=1
    int32 OTHER_ERROR=2
    int32 value