Public Types | Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes | Friends | List of all members
fcl::Convex< S_ > Class Template Reference

A convex polytope. More...

#include <convex.h>

Inheritance diagram for fcl::Convex< S_ >:
Inheritance graph
[legend]

Public Types

using S = S_
 
- Public Types inherited from fcl::ShapeBase< S_ >
using S = S_
 

Public Member Functions

Vector3< ScomputeCOM () const override
 
void computeLocalAABB () override
 Computes AABB in the geometry's canonical frame. More...
 
Matrix3< ScomputeMomentofInertia () const override
 
S computeVolume () const override
 
 Convex (const Convex &other)
 Copy constructor. More...
 
 Convex (const std::shared_ptr< const std::vector< Vector3< S >>> &vertices, int num_faces, const std::shared_ptr< const std::vector< int >> &faces, bool throw_if_invalid=false)
 Constructor. More...
 
const Vector3< S > & findExtremeVertex (const Vector3< S > &v_C) const
 Reports a vertex in this convex polytope that lies farthest in the given direction v_C. The direction vector must be expressed in the same frame C as the vertices of this Convex polytope. More...
 
std::vector< Vector3< S > > getBoundVertices (const Transform3< S > &tf) const
 Gets the vertices of some convex shape which can bound this shape in a specific configuration. More...
 
int getFaceCount () const
 Gets the total number of faces in the convex mesh. More...
 
const std::vector< int > & getFaces () const
 Gets the representation of the faces of the convex hull. More...
 
const Vector3< S > & getInteriorPoint () const
 A point guaranteed to be on the interior of the convex polytope, used for collision. More...
 
NODE_TYPE getNodeType () const override
 Gets node type: a convex polytope. More...
 
const std::vector< Vector3< S > > & getVertices () const
 Gets the vertex positions in the geometry's frame G. More...
 
std::string representation (int precision=20) const
 Create a string that should be sufficient to recreate this shape. This is akin to the repr() implementation in python. More...
 
 ~Convex ()=default
 
- Public Member Functions inherited from fcl::ShapeBase< S_ >
OBJECT_TYPE getObjectType () const
 Get object type: a geometric shape. More...
 
 ShapeBase ()
 
- Public Member Functions inherited from fcl::CollisionGeometry< S_ >
 CollisionGeometry ()
 
virtual Vector3< S_ > computeCOM () const
 compute center of mass More...
 
virtual Matrix3< S_ > computeMomentofInertia () const
 compute the inertia matrix, related to the origin More...
 
virtual Matrix3< S_ > computeMomentofInertiaRelatedToCOM () const
 compute the inertia matrix, related to the com More...
 
virtual S_ computeVolume () const
 compute the volume More...
 
virtual NODE_TYPE getNodeType () const
 get the node type More...
 
virtual OBJECT_TYPE getObjectType () const
 get the type of the object More...
 
void * getUserData () const
 get user data in geometry More...
 
bool isFree () const
 whether the object is completely free More...
 
bool isOccupied () const
 whether the object is completely occupied More...
 
bool isUncertain () const
 whether the object has some uncertainty More...
 
void setUserData (void *data)
 set user data in geometry More...
 
virtual ~CollisionGeometry ()
 

Private Member Functions

void FindVertexNeighbors ()
 
void ValidateMesh (bool throw_on_error)
 
void ValidateTopology (bool throw_on_error)
 

Private Attributes

const std::shared_ptr< const std::vector< int > > faces_
 
bool find_extreme_via_neighbors_ {false}
 
Vector3< Sinterior_point_
 
std::vector< int > neighbors_
 
const int num_faces_
 
const bool throw_if_invalid_ {}
 
const std::shared_ptr< const std::vector< Vector3< S > > > vertices_
 

Static Private Attributes

static constexpr int kMinVertCountForEdgeWalking = 32
 

Friends

class ConvexTester
 
std::ostream & operator<< (std::ostream &out, const Convex &convex)
 

Additional Inherited Members

- Public Attributes inherited from fcl::CollisionGeometry< S_ >
Vector3< S_ > aabb_center
 AABB center in local coordinate. More...
 
AABB< S_ > aabb_local
 AABB in local coordinate, used for tight AABB when only translation transform. More...
 
S_ aabb_radius
 AABB radius. More...
 
S_ cost_density
 collision cost for unit volume More...
 
S_ threshold_free
 threshold for free (<= is free) More...
 
S_ threshold_occupied
 threshold for occupied ( >= is occupied) More...
 
void * user_data
 pointer to user defined data specific to this object More...
 

Detailed Description

template<typename S_>
class fcl::Convex< S_ >

A convex polytope.

The Convex class represents a subset of general meshes: convex meshes. The class represents its underlying mesh quite simply: an ordered list of vertices, V = [v₀, v₁, ..., vₙ₋₁], and an ordered list of faces, F = [f₀, f₁, ..., fₘ₋₁], built on those vertices (via vertex indices).

A mesh is only compatible with Convex if it satisfies the following properties:

If those requirements are satisfied, for a given convex region, the mesh with the smallest number of faces may have non-triangular faces. In fact, they could be polygons with an arbitrary number of edges/vertices. The Convex class supports compact representation. But it also supports representations that decompose a large n-gon into a set of smaller polygons or triangles. In this case, each of the triangles supporting planes would be the same and the requirements listed above would still be satisfied.

Template Parameters
S_The scalar type; must be a valid Eigen scalar.

Definition at line 84 of file convex.h.

Member Typedef Documentation

◆ S

template<typename S_ >
using fcl::Convex< S_ >::S = S_

Definition at line 88 of file convex.h.

Constructor & Destructor Documentation

◆ Convex() [1/2]

template<typename S >
fcl::Convex< S >::Convex ( const std::shared_ptr< const std::vector< Vector3< S >>> &  vertices,
int  num_faces,
const std::shared_ptr< const std::vector< int >> &  faces,
bool  throw_if_invalid = false 
)

Constructor.

Note
: The Convex geometry assumes that the input data vertices and faces do not change through the life of the object.
Warning
: The Convex class only partially validates the input; it generally trusts that the inputs truly represent a coherent convex polytope. For those aspects that are validated, the constructor will throw for failed tests if throw_if_invalid is set to true.
Parameters
verticesThe positions of the polytope vertices.
num_facesThe number of faces defined in faces.
facesEncoding of the polytope faces. Must encode num_faces number of faces. See member documentation for details on encoding.
throw_if_invalidIf true, failed attempts to validate the mesh will throw an exception.

Definition at line 60 of file convex-inl.h.

◆ Convex() [2/2]

template<typename S >
fcl::Convex< S >::Convex ( const Convex< S_ > &  other)
default

Copy constructor.

◆ ~Convex()

template<typename S_ >
fcl::Convex< S_ >::~Convex ( )
default

Member Function Documentation

◆ computeCOM()

template<typename S >
Vector3< S > fcl::Convex< S >::computeCOM
override

Definition at line 166 of file convex-inl.h.

◆ computeLocalAABB()

template<typename S >
void fcl::Convex< S >::computeLocalAABB
overridevirtual

Computes AABB in the geometry's canonical frame.

Implements fcl::CollisionGeometry< S_ >.

Definition at line 86 of file convex-inl.h.

◆ computeMomentofInertia()

template<typename S >
Matrix3< S > fcl::Convex< S >::computeMomentofInertia
override

Definition at line 111 of file convex-inl.h.

◆ computeVolume()

template<typename S >
S fcl::Convex< S >::computeVolume
override

Definition at line 205 of file convex-inl.h.

◆ findExtremeVertex()

template<typename S >
const Vector3< S > & fcl::Convex< S >::findExtremeVertex ( const Vector3< S > &  v_C) const

Reports a vertex in this convex polytope that lies farthest in the given direction v_C. The direction vector must be expressed in the same frame C as the vertices of this Convex polytope.

Return values
p_CEthe position vector from Frame C's origin to the extreme vertex E. It is guaranteed that v_C⋅p_CE ≥ v_C⋅p_CF for all F ≠ E in the Convex polytope's set of vertices.

Definition at line 266 of file convex-inl.h.

◆ FindVertexNeighbors()

template<typename S >
void fcl::Convex< S >::FindVertexNeighbors
private

Definition at line 440 of file convex-inl.h.

◆ getBoundVertices()

template<typename S >
std::vector< Vector3< S > > fcl::Convex< S >::getBoundVertices ( const Transform3< S > &  tf) const

Gets the vertices of some convex shape which can bound this shape in a specific configuration.

Definition at line 252 of file convex-inl.h.

◆ getFaceCount()

template<typename S_ >
int fcl::Convex< S_ >::getFaceCount ( ) const
inline

Gets the total number of faces in the convex mesh.

Definition at line 129 of file convex.h.

◆ getFaces()

template<typename S_ >
const std::vector<int>& fcl::Convex< S_ >::getFaces ( ) const
inline

Gets the representation of the faces of the convex hull.

The array is the concatenation of an integer-based representations of each face. A single face is encoded as a sub-array of ints where the first int is the number n of vertices in the face, and the following n values are ordered indices into vertices which visit the vertex values in a counter-clockwise order (viewed from the outside).

For a well-formed face f consisting of indices [i₀, i₁, ..., iₘ₋₁], it should be the case that:

eⱼ × eⱼ₊₁ · n̂ₚ = |eⱼ × eⱼ₊₁|, ∀ 0 ≤ j < m, j ∈ ℤ, where n̂ₚ is the normal for plane π on which face f lies. eⱼ = vertices[iⱼ] - vertices[iⱼ₋₁] is the edge vector of face f defined by adjacent vertex indices at jᵗʰ vertex (wrapping around such that j - 1 = m - 1 for j = 0).

Satisfying this condition implies the following:

  1. vertices are not coincident and
  2. the indices of the face correspond to a proper counter-clockwise ordering.

Definition at line 152 of file convex.h.

◆ getInteriorPoint()

template<typename S_ >
const Vector3<S>& fcl::Convex< S_ >::getInteriorPoint ( ) const
inline

A point guaranteed to be on the interior of the convex polytope, used for collision.

Definition at line 156 of file convex.h.

◆ getNodeType()

template<typename S >
NODE_TYPE fcl::Convex< S >::getNodeType
override

Gets node type: a convex polytope.

Definition at line 100 of file convex-inl.h.

◆ getVertices()

template<typename S_ >
const std::vector<Vector3<S> >& fcl::Convex< S_ >::getVertices ( ) const
inline

Gets the vertex positions in the geometry's frame G.

Definition at line 126 of file convex.h.

◆ representation()

template<typename S >
std::string fcl::Convex< S >::representation ( int  precision = 20) const

Create a string that should be sufficient to recreate this shape. This is akin to the repr() implementation in python.

Parameters
precisionThe requested digits of precision for the numerical measures (same semantics as std::setprecision()).
Returns
The string representation of this instance.

Definition at line 318 of file convex-inl.h.

◆ ValidateMesh()

template<typename S >
void fcl::Convex< S >::ValidateMesh ( bool  throw_on_error)
private

Definition at line 352 of file convex-inl.h.

◆ ValidateTopology()

template<typename S >
void fcl::Convex< S >::ValidateTopology ( bool  throw_on_error)
private

Definition at line 360 of file convex-inl.h.

Friends And Related Function Documentation

◆ ConvexTester

template<typename S_ >
friend class ConvexTester
friend

Definition at line 195 of file convex.h.

◆ operator<<

template<typename S_ >
std::ostream& operator<< ( std::ostream &  out,
const Convex< S_ > &  convex 
)
friend

Definition at line 187 of file convex.h.

Member Data Documentation

◆ faces_

template<typename S_ >
const std::shared_ptr<const std::vector<int> > fcl::Convex< S_ >::faces_
private

Definition at line 235 of file convex.h.

◆ find_extreme_via_neighbors_

template<typename S_ >
bool fcl::Convex< S_ >::find_extreme_via_neighbors_ {false}
private

Definition at line 267 of file convex.h.

◆ interior_point_

template<typename S_ >
Vector3<S> fcl::Convex< S_ >::interior_point_
private

Definition at line 238 of file convex.h.

◆ kMinVertCountForEdgeWalking

template<typename S_ >
constexpr int fcl::Convex< S_ >::kMinVertCountForEdgeWalking = 32
staticconstexprprivate

Definition at line 272 of file convex.h.

◆ neighbors_

template<typename S_ >
std::vector<int> fcl::Convex< S_ >::neighbors_
private

Definition at line 263 of file convex.h.

◆ num_faces_

template<typename S_ >
const int fcl::Convex< S_ >::num_faces_
private

Definition at line 234 of file convex.h.

◆ throw_if_invalid_

template<typename S_ >
const bool fcl::Convex< S_ >::throw_if_invalid_ {}
private

Definition at line 237 of file convex.h.

◆ vertices_

template<typename S_ >
const std::shared_ptr<const std::vector<Vector3<S> > > fcl::Convex< S_ >::vertices_
private

Definition at line 233 of file convex.h.


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


fcl
Author(s):
autogenerated on Tue Dec 5 2023 03:40:50