object_segmentation_gui/ObjectSegmentationGuiResult Message

File: object_segmentation_gui/ObjectSegmentationGuiResult.msg

# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
# The information for the plane that has been detected
tabletop_object_detector/Table table

# The raw clusters detected in the scan 
sensor_msgs/PointCloud[] clusters

# Whether the detection has succeeded or failed
int32 NO_CLOUD_RECEIVED = 1
int32 NO_TABLE = 2
int32 OTHER_ERROR = 3
int32 SUCCESS = 4
int32 result


Expanded Definition

int32 NO_CLOUD_RECEIVED=1
int32 NO_TABLE=2
int32 OTHER_ERROR=3
int32 SUCCESS=4
tabletop_object_detector/Table table
    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 x_min
    float32 x_max
    float32 y_min
    float32 y_max
sensor_msgs/PointCloud[] clusters
    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 result