A body is a shape + its pose. Point inclusion, ray intersection can be tested, volumes and bounding spheres can be computed. More...
#include <bodies.h>

| Public Member Functions | |
| Body () | |
| BodyPtr | cloneAt (const Eigen::Affine3d &pose) const | 
| Get a clone of this body, but one that is located at the pose pose. | |
| virtual BodyPtr | cloneAt (const Eigen::Affine3d &pose, double padding, double scaling) const =0 | 
| Get a clone of this body, but one that is located at the pose pose and has possibly different passing and scaling: padding and scaling. This function is useful to implement thread safety, when bodies need to be moved around. | |
| virtual void | computeBoundingCylinder (BoundingCylinder &cylinder) const =0 | 
| Compute the bounding cylinder for the body, in its current pose. Scaling and padding are accounted for. | |
| virtual void | computeBoundingSphere (BoundingSphere &sphere) const =0 | 
| Compute the bounding radius for the body, in its current pose. Scaling and padding are accounted for. | |
| virtual double | computeVolume () const =0 | 
| Compute the volume of the body. This method includes changes induced by scaling and padding. | |
| bool | containsPoint (double x, double y, double z, bool verbose=false) const | 
| Check if a point is inside the body. | |
| virtual bool | containsPoint (const Eigen::Vector3d &p, bool verbose=false) const =0 | 
| Check if a point is inside the body. | |
| virtual std::vector< double > | getDimensions () const =0 | 
| Get the dimensions associated to this body (as read from corresponding shape) | |
| double | getPadding () const | 
| Retrieve the current padding. | |
| const Eigen::Affine3d & | getPose () const | 
| Retrieve the pose of the body. | |
| double | getScale () const | 
| Retrieve the current scale. | |
| shapes::ShapeType | getType () const | 
| Get the type of shape this body represents. | |
| virtual bool | intersectsRay (const Eigen::Vector3d &origin, const Eigen::Vector3d &dir, EigenSTL::vector_Vector3d *intersections=NULL, unsigned int count=0) const =0 | 
| Check if a ray intersects the body, and find the set of intersections, in order, along the ray. A maximum number of intersections can be specified as well. If that number is 0, all intersections are returned. | |
| virtual bool | samplePointInside (random_numbers::RandomNumberGenerator &rng, unsigned int max_attempts, Eigen::Vector3d &result) | 
| Sample a point that is included in the body using a given random number generator. Sometimes multiple attempts need to be generated; the function terminates with failure (returns false) after max_attempts attempts. If the call is successful (returns true) the point is written to result. | |
| void | setDimensions (const shapes::Shape *shape) | 
| Set the dimensions of the body (from corresponding shape) | |
| void | setPadding (double padd) | 
| If constant padding should be added to the body, this method sets the padding. Default is 0.0. | |
| void | setPose (const Eigen::Affine3d &pose) | 
| Set the pose of the body. Default is identity. | |
| void | setScale (double scale) | 
| If the dimension of the body should be scaled, this method sets the scale. Default is 1.0. | |
| virtual | ~Body () | 
| Protected Member Functions | |
| virtual void | updateInternalData ()=0 | 
| This function is called every time a change to the body is made, so that intermediate values stored for efficiency reasons are kept up to date. | |
| virtual void | useDimensions (const shapes::Shape *shape)=0 | 
| Depending on the shape, this function copies the relevant data to the body. | |
| Protected Attributes | |
| double | padding_ | 
| The scale that was set for this body. | |
| Eigen::Affine3d | pose_ | 
| The location of the body (position and orientation) | |
| double | scale_ | 
| The scale that was set for this body. | |
| shapes::ShapeType | type_ | 
| The type of shape this body was constructed from. | |
A body is a shape + its pose. Point inclusion, ray intersection can be tested, volumes and bounding spheres can be computed.
| bodies::Body::Body | ( | ) |  [inline] | 
| virtual bodies::Body::~Body | ( | ) |  [inline, virtual] | 
| BodyPtr bodies::Body::cloneAt | ( | const Eigen::Affine3d & | pose | ) | const  [inline] | 
| virtual BodyPtr bodies::Body::cloneAt | ( | const Eigen::Affine3d & | pose, | 
| double | padding, | ||
| double | scaling | ||
| ) | const  [pure virtual] | 
Get a clone of this body, but one that is located at the pose pose and has possibly different passing and scaling: padding and scaling. This function is useful to implement thread safety, when bodies need to be moved around.
Implemented in bodies::ConvexMesh, bodies::Box, bodies::Cylinder, and bodies::Sphere.
| virtual void bodies::Body::computeBoundingCylinder | ( | BoundingCylinder & | cylinder | ) | const  [pure virtual] | 
Compute the bounding cylinder for the body, in its current pose. Scaling and padding are accounted for.
Implemented in bodies::ConvexMesh, bodies::Box, bodies::Cylinder, and bodies::Sphere.
| virtual void bodies::Body::computeBoundingSphere | ( | BoundingSphere & | sphere | ) | const  [pure virtual] | 
Compute the bounding radius for the body, in its current pose. Scaling and padding are accounted for.
Implemented in bodies::ConvexMesh, bodies::Box, bodies::Cylinder, and bodies::Sphere.
| virtual double bodies::Body::computeVolume | ( | ) | const  [pure virtual] | 
Compute the volume of the body. This method includes changes induced by scaling and padding.
Implemented in bodies::ConvexMesh, bodies::Box, bodies::Cylinder, and bodies::Sphere.
| bool bodies::Body::containsPoint | ( | double | x, | 
| double | y, | ||
| double | z, | ||
| bool | verbose = false | ||
| ) | const  [inline] | 
| virtual bool bodies::Body::containsPoint | ( | const Eigen::Vector3d & | p, | 
| bool | verbose = false | ||
| ) | const  [pure virtual] | 
Check if a point is inside the body.
Implemented in bodies::ConvexMesh, bodies::Box, bodies::Cylinder, and bodies::Sphere.
| virtual std::vector<double> bodies::Body::getDimensions | ( | ) | const  [pure virtual] | 
Get the dimensions associated to this body (as read from corresponding shape)
Implemented in bodies::ConvexMesh, bodies::Box, bodies::Cylinder, and bodies::Sphere.
| double bodies::Body::getPadding | ( | ) | const  [inline] | 
| const Eigen::Affine3d& bodies::Body::getPose | ( | ) | const  [inline] | 
| double bodies::Body::getScale | ( | ) | const  [inline] | 
| shapes::ShapeType bodies::Body::getType | ( | ) | const  [inline] | 
| virtual bool bodies::Body::intersectsRay | ( | const Eigen::Vector3d & | origin, | 
| const Eigen::Vector3d & | dir, | ||
| EigenSTL::vector_Vector3d * | intersections = NULL, | ||
| unsigned int | count = 0 | ||
| ) | const  [pure virtual] | 
Check if a ray intersects the body, and find the set of intersections, in order, along the ray. A maximum number of intersections can be specified as well. If that number is 0, all intersections are returned.
Implemented in bodies::ConvexMesh, bodies::Box, bodies::Cylinder, and bodies::Sphere.
| bool bodies::Body::samplePointInside | ( | random_numbers::RandomNumberGenerator & | rng, | 
| unsigned int | max_attempts, | ||
| Eigen::Vector3d & | result | ||
| ) |  [virtual] | 
Sample a point that is included in the body using a given random number generator. Sometimes multiple attempts need to be generated; the function terminates with failure (returns false) after max_attempts attempts. If the call is successful (returns true) the point is written to result.
Reimplemented in bodies::Box, bodies::Cylinder, and bodies::Sphere.
Definition at line 114 of file bodies.cpp.
| void bodies::Body::setDimensions | ( | const shapes::Shape * | shape | ) | 
Set the dimensions of the body (from corresponding shape)
Definition at line 108 of file bodies.cpp.
| void bodies::Body::setPadding | ( | double | padd | ) |  [inline] | 
| void bodies::Body::setPose | ( | const Eigen::Affine3d & | pose | ) |  [inline] | 
| void bodies::Body::setScale | ( | double | scale | ) |  [inline] | 
| virtual void bodies::Body::updateInternalData | ( | ) |  [protected, pure virtual] | 
This function is called every time a change to the body is made, so that intermediate values stored for efficiency reasons are kept up to date.
Implemented in bodies::ConvexMesh, bodies::Box, bodies::Cylinder, and bodies::Sphere.
| virtual void bodies::Body::useDimensions | ( | const shapes::Shape * | shape | ) |  [protected, pure virtual] | 
Depending on the shape, this function copies the relevant data to the body.
Implemented in bodies::ConvexMesh, bodies::Box, bodies::Cylinder, and bodies::Sphere.
| double bodies::Body::padding_  [protected] | 
| Eigen::Affine3d bodies::Body::pose_  [protected] | 
| double bodies::Body::scale_  [protected] | 
| shapes::ShapeType bodies::Body::type_  [protected] |