tabletop_object_detector/TabletopDetectionResult Message

File: tabletop_object_detector/TabletopDetectionResult.msg

# Contains all the information from one run of the tabletop detection node

# The information for the plane that has been detected
Table table

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

# The list of potential models that have been detected for each cluster
# An empty list will be returned for a cluster that has no recognition results at all
household_objects_database_msgs/DatabaseModelPoseList[] models

# For each cluster, the index of the list of models that was fit to that cluster
# keep in mind that multiple raw clusters can correspond to a single fit
int32[] cluster_model_indices

# 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
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
household_objects_database_msgs/DatabaseModelPoseList[] models
    household_objects_database_msgs/DatabaseModelPose[] model_list
        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
int32[] cluster_model_indices
int32 result