Namespaces | Classes | Typedefs | Functions
bodies Namespace Reference

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

Namespaces

 detail
 

Classes

class  AABB
 Represents an axis-aligned bounding box. More...
 
class  Body
 A body is a shape + its pose. Point inclusion, ray intersection can be tested, volumes and bounding spheres can be computed. More...
 
class  BodyVector
 A vector of Body objects. More...
 
struct  BoundingCylinder
 Definition of a cylinder. More...
 
struct  BoundingSphere
 Definition of a sphere that bounds another object. More...
 
class  Box
 Definition of a box. More...
 
class  ConvexMesh
 Definition of a convex mesh. Convex hull is computed for a given shape::Mesh. More...
 
class  Cylinder
 Definition of a cylinder. More...
 
class  OBB
 Represents an oriented bounding box. More...
 
class  OBBPrivate
 
class  Sphere
 Definition of a sphere. More...
 

Typedefs

typedef std::shared_ptr< const BodyBodyConstPtr
 Shared pointer to a const Body. More...
 
typedef std::shared_ptr< BodyBodyPtr
 Shared pointer to a Body. More...
 

Functions

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. More...
 
BodyconstructBodyFromMsg (const shape_msgs::Mesh &shape, const geometry_msgs::Pose &pose)
 Create a body from a given shape. More...
 
BodyconstructBodyFromMsg (const shape_msgs::SolidPrimitive &shape, const geometry_msgs::Pose &pose)
 Create a body from a given shape. More...
 
BodyconstructBodyFromMsg (const shapes::ShapeMsg &shape, const geometry_msgs::Pose &pose)
 Create a body from a given shape. More...
 
template<typename T >
BodyconstructBodyFromMsgHelper (const T &shape_msg, const geometry_msgs::Pose &pose)
 
void constructMarkerFromBody (const bodies::Body *body, visualization_msgs::Marker &msg)
 Construct a Marker message that corresponds to this (scaled and padded) body. More...
 
shapes::ShapeConstPtr constructShapeFromBody (const bodies::Body *body)
 Get a shape that corresponds to this (scaled and padded) body. More...
 
BodycreateBodyFromShape (const shapes::Shape *shape)
 Create a body from a given shape. More...
 
BodycreateEmptyBodyFromShapeType (const shapes::ShapeType &shapeType)
 Create a body from a given shape. More...
 
Eigen::Vector3d fromFcl (const FCL_Vec3 &fclVec)
 
void mergeBoundingBoxes (const std::vector< AABB > &boxes, AABB &mergedBox)
 Compute an axis-aligned bounding box to enclose a set of bounding boxes. More...
 
void mergeBoundingBoxesApprox (const std::vector< OBB > &boxes, OBB &mergedBox)
 Compute an approximate oriented bounding box to enclose a set of bounding boxes. More...
 
void mergeBoundingSpheres (const std::vector< BoundingSphere > &spheres, BoundingSphere &mergedSphere)
 Compute a bounding sphere to enclose a set of bounding spheres. More...
 
Eigen::Vector3d normalize (const Eigen::Vector3d &dir)
 
FCL_Vec3 toFcl (const Eigen::Vector3d &eigenVec)
 

Detailed Description

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

Typedef Documentation

◆ BodyConstPtr

typedef std::shared_ptr< const Body > bodies::BodyConstPtr

Shared pointer to a const Body.

Definition at line 84 of file bodies.h.

◆ BodyPtr

typedef std::shared_ptr< Body > bodies::BodyPtr

Shared pointer to a Body.

Definition at line 78 of file bodies.h.

Function Documentation

◆ computeBoundingSphere()

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.

◆ constructBodyFromMsg() [1/3]

bodies::Body * bodies::constructBodyFromMsg ( const shape_msgs::Mesh &  shape,
const geometry_msgs::Pose &  pose 
)

Create a body from a given shape.

Definition at line 212 of file body_operations.cpp.

◆ constructBodyFromMsg() [2/3]

bodies::Body * bodies::constructBodyFromMsg ( const shape_msgs::SolidPrimitive &  shape,
const geometry_msgs::Pose &  pose 
)

Create a body from a given shape.

Definition at line 217 of file body_operations.cpp.

◆ constructBodyFromMsg() [3/3]

bodies::Body * bodies::constructBodyFromMsg ( const shapes::ShapeMsg shape,
const geometry_msgs::Pose &  pose 
)

Create a body from a given shape.

Definition at line 207 of file body_operations.cpp.

◆ constructBodyFromMsgHelper()

template<typename T >
Body* bodies::constructBodyFromMsgHelper ( const T &  shape_msg,
const geometry_msgs::Pose &  pose 
)

Definition at line 181 of file body_operations.cpp.

◆ constructMarkerFromBody()

void bodies::constructMarkerFromBody ( const bodies::Body body,
visualization_msgs::Marker &  msg 
)

Construct a Marker message that corresponds to this (scaled and padded) body.

Definition at line 130 of file body_operations.cpp.

◆ constructShapeFromBody()

shapes::ShapeConstPtr bodies::constructShapeFromBody ( const bodies::Body body)

Get a shape that corresponds to this (scaled and padded) body.

Definition at line 81 of file body_operations.cpp.

◆ createBodyFromShape()

bodies::Body * bodies::createBodyFromShape ( const shapes::Shape shape)

Create a body from a given shape.

Definition at line 68 of file body_operations.cpp.

◆ createEmptyBodyFromShapeType()

bodies::Body * bodies::createEmptyBodyFromShapeType ( const shapes::ShapeType shapeType)

Create a body from a given shape.

Author
Ioan Sucan, E. Gil Jones

Definition at line 43 of file body_operations.cpp.

◆ fromFcl()

Eigen::Vector3d bodies::fromFcl ( const FCL_Vec3 fclVec)

Definition at line 29 of file obb.cpp.

◆ mergeBoundingBoxes()

void bodies::mergeBoundingBoxes ( const std::vector< AABB > &  boxes,
AABB mergedBox 
)

Compute an axis-aligned bounding box to enclose a set of bounding boxes.

◆ mergeBoundingBoxesApprox()

void bodies::mergeBoundingBoxesApprox ( const std::vector< OBB > &  boxes,
OBB mergedBox 
)

Compute an approximate oriented bounding box to enclose a set of bounding boxes.

◆ mergeBoundingSpheres()

void bodies::mergeBoundingSpheres ( const std::vector< BoundingSphere > &  spheres,
BoundingSphere mergedSphere 
)

Compute a bounding sphere to enclose a set of bounding spheres.

Definition at line 147 of file body_operations.cpp.

◆ normalize()

Eigen::Vector3d bodies::normalize ( const Eigen::Vector3d &  dir)
inline

Definition at line 151 of file bodies.cpp.

◆ toFcl()

FCL_Vec3 bodies::toFcl ( const Eigen::Vector3d &  eigenVec)
inline

Definition at line 18 of file obb.cpp.



geometric_shapes
Author(s): Ioan Sucan , Gil Jones
autogenerated on Fri Apr 14 2023 02:14:40