Classes | Public Member Functions | Protected Member Functions | Protected Attributes | Private Attributes
bodies::ConvexMesh Class Reference

Definition of a convex mesh. Convex hull is computed for a given shape::Mesh. More...

#include <bodies.h>

Inheritance diagram for bodies::ConvexMesh:
Inheritance graph
[legend]

List of all members.

Classes

struct  MeshData

Public Member Functions

virtual BodyPtr cloneAt (const Eigen::Affine3d &pose, double padding, double scale) const
 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
 Compute the bounding cylinder for the body, in its current pose. Scaling and padding are accounted for.
virtual void computeBoundingSphere (BoundingSphere &sphere) const
 Compute the bounding radius for the body, in its current pose. Scaling and padding are accounted for.
void computeScaledVerticesFromPlaneProjections ()
 Project the original vertex to the scaled and padded planes and average.
virtual double computeVolume () const
 Compute the volume of the body. This method includes changes induced by scaling and padding.
virtual bool containsPoint (const Eigen::Vector3d &p, bool verbose=false) const
 Check if a point is inside the body.
 ConvexMesh ()
 ConvexMesh (const shapes::Shape *shape)
void correctVertexOrderFromPlanes ()
virtual std::vector< double > getDimensions () const
 Returns an empty vector.
const EigenSTL::vector_Vector3dgetScaledVertices () const
const std::vector< unsigned int > & getTriangles () const
const EigenSTL::vector_Vector3dgetVertices () const
virtual bool intersectsRay (const Eigen::Vector3d &origin, const Eigen::Vector3d &dir, EigenSTL::vector_Vector3d *intersections=NULL, unsigned int count=0) const
 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 ~ConvexMesh ()

Protected Member Functions

unsigned int countVerticesBehindPlane (const Eigen::Vector4f &planeNormal) const
 (Used mainly for debugging) Count the number of vertices behind a plane
bool isPointInsidePlanes (const Eigen::Vector3d &point) const
 Check if a point is inside a set of planes that make up a convex mesh.
virtual void updateInternalData ()
 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)
 Depending on the shape, this function copies the relevant data to the body.

Protected Attributes

Box bounding_box_
Eigen::Vector3d center_
Eigen::Affine3d i_pose_
boost::shared_ptr< MeshDatamesh_data_
double radiusB_
double radiusBSqr_
EigenSTL::vector_Vector3dscaled_vertices_

Private Attributes

boost::scoped_ptr
< EigenSTL::vector_Vector3d
scaled_vertices_storage_

Detailed Description

Definition of a convex mesh. Convex hull is computed for a given shape::Mesh.

Definition at line 390 of file bodies.h.


Constructor & Destructor Documentation

Definition at line 394 of file bodies.h.

bodies::ConvexMesh::ConvexMesh ( const shapes::Shape shape) [inline]

Definition at line 400 of file bodies.h.

virtual bodies::ConvexMesh::~ConvexMesh ( ) [inline, virtual]

Definition at line 407 of file bodies.h.


Member Function Documentation

boost::shared_ptr< bodies::Body > bodies::ConvexMesh::cloneAt ( const Eigen::Affine3d &  pose,
double  padding,
double  scaling 
) const [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.

Implements bodies::Body.

Definition at line 970 of file bodies.cpp.

void bodies::ConvexMesh::computeBoundingCylinder ( BoundingCylinder cylinder) const [virtual]

Compute the bounding cylinder for the body, in its current pose. Scaling and padding are accounted for.

Implements bodies::Body.

Definition at line 987 of file bodies.cpp.

void bodies::ConvexMesh::computeBoundingSphere ( BoundingSphere sphere) const [virtual]

Compute the bounding radius for the body, in its current pose. Scaling and padding are accounted for.

Implements bodies::Body.

Definition at line 981 of file bodies.cpp.

Project the original vertex to the scaled and padded planes and average.

Definition at line 860 of file bodies.cpp.

double bodies::ConvexMesh::computeVolume ( ) const [virtual]

Compute the volume of the body. This method includes changes induced by scaling and padding.

Implements bodies::Body.

Definition at line 1025 of file bodies.cpp.

bool bodies::ConvexMesh::containsPoint ( const Eigen::Vector3d &  p,
bool  verbose = false 
) const [virtual]

Check if a point is inside the body.

Implements bodies::Body.

Definition at line 657 of file bodies.cpp.

Definition at line 670 of file bodies.cpp.

unsigned int bodies::ConvexMesh::countVerticesBehindPlane ( const Eigen::Vector4f &  planeNormal) const [protected]

(Used mainly for debugging) Count the number of vertices behind a plane

Definition at line 1011 of file bodies.cpp.

std::vector< double > bodies::ConvexMesh::getDimensions ( ) const [virtual]

Returns an empty vector.

Implements bodies::Body.

Definition at line 855 of file bodies.cpp.

Definition at line 965 of file bodies.cpp.

const std::vector< unsigned int > & bodies::ConvexMesh::getTriangles ( ) const

Definition at line 953 of file bodies.cpp.

Definition at line 959 of file bodies.cpp.

bool bodies::ConvexMesh::intersectsRay ( const Eigen::Vector3d &  origin,
const Eigen::Vector3d &  dir,
EigenSTL::vector_Vector3d intersections = NULL,
unsigned int  count = 0 
) const [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.

Implements bodies::Body.

Definition at line 1039 of file bodies.cpp.

bool bodies::ConvexMesh::isPointInsidePlanes ( const Eigen::Vector3d &  point) const [protected]

Check if a point is inside a set of planes that make up a convex mesh.

Definition at line 997 of file bodies.cpp.

void bodies::ConvexMesh::updateInternalData ( ) [protected, 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.

Implements bodies::Body.

Definition at line 918 of file bodies.cpp.

void bodies::ConvexMesh::useDimensions ( const shapes::Shape shape) [protected, virtual]

Depending on the shape, this function copies the relevant data to the body.

Implements bodies::Body.

Definition at line 692 of file bodies.cpp.


Member Data Documentation

Definition at line 466 of file bodies.h.

Eigen::Vector3d bodies::ConvexMesh::center_ [protected]

Definition at line 463 of file bodies.h.

Eigen::Affine3d bodies::ConvexMesh::i_pose_ [protected]

Definition at line 462 of file bodies.h.

boost::shared_ptr<MeshData> bodies::ConvexMesh::mesh_data_ [protected]

Definition at line 459 of file bodies.h.

double bodies::ConvexMesh::radiusB_ [protected]

Definition at line 464 of file bodies.h.

double bodies::ConvexMesh::radiusBSqr_ [protected]

Definition at line 465 of file bodies.h.

Definition at line 471 of file bodies.h.

Definition at line 474 of file bodies.h.


The documentation for this class was generated from the following files:


geometric_shapes
Author(s): Ioan Sucan , Gil Jones
autogenerated on Thu Jun 6 2019 20:13:53