Namespaces | Functions
body_operations.h File Reference
#include "geometric_shapes/shapes.h"
#include "geometric_shapes/bodies.h"
#include "geometric_shapes/shape_messages.h"
#include <geometry_msgs/Pose.h>
#include <visualization_msgs/Marker.h>
#include <vector>
Include dependency graph for body_operations.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 bodies
 This set of classes allows quickly detecting whether a given point is inside an object or not. This capability is useful when removing points from inside the robot (when the robot sees its arms, for example).
 

Functions

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...
 


geometric_shapes
Author(s): Ioan Sucan , Gil Jones
autogenerated on Sun Oct 1 2023 02:40:16