pr2_grasp_adjust/GraspAdjust Service

File: pr2_grasp_adjust/GraspAdjust.srv

geometry_msgs/PoseStamped   grasp_pose
geometry_msgs/Vector3       roi_dims
uint8                       search_mode 

int32 GLOBAL_SEARCH = 0
int32 LOCAL_SEARCH = 1
int32 SINGLE_POSE = 2

---
geometry_msgs/PoseStamped[]  grasp_poses
float64[]  pose_scores
float32[]  gripper_openings

object_manipulation_msgs/ManipulationResult result


Expanded Definition

int32 GLOBAL_SEARCH=0
int32 LOCAL_SEARCH=1
int32 SINGLE_POSE=2
geometry_msgs/PoseStamped grasp_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
geometry_msgs/Vector3 roi_dims
    float64 x
    float64 y
    float64 z
uint8 search_mode

geometry_msgs/PoseStamped[] grasp_poses
    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
float64[] pose_scores
float32[] gripper_openings
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