Go to the documentation of this file.
37 #ifndef GEOMETRIC_SHAPES_BODY_OPERATIONS_
38 #define GEOMETRIC_SHAPES_BODY_OPERATIONS_
43 #include <geometry_msgs/Pose.h>
44 #include <visualization_msgs/Marker.h>
59 Body*
constructBodyFromMsg(
const shape_msgs::SolidPrimitive& shape,
const geometry_msgs::Pose& pose);
71 void mergeBoundingSpheres(
const std::vector<BoundingSphere>& spheres, BoundingSphere& mergedSphere);
boost::variant< shape_msgs::SolidPrimitive, shape_msgs::Mesh, shape_msgs::Plane > ShapeMsg
Type that can hold any of the desired shape message types.
void constructMarkerFromBody(const bodies::Body *body, visualization_msgs::Marker &msg)
Construct a Marker message that corresponds to this (scaled and padded) body.
void mergeBoundingBoxesApprox(const std::vector< OBB > &boxes, OBB &mergedBox)
Compute an approximate oriented bounding box to enclose a set of bounding boxes.
A basic definition of a shape. Shapes are considered centered at origin.
void mergeBoundingBoxes(const std::vector< AABB > &boxes, AABB &mergedBox)
Compute an axis-aligned bounding box to enclose a set of bounding boxes.
A body is a shape + its pose. Point inclusion, ray intersection can be tested, volumes and bounding s...
void 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.
Body * constructBodyFromMsg(const shape_msgs::Mesh &shape, const geometry_msgs::Pose &pose)
Create a body from a given shape.
Body * createEmptyBodyFromShapeType(const shapes::ShapeType &shapeType)
Create a body from a given shape.
ShapeType
A list of known shape types.
shapes::ShapeConstPtr constructShapeFromBody(const bodies::Body *body)
Get a shape that corresponds to this (scaled and padded) body.
This set of classes allows quickly detecting whether a given point is inside an object or not....
void mergeBoundingSpheres(const std::vector< BoundingSphere > &spheres, BoundingSphere &mergedSphere)
Compute a bounding sphere to enclose a set of bounding spheres.
std::shared_ptr< const Shape > ShapeConstPtr
Shared pointer to a const Shape.
Body * createBodyFromShape(const shapes::Shape *shape)
Create a body from a given shape.
geometric_shapes
Author(s): Ioan Sucan
, Gil Jones
autogenerated on Tue Aug 13 2024 02:40:57