object_manipulation_msgs/GraspableObject Message

File: object_manipulation_msgs/GraspableObject.msg

# an object that the object_manipulator can work on

# a graspable object can be represented in multiple ways. This message
# can contain all of them. Which one is actually used is up to the receiver
# of this message. When adding new representations, one must be careful that
# they have reasonable lightweight defaults indicating that that particular
# representation is not available.

# the tf frame to be used as a reference frame when combining information from
# the different representations below
string reference_frame_id

# potential recognition results from a database of models
# all poses are relative to the object reference pose
household_objects_database_msgs/DatabaseModelPose[] potential_models

# the point cloud itself
sensor_msgs/PointCloud cluster

# a region of a PointCloud2 of interest
object_manipulation_msgs/SceneRegion region


Expanded Definition

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