|
void | bodies::computeBoundingSphere (const std::vector< const Body * > &bodies, BoundingSphere &mergedSphere) |
| Compute the bounding sphere for a set of bodies and store the resulting sphere in mergedSphere. More...
|
|
Body * | bodies::constructBodyFromMsg (const shape_msgs::Mesh &shape, const geometry_msgs::Pose &pose) |
| Create a body from a given shape. More...
|
|
Body * | bodies::constructBodyFromMsg (const shape_msgs::SolidPrimitive &shape, const geometry_msgs::Pose &pose) |
| Create a body from a given shape. More...
|
|
Body * | bodies::constructBodyFromMsg (const shapes::ShapeMsg &shape, const geometry_msgs::Pose &pose) |
| Create a body from a given shape. More...
|
|
void | bodies::constructMarkerFromBody (const bodies::Body *body, visualization_msgs::Marker &msg) |
| Construct a Marker message that corresponds to this (scaled and padded) body. More...
|
|
shapes::ShapeConstPtr | bodies::constructShapeFromBody (const bodies::Body *body) |
| Get a shape that corresponds to this (scaled and padded) body. More...
|
|
Body * | bodies::createBodyFromShape (const shapes::Shape *shape) |
| Create a body from a given shape. More...
|
|
Body * | bodies::createEmptyBodyFromShapeType (const shapes::ShapeType &shapeType) |
| Create a body from a given shape. More...
|
|
void | bodies::mergeBoundingBoxes (const std::vector< AABB > &boxes, AABB &mergedBox) |
| Compute an axis-aligned bounding box to enclose a set of bounding boxes. More...
|
|
void | bodies::mergeBoundingBoxesApprox (const std::vector< OBB > &boxes, OBB &mergedBox) |
| Compute an approximate oriented bounding box to enclose a set of bounding boxes. More...
|
|
void | bodies::mergeBoundingSpheres (const std::vector< BoundingSphere > &spheres, BoundingSphere &mergedSphere) |
| Compute a bounding sphere to enclose a set of bounding spheres. More...
|
|