tabletop_collision_map_processing/TabletopCollisionMapProcessing Service

File: tabletop_collision_map_processing/TabletopCollisionMapProcessing.srv

# given the result of a tabletop detection, adds the objects to
# the collision map and returns them as instances of GraspableObjects
# with correct collision names

# a list of clusters and database models, directly as produced by the detector
# note that it is possible to not set the Table inside here (leave its
# extents set to zero), in which case it does not get added to the environment
tabletop_object_detector/TabletopDetectionResult detection_result

# whether the current collision models should be reset before adding new models
bool reset_collision_models

# whether the current list of models attached to the robot should be reset
bool reset_attached_models

# whether the static map should be reset before before any other processing is done
bool reset_static_map

# whether a new static map should be taken after objects are added
bool take_static_collision_map

# what tf frame the results should be returned in
# if empty, results will be in the same frame as the input 
string desired_frame

---

# the objects added to the collision environment and packaged as graspable objects
object_manipulation_msgs/GraspableObject[] graspable_objects

# the list of collision names that the objects got in the environment
# in the same order as graspable_objects
string[] collision_object_names

# the name that the table got in the collision map, if any
string collision_support_surface_name

Expanded Definition

tabletop_object_detector/TabletopDetectionResult detection_result
    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
bool reset_collision_models
bool reset_attached_models
bool reset_static_map
bool take_static_collision_map
string desired_frame

object_manipulation_msgs/GraspableObject[] graspable_objects
    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
string[] collision_object_names
string collision_support_surface_name