object_manipulation_msgs/FindClusterBoundingBox Service

File: object_manipulation_msgs/FindClusterBoundingBox.srv

sensor_msgs/PointCloud cluster

---

#the pose of the box frame
geometry_msgs/PoseStamped pose

#the dimensions of the box
geometry_msgs/Vector3 box_dims

#whether there was an error
int32 SUCCESS=0
int32 TF_ERROR=1
int32 error_code

Expanded Definition

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

int32 SUCCESS=0
int32 TF_ERROR=1
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
geometry_msgs/Vector3 box_dims
    float64 x
    float64 y
    float64 z
int32 error_code