object_manipulation_msgs/SceneRegion Message

File: object_manipulation_msgs/SceneRegion.msg

# Point cloud
sensor_msgs/PointCloud2 cloud

# Indices for the region of interest
int32[] mask

# One of the corresponding 2D images, if applicable
sensor_msgs/Image image

# The disparity image, if applicable
sensor_msgs/Image disparity_image

# Camera info for the camera that took the image
sensor_msgs/CameraInfo cam_info

Expanded Definition

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