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 | |
namespace | detail |
Classes | |
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 | Sphere |
Definition of a sphere. More... | |
Typedefs | |
typedef boost::shared_ptr < const Body > | BodyConstPtr |
Shared pointer to a const Body. | |
typedef boost::shared_ptr< Body > | BodyPtr |
Shared pointer to a Body. | |
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. | |
Body * | constructBodyFromMsg (const shape_msgs::Mesh &shape, const geometry_msgs::Pose &pose) |
Create a body from a given shape. | |
Body * | constructBodyFromMsg (const shape_msgs::SolidPrimitive &shape, const geometry_msgs::Pose &pose) |
Create a body from a given shape. | |
Body * | constructBodyFromMsg (const shapes::ShapeMsg &shape, const geometry_msgs::Pose &pose) |
Create a body from a given shape. | |
template<typename T > | |
Body * | constructBodyFromMsgHelper (const T &shape_msg, const geometry_msgs::Pose &pose) |
Body * | createBodyFromShape (const shapes::Shape *shape) |
Create a body from a given shape. | |
void | mergeBoundingSpheres (const std::vector< BoundingSphere > &spheres, BoundingSphere &mergedSphere) |
Compute a bounding sphere to enclose a set of bounding spheres. |
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 boost::shared_ptr< const Body > bodies::BodyConstPtr |
typedef boost::shared_ptr< Body > bodies::BodyPtr |
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.
bodies::Body * bodies::constructBodyFromMsg | ( | const shape_msgs::Mesh & | shape, |
const geometry_msgs::Pose & | pose | ||
) |
Create a body from a given shape.
Definition at line 132 of file body_operations.cpp.
bodies::Body * bodies::constructBodyFromMsg | ( | const shape_msgs::SolidPrimitive & | shape, |
const geometry_msgs::Pose & | pose | ||
) |
Create a body from a given shape.
Definition at line 137 of file body_operations.cpp.
bodies::Body * bodies::constructBodyFromMsg | ( | const shapes::ShapeMsg & | shape, |
const geometry_msgs::Pose & | pose | ||
) |
Create a body from a given shape.
Definition at line 127 of file body_operations.cpp.
Body* bodies::constructBodyFromMsgHelper | ( | const T & | shape_msg, |
const geometry_msgs::Pose & | pose | ||
) |
Definition at line 103 of file body_operations.cpp.
bodies::Body * bodies::createBodyFromShape | ( | const shapes::Shape * | shape | ) |
Create a body from a given shape.
Definition at line 42 of file body_operations.cpp.
void bodies::mergeBoundingSpheres | ( | const std::vector< BoundingSphere > & | spheres, |
BoundingSphere & | mergedSphere | ||
) |
Compute a bounding sphere to enclose a set of bounding spheres.
Definition at line 69 of file body_operations.cpp.