tabletop_object_detector/TabletopDetection Service

File: tabletop_object_detector/TabletopDetection.srv

# service will run on last received cloud, no cloud is passed in

# clustering is done as an intermediate step for model detection
# but we can also return the clusters themselves if the caller wants them
# this flag tells whether the computed clusters should be returned
bool return_clusters

# if only clusters are of interest, then model fitting can be skipped
# this flag tells whether model fitting should be performed and the results returned
bool return_models

# The number of potential fit models which should be returned for each cluster 
int32 num_models
---
# reply is message with table and models
TabletopDetectionResult detection

Expanded Definition

bool return_clusters
bool return_models
int32 num_models

TabletopDetectionResult detection
    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
    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