planning_environment_msgs/GetCollisionObjects Service

File: planning_environment_msgs/GetCollisionObjects.srv

#Whether or not to include the points in the collision map
#if set to false, collision map in feedback will contain
#no points
bool include_points
---
#points in the collision map if include_points is set to true
mapping_msgs/CollisionMap points
#vector of collision objects in the collision map
mapping_msgs/CollisionObject[] collision_objects
#vector of attached collision objects in the collision map
mapping_msgs/AttachedCollisionObject[] attached_collision_objects

Expanded Definition

bool include_points

mapping_msgs/CollisionMap points
    Header header
        uint32 seq
        time stamp
        string frame_id
    mapping_msgs/OrientedBoundingBox[] boxes
        geometry_msgs/Point32 center
            float32 x
            float32 y
            float32 z
        geometry_msgs/Point32 extents
            float32 x
            float32 y
            float32 z
        geometry_msgs/Point32 axis
            float32 x
            float32 y
            float32 z
        float32 angle
mapping_msgs/CollisionObject[] collision_objects
    Header header
        uint32 seq
        time stamp
        string frame_id
    string id
    mapping_msgs/CollisionObjectOperation operation
        byte ADD=0
        byte REMOVE=1
        byte DETACH_AND_ADD_AS_OBJECT=2
        byte ATTACH_AND_REMOVE_AS_OBJECT=3
        byte operation
    geometric_shapes_msgs/Shape[] shapes
        byte SPHERE=0
        byte BOX=1
        byte CYLINDER=2
        byte MESH=3
        byte type
        float64[] dimensions
        int32[] triangles
        geometry_msgs/Point[] vertices
            float64 x
            float64 y
            float64 z
    geometry_msgs/Pose[] poses
        geometry_msgs/Point position
            float64 x
            float64 y
            float64 z
        geometry_msgs/Quaternion orientation
            float64 x
            float64 y
            float64 z
            float64 w
mapping_msgs/AttachedCollisionObject[] attached_collision_objects
    string REMOVE_ALL_ATTACHED_OBJECTS="all"
    string link_name
    mapping_msgs/CollisionObject object
        Header header
            uint32 seq
            time stamp
            string frame_id
        string id
        mapping_msgs/CollisionObjectOperation operation
            byte ADD=0
            byte REMOVE=1
            byte DETACH_AND_ADD_AS_OBJECT=2
            byte ATTACH_AND_REMOVE_AS_OBJECT=3
            byte operation
        geometric_shapes_msgs/Shape[] shapes
            byte SPHERE=0
            byte BOX=1
            byte CYLINDER=2
            byte MESH=3
            byte type
            float64[] dimensions
            int32[] triangles
            geometry_msgs/Point[] vertices
                float64 x
                float64 y
                float64 z
        geometry_msgs/Pose[] poses
            geometry_msgs/Point position
                float64 x
                float64 y
                float64 z
            geometry_msgs/Quaternion orientation
                float64 x
                float64 y
                float64 z
                float64 w
    string[] touch_links