Classes | Public Member Functions | Protected Member Functions | Protected Attributes | Private Attributes | List of all members
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]

Classes

struct  MeshData
 

Public Member Functions

BodyPtr cloneAt (const Eigen::Isometry3d &pose, double padding, double scale) const override
 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. More...
 
void computeBoundingBox (AABB &bbox) const override
 Compute the axis-aligned bounding box for the body, in its current pose. Scaling and padding are accounted for. More...
 
void computeBoundingBox (OBB &bbox) const override
 Compute the oriented bounding box for the body, in its current pose. Scaling and padding are accounted for. More...
 
void computeBoundingCylinder (BoundingCylinder &cylinder) const override
 Compute the bounding cylinder for the body, in its current pose. Scaling and padding are accounted for. More...
 
void computeBoundingSphere (BoundingSphere &sphere) const override
 Compute the bounding radius for the body, in its current pose. Scaling and padding are accounted for. More...
 
void computeScaledVerticesFromPlaneProjections ()
 Project the original vertex to the scaled and padded planes and average. More...
 
double computeVolume () const override
 Compute the volume of the body. This method includes changes induced by scaling and padding. More...
 
bool containsPoint (const Eigen::Vector3d &p, bool verbose=false) const override
 Check if a point is inside the body. Surface points are included. More...
 
 ConvexMesh ()
 
 ConvexMesh (const shapes::Shape *shape)
 
void correctVertexOrderFromPlanes ()
 
std::vector< double > getDimensions () const override
 Returns an empty vector. More...
 
const EigenSTL::vector_Vector4dgetPlanes () const
 Get the planes that define the convex shape. More...
 
std::vector< double > getScaledDimensions () const override
 Returns an empty vector. More...
 
const EigenSTL::vector_Vector3dgetScaledVertices () const
 
const std::vector< unsigned int > & getTriangles () const
 
const EigenSTL::vector_Vector3dgetVertices () const
 
bool intersectsRay (const Eigen::Vector3d &origin, const Eigen::Vector3d &dir, EigenSTL::vector_Vector3d *intersections=nullptr, unsigned int count=0) const override
 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. Passing dir as a unit vector will result in faster computation. More...
 
void updateInternalData () override
 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. More...
 
 ~ConvexMesh () override=default
 
- Public Member Functions inherited from bodies::Body
 Body ()
 
BodyPtr cloneAt (const Eigen::Isometry3d &pose) const
 Get a clone of this body, but one that is located at the pose pose. More...
 
bool containsPoint (double x, double y, double z, bool verbose=false) const
 Check if a point is inside the body. More...
 
double getPadding () const
 Retrieve the current padding. More...
 
const Eigen::Isometry3d & getPose () const
 Retrieve the pose of the body. More...
 
double getScale () const
 Retrieve the current scale. More...
 
shapes::ShapeType getType () const
 Get the type of shape this body represents. More...
 
virtual bool samplePointInside (random_numbers::RandomNumberGenerator &rng, unsigned int max_attempts, Eigen::Vector3d &result) const
 Sample a point that is included in the body using a given random number generator. More...
 
void setDimensions (const shapes::Shape *shape)
 Set the dimensions of the body (from corresponding shape) More...
 
void setDimensionsDirty (const shapes::Shape *shape)
 Set the dimensions of the body (from corresponding shape). More...
 
void setPadding (double padd)
 If constant padding should be added to the body, this method sets the padding. Default is 0.0. More...
 
void setPaddingDirty (double padd)
 If the dimension of the body should be padded, this method sets the pading. More...
 
void setPose (const Eigen::Isometry3d &pose)
 Set the pose of the body. Default is identity. More...
 
void setPoseDirty (const Eigen::Isometry3d &pose)
 Set the pose of the body. More...
 
void setScale (double scale)
 If the dimension of the body should be scaled, this method sets the scale. Default is 1.0. More...
 
void setScaleDirty (double scale)
 If the dimension of the body should be scaled, this method sets the scale. More...
 
virtual ~Body ()=default
 

Protected Member Functions

unsigned int countVerticesBehindPlane (const Eigen::Vector4f &planeNormal) const
 (Used mainly for debugging) Count the number of vertices behind a plane More...
 
bool isPointInsidePlanes (const Eigen::Vector3d &point) const
 Check if the point is inside all halfspaces this mesh consists of (mesh_data_->planes_). More...
 
void useDimensions (const shapes::Shape *shape) override
 Depending on the shape, this function copies the relevant data to the body. More...
 

Protected Attributes

Box bounding_box_
 
Eigen::Vector3d center_
 
Eigen::Isometry3d i_pose_
 
std::shared_ptr< MeshDatamesh_data_
 
double radiusB_
 
double radiusBSqr_
 
EigenSTL::vector_Vector3dscaled_vertices_
 
- Protected Attributes inherited from bodies::Body
double padding_
 The scale that was set for this body. More...
 
Eigen::Isometry3d pose_
 The location of the body (position and orientation) More...
 
double scale_
 The scale that was set for this body. More...
 
shapes::ShapeType type_
 The type of shape this body was constructed from. More...
 

Private Attributes

std::unique_ptr< EigenSTL::vector_Vector3dscaled_vertices_storage_
 

Detailed Description

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

Definition at line 506 of file bodies.h.

Constructor & Destructor Documentation

◆ ConvexMesh() [1/2]

bodies::ConvexMesh::ConvexMesh ( )
inline

Definition at line 509 of file bodies.h.

◆ ConvexMesh() [2/2]

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

Definition at line 515 of file bodies.h.

◆ ~ConvexMesh()

bodies::ConvexMesh::~ConvexMesh ( )
overridedefault

Member Function Documentation

◆ cloneAt()

std::shared_ptr< bodies::Body > bodies::ConvexMesh::cloneAt ( const Eigen::Isometry3d &  pose,
double  padding,
double  scaling 
) const
overridevirtual

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 1147 of file bodies.cpp.

◆ computeBoundingBox() [1/2]

void bodies::ConvexMesh::computeBoundingBox ( AABB bbox) const
overridevirtual

Compute the axis-aligned bounding box for the body, in its current pose. Scaling and padding are accounted for.

Implements bodies::Body.

Definition at line 1176 of file bodies.cpp.

◆ computeBoundingBox() [2/2]

void bodies::ConvexMesh::computeBoundingBox ( OBB bbox) const
overridevirtual

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

Implements bodies::Body.

Definition at line 1183 of file bodies.cpp.

◆ computeBoundingCylinder()

void bodies::ConvexMesh::computeBoundingCylinder ( BoundingCylinder cylinder) const
overridevirtual

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

Implements bodies::Body.

Definition at line 1165 of file bodies.cpp.

◆ computeBoundingSphere()

void bodies::ConvexMesh::computeBoundingSphere ( BoundingSphere sphere) const
overridevirtual

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

Implements bodies::Body.

Definition at line 1159 of file bodies.cpp.

◆ computeScaledVerticesFromPlaneProjections()

void bodies::ConvexMesh::computeScaledVerticesFromPlaneProjections ( )

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

Definition at line 1021 of file bodies.cpp.

◆ computeVolume()

double bodies::ConvexMesh::computeVolume ( ) const
overridevirtual

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

Implements bodies::Body.

Definition at line 1222 of file bodies.cpp.

◆ containsPoint()

bool bodies::ConvexMesh::containsPoint ( const Eigen::Vector3d p,
bool  verbose = false 
) const
overridevirtual

Check if a point is inside the body. Surface points are included.

Implements bodies::Body.

Definition at line 794 of file bodies.cpp.

◆ correctVertexOrderFromPlanes()

void bodies::ConvexMesh::correctVertexOrderFromPlanes ( )

Definition at line 808 of file bodies.cpp.

◆ countVerticesBehindPlane()

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 1208 of file bodies.cpp.

◆ getDimensions()

std::vector< double > bodies::ConvexMesh::getDimensions ( ) const
overridevirtual

Returns an empty vector.

Implements bodies::Body.

Definition at line 1011 of file bodies.cpp.

◆ getPlanes()

const EigenSTL::vector_Vector4d & bodies::ConvexMesh::getPlanes ( ) const

Get the planes that define the convex shape.

Returns
A list of Vector4d(nx, ny, nz, d).

Definition at line 1141 of file bodies.cpp.

◆ getScaledDimensions()

std::vector< double > bodies::ConvexMesh::getScaledDimensions ( ) const
overridevirtual

Returns an empty vector.

Implements bodies::Body.

Definition at line 1016 of file bodies.cpp.

◆ getScaledVertices()

const EigenSTL::vector_Vector3d & bodies::ConvexMesh::getScaledVertices ( ) const

Definition at line 1136 of file bodies.cpp.

◆ getTriangles()

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

Definition at line 1124 of file bodies.cpp.

◆ getVertices()

const EigenSTL::vector_Vector3d & bodies::ConvexMesh::getVertices ( ) const

Definition at line 1130 of file bodies.cpp.

◆ intersectsRay()

bool bodies::ConvexMesh::intersectsRay ( const Eigen::Vector3d origin,
const Eigen::Vector3d dir,
EigenSTL::vector_Vector3d intersections = nullptr,
unsigned int  count = 0 
) const
overridevirtual

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. Passing dir as a unit vector will result in faster computation.

Implements bodies::Body.

Definition at line 1237 of file bodies.cpp.

◆ isPointInsidePlanes()

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

Check if the point is inside all halfspaces this mesh consists of (mesh_data_->planes_).

Note
The point is expected to have pose_ "cancelled" (have inverse pose of this mesh applied to it).
Scale and padding of the mesh are taken into account.
There is a 1e-9 margin "outside" the planes where points are still considered to be inside.

Definition at line 1188 of file bodies.cpp.

◆ updateInternalData()

void bodies::ConvexMesh::updateInternalData ( )
overridevirtual

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 1085 of file bodies.cpp.

◆ useDimensions()

void bodies::ConvexMesh::useDimensions ( const shapes::Shape shape)
overrideprotectedvirtual

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

Implements bodies::Body.

Definition at line 831 of file bodies.cpp.

Member Data Documentation

◆ bounding_box_

Box bodies::ConvexMesh::bounding_box_
protected

Definition at line 583 of file bodies.h.

◆ center_

Eigen::Vector3d bodies::ConvexMesh::center_
protected

Definition at line 580 of file bodies.h.

◆ i_pose_

Eigen::Isometry3d bodies::ConvexMesh::i_pose_
protected

Definition at line 579 of file bodies.h.

◆ mesh_data_

std::shared_ptr<MeshData> bodies::ConvexMesh::mesh_data_
protected

Definition at line 573 of file bodies.h.

◆ radiusB_

double bodies::ConvexMesh::radiusB_
protected

Definition at line 581 of file bodies.h.

◆ radiusBSqr_

double bodies::ConvexMesh::radiusBSqr_
protected

Definition at line 582 of file bodies.h.

◆ scaled_vertices_

EigenSTL::vector_Vector3d* bodies::ConvexMesh::scaled_vertices_
protected

Definition at line 589 of file bodies.h.

◆ scaled_vertices_storage_

std::unique_ptr<EigenSTL::vector_Vector3d> bodies::ConvexMesh::scaled_vertices_storage_
private

Definition at line 592 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 Sun Oct 1 2023 02:40:16