Classes | Functions | Variables
Geometric shapes

Classes

class  hpp::fcl::Box
 Center at zero point, axis aligned box. More...
 
class  hpp::fcl::Capsule
 Capsule It is $ { x~\in~\mathbb{R}^3, d(x, AB) \leq radius } $ where $ d(x, AB) $ is the distance between the point x and the capsule segment AB, with $ A = (0,0,-halfLength), B = (0,0,halfLength) $. More...
 
class  hpp::fcl::Cone
 Cone The base of the cone is at $ z = - halfLength $ and the top is at $ z = halfLength $. More...
 
class  hpp::fcl::Convex< PolygonT >
 Convex polytope. More...
 
class  hpp::fcl::ConvexBase
 Base for convex polytope. More...
 
class  hpp::fcl::Cylinder
 Cylinder along Z axis. The cylinder is defined at its centroid. More...
 
class  hpp::fcl::Ellipsoid
 Ellipsoid centered at point zero. More...
 
class  hpp::fcl::Halfspace
 Half Space: this is equivalent to the Plane in ODE. The separation plane is defined as n * x = d; Points in the negative side of the separation plane (i.e. {x | n * x < d}) are inside the half space and points in the positive side of the separation plane (i.e. {x | n * x > d}) are outside the half space. More...
 
struct  hpp::fcl::ConvexBase::Neighbors
 
class  hpp::fcl::Plane
 Infinite plane. More...
 
class  hpp::fcl::Sphere
 Center at zero point sphere. More...
 
class  hpp::fcl::TriangleP
 Triangle stores the points instead of only indices of points. More...
 

Functions

 hpp::fcl::Box::Box (FCL_REAL x, FCL_REAL y, FCL_REAL z)
 
 hpp::fcl::Box::Box (const Vec3f &side_)
 
 hpp::fcl::Box::Box (const Box &other)
 
 hpp::fcl::Box::Box ()
 Default constructor. More...
 
 hpp::fcl::Capsule::Capsule ()
 Default constructor. More...
 
 hpp::fcl::Capsule::Capsule (FCL_REAL radius_, FCL_REAL lz_)
 
 hpp::fcl::Capsule::Capsule (const Capsule &other)
 
virtual TrianglePhpp::fcl::TriangleP::clone () const
 Clone *this into a new TriangleP. More...
 
virtual Boxhpp::fcl::Box::clone () const
 Clone *this into a new Box. More...
 
virtual Spherehpp::fcl::Sphere::clone () const
 Clone *this into a new Sphere. More...
 
virtual Ellipsoidhpp::fcl::Ellipsoid::clone () const
 Clone *this into a new Ellipsoid. More...
 
virtual Capsulehpp::fcl::Capsule::clone () const
 Clone *this into a new Capsule. More...
 
virtual Conehpp::fcl::Cone::clone () const
 Clone *this into a new Cone. More...
 
virtual Cylinderhpp::fcl::Cylinder::clone () const
 Clone *this into a new Cylinder. More...
 
virtual ConvexBasehpp::fcl::ConvexBase::clone () const
  . More...
 
virtual Halfspacehpp::fcl::Halfspace::clone () const
 Clone *this into a new Halfspace. More...
 
virtual Planehpp::fcl::Plane::clone () const
 Clone *this into a new Plane. More...
 
void hpp::fcl::ConvexBase::computeCenter ()
 
Vec3f hpp::fcl::Cone::computeCOM () const
 compute center of mass More...
 
void hpp::fcl::TriangleP::computeLocalAABB ()
 virtual function of compute AABB in local coordinate More...
 
void hpp::fcl::Box::computeLocalAABB ()
 Compute AABB. More...
 
void hpp::fcl::Sphere::computeLocalAABB ()
 Compute AABB. More...
 
void hpp::fcl::Ellipsoid::computeLocalAABB ()
 Compute AABB. More...
 
void hpp::fcl::Capsule::computeLocalAABB ()
 Compute AABB. More...
 
void hpp::fcl::Cone::computeLocalAABB ()
 Compute AABB. More...
 
void hpp::fcl::Cylinder::computeLocalAABB ()
 Compute AABB. More...
 
void hpp::fcl::ConvexBase::computeLocalAABB ()
 Compute AABB. More...
 
void hpp::fcl::Halfspace::computeLocalAABB ()
 Compute AABB. More...
 
void hpp::fcl::Plane::computeLocalAABB ()
 Compute AABB. More...
 
Matrix3f hpp::fcl::Box::computeMomentofInertia () const
 compute the inertia matrix, related to the origin More...
 
Matrix3f hpp::fcl::Sphere::computeMomentofInertia () const
 compute the inertia matrix, related to the origin More...
 
Matrix3f hpp::fcl::Ellipsoid::computeMomentofInertia () const
 compute the inertia matrix, related to the origin More...
 
Matrix3f hpp::fcl::Capsule::computeMomentofInertia () const
 compute the inertia matrix, related to the origin More...
 
Matrix3f hpp::fcl::Cone::computeMomentofInertia () const
 compute the inertia matrix, related to the origin More...
 
Matrix3f hpp::fcl::Cylinder::computeMomentofInertia () const
 compute the inertia matrix, related to the origin More...
 
FCL_REAL hpp::fcl::Box::computeVolume () const
 compute the volume More...
 
FCL_REAL hpp::fcl::Sphere::computeVolume () const
 compute the volume More...
 
FCL_REAL hpp::fcl::Ellipsoid::computeVolume () const
 compute the volume More...
 
FCL_REAL hpp::fcl::Capsule::computeVolume () const
 compute the volume More...
 
FCL_REAL hpp::fcl::Cone::computeVolume () const
 compute the volume More...
 
FCL_REAL hpp::fcl::Cylinder::computeVolume () const
 compute the volume More...
 
 hpp::fcl::Cone::Cone ()
 Default constructor. More...
 
 hpp::fcl::Cone::Cone (FCL_REAL radius_, FCL_REAL lz_)
 
 hpp::fcl::Cone::Cone (const Cone &other)
 
 hpp::fcl::ConvexBase::ConvexBase ()
 Construct an uninitialized convex object Initialization is done with ConvexBase::initialize. More...
 
 hpp::fcl::ConvexBase::ConvexBase (const ConvexBase &other)
 Copy constructor Only the list of neighbors is copied. More...
 
static ConvexBasehpp::fcl::ConvexBase::convexHull (const Vec3f *points, unsigned int num_points, bool keepTriangles, const char *qhullCommand=NULL)
 Build a convex hull based on Qhull library and store the vertices and optionally the triangles. More...
 
unsigned char const & hpp::fcl::ConvexBase::Neighbors::count () const
 
 hpp::fcl::Cylinder::Cylinder ()
 Default constructor. More...
 
 hpp::fcl::Cylinder::Cylinder (FCL_REAL radius_, FCL_REAL lz_)
 
 hpp::fcl::Cylinder::Cylinder (const Cylinder &other)
 
FCL_REAL hpp::fcl::Halfspace::distance (const Vec3f &p) const
 
FCL_REAL hpp::fcl::Plane::distance (const Vec3f &p) const
 
 hpp::fcl::Ellipsoid::Ellipsoid ()
 Default constructor. More...
 
 hpp::fcl::Ellipsoid::Ellipsoid (FCL_REAL rx, FCL_REAL ry, FCL_REAL rz)
 
 hpp::fcl::Ellipsoid::Ellipsoid (const Vec3f &radii)
 
 hpp::fcl::Ellipsoid::Ellipsoid (const Ellipsoid &other)
 
NODE_TYPE hpp::fcl::TriangleP::getNodeType () const
 get the node type More...
 
NODE_TYPE hpp::fcl::Box::getNodeType () const
 Get node type: a box. More...
 
NODE_TYPE hpp::fcl::Sphere::getNodeType () const
 Get node type: a sphere. More...
 
NODE_TYPE hpp::fcl::Ellipsoid::getNodeType () const
 Get node type: an ellipsoid. More...
 
NODE_TYPE hpp::fcl::Capsule::getNodeType () const
 Get node type: a capsule. More...
 
NODE_TYPE hpp::fcl::Cone::getNodeType () const
 Get node type: a cone. More...
 
NODE_TYPE hpp::fcl::Cylinder::getNodeType () const
 Get node type: a cylinder. More...
 
NODE_TYPE hpp::fcl::ConvexBase::getNodeType () const
 Get node type: a conex polytope. More...
 
NODE_TYPE hpp::fcl::Halfspace::getNodeType () const
 Get node type: a half space. More...
 
NODE_TYPE hpp::fcl::Plane::getNodeType () const
 Get node type: a plane. More...
 
OBJECT_TYPE hpp::fcl::ShapeBase::getObjectType () const
 Get object type: a geometric shape. More...
 
 hpp::fcl::Halfspace::Halfspace (const Vec3f &n_, FCL_REAL d_)
 Construct a half space with normal direction and offset. More...
 
 hpp::fcl::Halfspace::Halfspace (FCL_REAL a, FCL_REAL b, FCL_REAL c, FCL_REAL d_)
 Construct a plane with normal direction and offset. More...
 
 hpp::fcl::Halfspace::Halfspace ()
 
 hpp::fcl::Halfspace::Halfspace (const Halfspace &other)
 
std::pair< Box, Transform3fhpp::fcl::Box::inflated (const FCL_REAL value) const
 Inflate the box by an amount given by value. More...
 
std::pair< Sphere, Transform3fhpp::fcl::Sphere::inflated (const FCL_REAL value) const
 Inflate the sphere by an amount given by value. More...
 
std::pair< Ellipsoid, Transform3fhpp::fcl::Ellipsoid::inflated (const FCL_REAL value) const
 Inflate the ellipsoid by an amount given by value. More...
 
std::pair< Capsule, Transform3fhpp::fcl::Capsule::inflated (const FCL_REAL value) const
 Inflate the capsule by an amount given by value. More...
 
std::pair< Cone, Transform3fhpp::fcl::Cone::inflated (const FCL_REAL value) const
 Inflate the cone by an amount given by value. More...
 
std::pair< Cylinder, Transform3fhpp::fcl::Cylinder::inflated (const FCL_REAL value) const
 Inflate the cylinder by an amount given by value. More...
 
std::pair< Halfspace, Transform3fhpp::fcl::Halfspace::inflated (const FCL_REAL value) const
 Inflate the cylinder by an amount given by value. More...
 
void hpp::fcl::ConvexBase::initialize (bool ownStorage, Vec3f *points_, unsigned int num_points_)
 Initialize the points of the convex shape This also initializes the ConvexBase::center. More...
 
virtual bool hpp::fcl::TriangleP::isEqual (const CollisionGeometry &_other) const
 equal operator with another object of derived type. More...
 
virtual bool hpp::fcl::Box::isEqual (const CollisionGeometry &_other) const
 equal operator with another object of derived type. More...
 
virtual bool hpp::fcl::Sphere::isEqual (const CollisionGeometry &_other) const
 equal operator with another object of derived type. More...
 
virtual bool hpp::fcl::Ellipsoid::isEqual (const CollisionGeometry &_other) const
 equal operator with another object of derived type. More...
 
virtual bool hpp::fcl::Capsule::isEqual (const CollisionGeometry &_other) const
 equal operator with another object of derived type. More...
 
virtual bool hpp::fcl::Cone::isEqual (const CollisionGeometry &_other) const
 equal operator with another object of derived type. More...
 
virtual bool hpp::fcl::Cylinder::isEqual (const CollisionGeometry &_other) const
 equal operator with another object of derived type. More...
 
virtual bool hpp::fcl::ConvexBase::isEqual (const CollisionGeometry &_other) const
 equal operator with another object of derived type. More...
 
virtual bool hpp::fcl::Halfspace::isEqual (const CollisionGeometry &_other) const
 equal operator with another object of derived type. More...
 
virtual bool hpp::fcl::Plane::isEqual (const CollisionGeometry &_other) const
 equal operator with another object of derived type. More...
 
FCL_REAL hpp::fcl::Box::minInflationValue () const
 
FCL_REAL hpp::fcl::Sphere::minInflationValue () const
 
FCL_REAL hpp::fcl::Ellipsoid::minInflationValue () const
 
FCL_REAL hpp::fcl::Capsule::minInflationValue () const
 
FCL_REAL hpp::fcl::Cone::minInflationValue () const
 
FCL_REAL hpp::fcl::Cylinder::minInflationValue () const
 
FCL_REAL hpp::fcl::Halfspace::minInflationValue () const
 
bool hpp::fcl::ConvexBase::Neighbors::operator!= (const Neighbors &other) const
 
ShapeBasehpp::fcl::ShapeBase::operator= (const ShapeBase &other)=default
 
Boxhpp::fcl::Box::operator= (const Box &other)
 
Cylinderhpp::fcl::Cylinder::operator= (const Cylinder &other)
 
Halfspacehpp::fcl::Halfspace::operator= (const Halfspace &other)
 operator = More...
 
Planehpp::fcl::Plane::operator= (const Plane &other)
 operator = More...
 
bool hpp::fcl::ConvexBase::Neighbors::operator== (const Neighbors &other) const
 
unsigned int & hpp::fcl::ConvexBase::Neighbors::operator[] (int i)
 
unsigned int const & hpp::fcl::ConvexBase::Neighbors::operator[] (int i) const
 
 hpp::fcl::Plane::Plane (const Vec3f &n_, FCL_REAL d_)
 Construct a plane with normal direction and offset. More...
 
 hpp::fcl::Plane::Plane (FCL_REAL a, FCL_REAL b, FCL_REAL c, FCL_REAL d_)
 Construct a plane with normal direction and offset. More...
 
 hpp::fcl::Plane::Plane ()
 
 hpp::fcl::Plane::Plane (const Plane &other)
 
void hpp::fcl::ConvexBase::set (bool ownStorage, Vec3f *points_, unsigned int num_points_)
 Set the points of the convex shape. More...
 
 hpp::fcl::ShapeBase::ShapeBase ()
 
 hpp::fcl::ShapeBase::ShapeBase (const ShapeBase &other)
  . More...
 
FCL_REAL hpp::fcl::Halfspace::signedDistance (const Vec3f &p) const
 
FCL_REAL hpp::fcl::Plane::signedDistance (const Vec3f &p) const
 
 hpp::fcl::Sphere::Sphere ()
 Default constructor. More...
 
 hpp::fcl::Sphere::Sphere (FCL_REAL radius_)
 
 hpp::fcl::Sphere::Sphere (const Sphere &other)
 
 hpp::fcl::TriangleP::TriangleP ()
 
 hpp::fcl::TriangleP::TriangleP (const Vec3f &a_, const Vec3f &b_, const Vec3f &c_)
 
 hpp::fcl::TriangleP::TriangleP (const TriangleP &other)
 
void hpp::fcl::Halfspace::unitNormalTest ()
 Turn non-unit normal into unit. More...
 
void hpp::fcl::Plane::unitNormalTest ()
 Turn non-unit normal into unit. More...
 
virtual hpp::fcl::ConvexBase::~ConvexBase ()
 
virtual hpp::fcl::ShapeBase::~ShapeBase ()
 

Variables

Vec3f hpp::fcl::TriangleP::a
 
Vec3f hpp::fcl::TriangleP::b
 
Vec3f hpp::fcl::TriangleP::c
 
Vec3f hpp::fcl::ConvexBase::center
 center of the convex polytope, this is used for collision: center is guaranteed in the internal of the polytope (as it is convex) More...
 
unsigned char hpp::fcl::ConvexBase::Neighbors::count_
 
FCL_REAL hpp::fcl::Halfspace::d
 Plane offset. More...
 
FCL_REAL hpp::fcl::Plane::d
 Plane offset. More...
 
FCL_REAL hpp::fcl::Capsule::halfLength
 Half Length along z axis. More...
 
FCL_REAL hpp::fcl::Cone::halfLength
 Half Length along z axis. More...
 
FCL_REAL hpp::fcl::Cylinder::halfLength
 Half Length along z axis. More...
 
Vec3f hpp::fcl::Box::halfSide
 box side half-length More...
 
Vec3f hpp::fcl::Halfspace::n
 Plane normal. More...
 
Vec3f hpp::fcl::Plane::n
 Plane normal. More...
 
unsigned int * hpp::fcl::ConvexBase::Neighbors::n_
 
Neighborshpp::fcl::ConvexBase::neighbors
 
unsigned int * hpp::fcl::ConvexBase::nneighbors_
 
unsigned int hpp::fcl::ConvexBase::num_points
 
bool hpp::fcl::ConvexBase::own_storage_
 
Vec3fhpp::fcl::ConvexBase::points
 An array of the points of the polygon. More...
 
Vec3f hpp::fcl::Ellipsoid::radii
 Radii of the Ellipsoid (such that on boundary: x^2/rx^2 + y^2/ry^2. More...
 
FCL_REAL hpp::fcl::Sphere::radius
 Radius of the sphere. More...
 
FCL_REAL hpp::fcl::Capsule::radius
 Radius of capsule. More...
 
FCL_REAL hpp::fcl::Cone::radius
 Radius of the cone. More...
 
FCL_REAL hpp::fcl::Cylinder::radius
 Radius of the cylinder. More...
 

Detailed Description

Classes of different types of geometric shapes.

Function Documentation

◆ Box() [1/4]

hpp::fcl::Box::Box ( FCL_REAL  x,
FCL_REAL  y,
FCL_REAL  z 
)
inline

Definition at line 127 of file shape/geometric_shapes.h.

◆ Box() [2/4]

hpp::fcl::Box::Box ( const Vec3f side_)
inline

Definition at line 130 of file shape/geometric_shapes.h.

◆ Box() [3/4]

hpp::fcl::Box::Box ( const Box other)
inline

Definition at line 132 of file shape/geometric_shapes.h.

◆ Box() [4/4]

hpp::fcl::Box::Box ( )
inline

Default constructor.

Definition at line 145 of file shape/geometric_shapes.h.

◆ Capsule() [1/3]

hpp::fcl::Capsule::Capsule ( )
inline

Default constructor.

Definition at line 336 of file shape/geometric_shapes.h.

◆ Capsule() [2/3]

hpp::fcl::Capsule::Capsule ( FCL_REAL  radius_,
FCL_REAL  lz_ 
)
inline

Definition at line 338 of file shape/geometric_shapes.h.

◆ Capsule() [3/3]

hpp::fcl::Capsule::Capsule ( const Capsule other)
inline

Definition at line 342 of file shape/geometric_shapes.h.

◆ clone() [1/10]

virtual TriangleP* hpp::fcl::TriangleP::clone ( ) const
inlinevirtual

Clone *this into a new TriangleP.

Implements hpp::fcl::CollisionGeometry.

Definition at line 82 of file shape/geometric_shapes.h.

◆ clone() [2/10]

virtual Box* hpp::fcl::Box::clone ( ) const
inlinevirtual

Clone *this into a new Box.

Implements hpp::fcl::CollisionGeometry.

Definition at line 142 of file shape/geometric_shapes.h.

◆ clone() [3/10]

virtual Sphere* hpp::fcl::Sphere::clone ( ) const
inlinevirtual

Clone *this into a new Sphere.

Implements hpp::fcl::CollisionGeometry.

Definition at line 206 of file shape/geometric_shapes.h.

◆ clone() [4/10]

virtual Ellipsoid* hpp::fcl::Ellipsoid::clone ( ) const
inlinevirtual

Clone *this into a new Ellipsoid.

Implements hpp::fcl::CollisionGeometry.

Definition at line 271 of file shape/geometric_shapes.h.

◆ clone() [5/10]

virtual Capsule* hpp::fcl::Capsule::clone ( ) const
inlinevirtual

Clone *this into a new Capsule.

Implements hpp::fcl::CollisionGeometry.

Definition at line 346 of file shape/geometric_shapes.h.

◆ clone() [6/10]

virtual Cone* hpp::fcl::Cone::clone ( ) const
inlinevirtual

Clone *this into a new Cone.

Implements hpp::fcl::CollisionGeometry.

Definition at line 427 of file shape/geometric_shapes.h.

◆ clone() [7/10]

virtual Cylinder* hpp::fcl::Cylinder::clone ( ) const
inlinevirtual

Clone *this into a new Cylinder.

Implements hpp::fcl::CollisionGeometry.

Definition at line 522 of file shape/geometric_shapes.h.

◆ clone() [8/10]

virtual ConvexBase* hpp::fcl::ConvexBase::clone ( ) const
inlinevirtual

 .

Clone (deep copy).

Implements hpp::fcl::CollisionGeometry.

Reimplemented in hpp::fcl::Convex< PolygonT >.

Definition at line 602 of file shape/geometric_shapes.h.

◆ clone() [9/10]

virtual Halfspace* hpp::fcl::Halfspace::clone ( ) const
inlinevirtual

Clone *this into a new Halfspace.

Implements hpp::fcl::CollisionGeometry.

Definition at line 755 of file shape/geometric_shapes.h.

◆ clone() [10/10]

virtual Plane* hpp::fcl::Plane::clone ( ) const
inlinevirtual

Clone *this into a new Plane.

Implements hpp::fcl::CollisionGeometry.

Definition at line 835 of file shape/geometric_shapes.h.

◆ computeCenter()

void hpp::fcl::ConvexBase::computeCenter ( )
private

Definition at line 91 of file src/shape/geometric_shapes.cpp.

◆ computeCOM()

Vec3f hpp::fcl::Cone::computeCOM ( ) const
inlinevirtual

compute center of mass

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 455 of file shape/geometric_shapes.h.

◆ computeLocalAABB() [1/10]

void hpp::fcl::TriangleP::computeLocalAABB ( )
virtual

virtual function of compute AABB in local coordinate

Implements hpp::fcl::CollisionGeometry.

Definition at line 176 of file src/shape/geometric_shapes.cpp.

◆ computeLocalAABB() [2/10]

void hpp::fcl::Box::computeLocalAABB ( )
virtual

Compute AABB.

Implements hpp::fcl::CollisionGeometry.

Definition at line 122 of file src/shape/geometric_shapes.cpp.

◆ computeLocalAABB() [3/10]

void hpp::fcl::Sphere::computeLocalAABB ( )
virtual

Compute AABB.

Implements hpp::fcl::CollisionGeometry.

Definition at line 128 of file src/shape/geometric_shapes.cpp.

◆ computeLocalAABB() [4/10]

void hpp::fcl::Ellipsoid::computeLocalAABB ( )
virtual

Compute AABB.

Implements hpp::fcl::CollisionGeometry.

Definition at line 134 of file src/shape/geometric_shapes.cpp.

◆ computeLocalAABB() [5/10]

void hpp::fcl::Capsule::computeLocalAABB ( )
virtual

Compute AABB.

Implements hpp::fcl::CollisionGeometry.

Definition at line 140 of file src/shape/geometric_shapes.cpp.

◆ computeLocalAABB() [6/10]

void hpp::fcl::Cone::computeLocalAABB ( )
virtual

Compute AABB.

Implements hpp::fcl::CollisionGeometry.

Definition at line 146 of file src/shape/geometric_shapes.cpp.

◆ computeLocalAABB() [7/10]

void hpp::fcl::Cylinder::computeLocalAABB ( )
virtual

Compute AABB.

Implements hpp::fcl::CollisionGeometry.

Definition at line 152 of file src/shape/geometric_shapes.cpp.

◆ computeLocalAABB() [8/10]

void hpp::fcl::ConvexBase::computeLocalAABB ( )
virtual

Compute AABB.

Implements hpp::fcl::CollisionGeometry.

Definition at line 158 of file src/shape/geometric_shapes.cpp.

◆ computeLocalAABB() [9/10]

void hpp::fcl::Halfspace::computeLocalAABB ( )
virtual

Compute AABB.

Implements hpp::fcl::CollisionGeometry.

Definition at line 164 of file src/shape/geometric_shapes.cpp.

◆ computeLocalAABB() [10/10]

void hpp::fcl::Plane::computeLocalAABB ( )
virtual

Compute AABB.

Implements hpp::fcl::CollisionGeometry.

Definition at line 170 of file src/shape/geometric_shapes.cpp.

◆ computeMomentofInertia() [1/6]

Matrix3f hpp::fcl::Box::computeMomentofInertia ( ) const
inlinevirtual

compute the inertia matrix, related to the origin

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 158 of file shape/geometric_shapes.h.

◆ computeMomentofInertia() [2/6]

Matrix3f hpp::fcl::Sphere::computeMomentofInertia ( ) const
inlinevirtual

compute the inertia matrix, related to the origin

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 217 of file shape/geometric_shapes.h.

◆ computeMomentofInertia() [3/6]

Matrix3f hpp::fcl::Ellipsoid::computeMomentofInertia ( ) const
inlinevirtual

compute the inertia matrix, related to the origin

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 283 of file shape/geometric_shapes.h.

◆ computeMomentofInertia() [4/6]

Matrix3f hpp::fcl::Capsule::computeMomentofInertia ( ) const
inlinevirtual

compute the inertia matrix, related to the origin

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 365 of file shape/geometric_shapes.h.

◆ computeMomentofInertia() [5/6]

Matrix3f hpp::fcl::Cone::computeMomentofInertia ( ) const
inlinevirtual

compute the inertia matrix, related to the origin

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 446 of file shape/geometric_shapes.h.

◆ computeMomentofInertia() [6/6]

Matrix3f hpp::fcl::Cylinder::computeMomentofInertia ( ) const
inlinevirtual

compute the inertia matrix, related to the origin

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 541 of file shape/geometric_shapes.h.

◆ computeVolume() [1/6]

FCL_REAL hpp::fcl::Box::computeVolume ( ) const
inlinevirtual

compute the volume

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 156 of file shape/geometric_shapes.h.

◆ computeVolume() [2/6]

FCL_REAL hpp::fcl::Sphere::computeVolume ( ) const
inlinevirtual

compute the volume

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 222 of file shape/geometric_shapes.h.

◆ computeVolume() [3/6]

FCL_REAL hpp::fcl::Ellipsoid::computeVolume ( ) const
inlinevirtual

compute the volume

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 293 of file shape/geometric_shapes.h.

◆ computeVolume() [4/6]

FCL_REAL hpp::fcl::Capsule::computeVolume ( ) const
inlinevirtual

compute the volume

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 360 of file shape/geometric_shapes.h.

◆ computeVolume() [5/6]

FCL_REAL hpp::fcl::Cone::computeVolume ( ) const
inlinevirtual

compute the volume

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 441 of file shape/geometric_shapes.h.

◆ computeVolume() [6/6]

FCL_REAL hpp::fcl::Cylinder::computeVolume ( ) const
inlinevirtual

compute the volume

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 536 of file shape/geometric_shapes.h.

◆ Cone() [1/3]

hpp::fcl::Cone::Cone ( )
inline

Default constructor.

Definition at line 417 of file shape/geometric_shapes.h.

◆ Cone() [2/3]

hpp::fcl::Cone::Cone ( FCL_REAL  radius_,
FCL_REAL  lz_ 
)
inline

Definition at line 419 of file shape/geometric_shapes.h.

◆ Cone() [3/3]

hpp::fcl::Cone::Cone ( const Cone other)
inline

Definition at line 423 of file shape/geometric_shapes.h.

◆ ConvexBase() [1/2]

hpp::fcl::ConvexBase::ConvexBase ( )
inlineprotected

Construct an uninitialized convex object Initialization is done with ConvexBase::initialize.

Definition at line 664 of file shape/geometric_shapes.h.

◆ ConvexBase() [2/2]

hpp::fcl::ConvexBase::ConvexBase ( const ConvexBase other)
protected

Copy constructor Only the list of neighbors is copied.

Definition at line 58 of file src/shape/geometric_shapes.cpp.

◆ convexHull()

ConvexBase * hpp::fcl::ConvexBase::convexHull ( const Vec3f points,
unsigned int  num_points,
bool  keepTriangles,
const char *  qhullCommand = NULL 
)
static

Build a convex hull based on Qhull library and store the vertices and optionally the triangles.

Parameters
points,num_pointsthe points whose convex hull should be computed.
keepTrianglesif true, returns a Convex<Triangle> object which contains the triangle of the shape.
qhullCommandthe command sent to qhull.
  • if keepTriangles is true, this parameter should include "Qt". If NULL, "Qt" is passed to Qhull.
  • if keepTriangles is false, an empty string is passed to Qhull.
Note
hpp-fcl must have been compiled with option HPP_FCL_HAS_QHULL set to ON.

Definition at line 46 of file src/shape/convex.cpp.

◆ count()

unsigned char const& hpp::fcl::ConvexBase::Neighbors::count ( ) const
inline

Definition at line 630 of file shape/geometric_shapes.h.

◆ Cylinder() [1/3]

hpp::fcl::Cylinder::Cylinder ( )
inline

Default constructor.

Definition at line 504 of file shape/geometric_shapes.h.

◆ Cylinder() [2/3]

hpp::fcl::Cylinder::Cylinder ( FCL_REAL  radius_,
FCL_REAL  lz_ 
)
inline

Definition at line 506 of file shape/geometric_shapes.h.

◆ Cylinder() [3/3]

hpp::fcl::Cylinder::Cylinder ( const Cylinder other)
inline

Definition at line 510 of file shape/geometric_shapes.h.

◆ distance() [1/2]

FCL_REAL hpp::fcl::Halfspace::distance ( const Vec3f p) const
inline

Definition at line 759 of file shape/geometric_shapes.h.

◆ distance() [2/2]

FCL_REAL hpp::fcl::Plane::distance ( const Vec3f p) const
inline

Definition at line 839 of file shape/geometric_shapes.h.

◆ Ellipsoid() [1/4]

hpp::fcl::Ellipsoid::Ellipsoid ( )
inline

Default constructor.

Definition at line 261 of file shape/geometric_shapes.h.

◆ Ellipsoid() [2/4]

hpp::fcl::Ellipsoid::Ellipsoid ( FCL_REAL  rx,
FCL_REAL  ry,
FCL_REAL  rz 
)
inline

Definition at line 263 of file shape/geometric_shapes.h.

◆ Ellipsoid() [3/4]

hpp::fcl::Ellipsoid::Ellipsoid ( const Vec3f radii)
inlineexplicit

Definition at line 266 of file shape/geometric_shapes.h.

◆ Ellipsoid() [4/4]

hpp::fcl::Ellipsoid::Ellipsoid ( const Ellipsoid other)
inline

Definition at line 268 of file shape/geometric_shapes.h.

◆ getNodeType() [1/10]

NODE_TYPE hpp::fcl::TriangleP::getNodeType ( ) const
inlinevirtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 87 of file shape/geometric_shapes.h.

◆ getNodeType() [2/10]

NODE_TYPE hpp::fcl::Box::getNodeType ( ) const
inlinevirtual

Get node type: a box.

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 154 of file shape/geometric_shapes.h.

◆ getNodeType() [3/10]

NODE_TYPE hpp::fcl::Sphere::getNodeType ( ) const
inlinevirtual

Get node type: a sphere.

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 215 of file shape/geometric_shapes.h.

◆ getNodeType() [4/10]

NODE_TYPE hpp::fcl::Ellipsoid::getNodeType ( ) const
inlinevirtual

Get node type: an ellipsoid.

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 281 of file shape/geometric_shapes.h.

◆ getNodeType() [5/10]

NODE_TYPE hpp::fcl::Capsule::getNodeType ( ) const
inlinevirtual

Get node type: a capsule.

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 358 of file shape/geometric_shapes.h.

◆ getNodeType() [6/10]

NODE_TYPE hpp::fcl::Cone::getNodeType ( ) const
inlinevirtual

Get node type: a cone.

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 439 of file shape/geometric_shapes.h.

◆ getNodeType() [7/10]

NODE_TYPE hpp::fcl::Cylinder::getNodeType ( ) const
inlinevirtual

Get node type: a cylinder.

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 534 of file shape/geometric_shapes.h.

◆ getNodeType() [8/10]

NODE_TYPE hpp::fcl::ConvexBase::getNodeType ( ) const
inlinevirtual

Get node type: a conex polytope.

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 620 of file shape/geometric_shapes.h.

◆ getNodeType() [9/10]

NODE_TYPE hpp::fcl::Halfspace::getNodeType ( ) const
inlinevirtual

Get node type: a half space.

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 765 of file shape/geometric_shapes.h.

◆ getNodeType() [10/10]

NODE_TYPE hpp::fcl::Plane::getNodeType ( ) const
inlinevirtual

Get node type: a plane.

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 845 of file shape/geometric_shapes.h.

◆ getObjectType()

OBJECT_TYPE hpp::fcl::ShapeBase::getObjectType ( ) const
inlinevirtual

Get object type: a geometric shape.

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 63 of file shape/geometric_shapes.h.

◆ Halfspace() [1/4]

hpp::fcl::Halfspace::Halfspace ( const Vec3f n_,
FCL_REAL  d_ 
)
inline

Construct a half space with normal direction and offset.

Definition at line 732 of file shape/geometric_shapes.h.

◆ Halfspace() [2/4]

hpp::fcl::Halfspace::Halfspace ( FCL_REAL  a,
FCL_REAL  b,
FCL_REAL  c,
FCL_REAL  d_ 
)
inline

Construct a plane with normal direction and offset.

Definition at line 737 of file shape/geometric_shapes.h.

◆ Halfspace() [3/4]

hpp::fcl::Halfspace::Halfspace ( )
inline

Definition at line 742 of file shape/geometric_shapes.h.

◆ Halfspace() [4/4]

hpp::fcl::Halfspace::Halfspace ( const Halfspace other)
inline

Definition at line 744 of file shape/geometric_shapes.h.

◆ inflated() [1/7]

std::pair<Box, Transform3f> hpp::fcl::Box::inflated ( const FCL_REAL  value) const
inline

Inflate the box by an amount given by value.

Parameters
[in]valueof the shape inflation.
Returns
a new inflated box and the related transform to account for the change of shape frame

Definition at line 172 of file shape/geometric_shapes.h.

◆ inflated() [2/7]

std::pair<Sphere, Transform3f> hpp::fcl::Sphere::inflated ( const FCL_REAL  value) const
inline

Inflate the sphere by an amount given by value.

Parameters
[in]valueof the shape inflation.
Returns
a new inflated sphere and the related transform to account for the change of shape frame

Definition at line 235 of file shape/geometric_shapes.h.

◆ inflated() [3/7]

std::pair<Ellipsoid, Transform3f> hpp::fcl::Ellipsoid::inflated ( const FCL_REAL  value) const
inline

Inflate the ellipsoid by an amount given by value.

Parameters
[in]valueof the shape inflation.
Returns
a new inflated ellipsoid and the related transform to account for the change of shape frame

Definition at line 306 of file shape/geometric_shapes.h.

◆ inflated() [4/7]

std::pair<Capsule, Transform3f> hpp::fcl::Capsule::inflated ( const FCL_REAL  value) const
inline

Inflate the capsule by an amount given by value.

Parameters
[in]valueof the shape inflation.
Returns
a new inflated capsule and the related transform to account for the change of shape frame

Definition at line 388 of file shape/geometric_shapes.h.

◆ inflated() [5/7]

std::pair<Cone, Transform3f> hpp::fcl::Cone::inflated ( const FCL_REAL  value) const
inline

Inflate the cone by an amount given by value.

Parameters
[in]valueof the shape inflation.
Returns
a new inflated cone and the related transform to account for the change of shape frame

Definition at line 465 of file shape/geometric_shapes.h.

◆ inflated() [6/7]

std::pair<Cylinder, Transform3f> hpp::fcl::Cylinder::inflated ( const FCL_REAL  value) const
inline

Inflate the cylinder by an amount given by value.

Parameters
[in]valueof the shape inflation.
Returns
a new inflated cylinder and the related transform to account for the change of shape frame

Definition at line 556 of file shape/geometric_shapes.h.

◆ inflated() [7/7]

std::pair<Halfspace, Transform3f> hpp::fcl::Halfspace::inflated ( const FCL_REAL  value) const
inline

Inflate the cylinder by an amount given by value.

Parameters
[in]valueof the shape inflation.
Returns
a new inflated cylinder and the related transform to account for the change of shape frame

Definition at line 777 of file shape/geometric_shapes.h.

◆ initialize()

void hpp::fcl::ConvexBase::initialize ( bool  ownStorage,
Vec3f points_,
unsigned int  num_points_ 
)
protected

Initialize the points of the convex shape This also initializes the ConvexBase::center.

Parameters
ownStorageweither the ConvexBase owns the data.
points_list of 3D points ///
num_points_number of 3D points

Definition at line 44 of file src/shape/geometric_shapes.cpp.

◆ isEqual() [1/10]

virtual bool hpp::fcl::TriangleP::isEqual ( const CollisionGeometry other) const
inlineprivatevirtual

equal operator with another object of derived type.

Implements hpp::fcl::CollisionGeometry.

Definition at line 112 of file shape/geometric_shapes.h.

◆ isEqual() [2/10]

virtual bool hpp::fcl::Box::isEqual ( const CollisionGeometry other) const
inlineprivatevirtual

equal operator with another object of derived type.

Implements hpp::fcl::CollisionGeometry.

Definition at line 183 of file shape/geometric_shapes.h.

◆ isEqual() [3/10]

virtual bool hpp::fcl::Sphere::isEqual ( const CollisionGeometry other) const
inlineprivatevirtual

equal operator with another object of derived type.

Implements hpp::fcl::CollisionGeometry.

Definition at line 245 of file shape/geometric_shapes.h.

◆ isEqual() [4/10]

virtual bool hpp::fcl::Ellipsoid::isEqual ( const CollisionGeometry other) const
inlineprivatevirtual

equal operator with another object of derived type.

Implements hpp::fcl::CollisionGeometry.

Definition at line 317 of file shape/geometric_shapes.h.

◆ isEqual() [5/10]

virtual bool hpp::fcl::Capsule::isEqual ( const CollisionGeometry other) const
inlineprivatevirtual

equal operator with another object of derived type.

Implements hpp::fcl::CollisionGeometry.

Definition at line 399 of file shape/geometric_shapes.h.

◆ isEqual() [6/10]

virtual bool hpp::fcl::Cone::isEqual ( const CollisionGeometry other) const
inlineprivatevirtual

equal operator with another object of derived type.

Implements hpp::fcl::CollisionGeometry.

Definition at line 487 of file shape/geometric_shapes.h.

◆ isEqual() [7/10]

virtual bool hpp::fcl::Cylinder::isEqual ( const CollisionGeometry other) const
inlineprivatevirtual

equal operator with another object of derived type.

Implements hpp::fcl::CollisionGeometry.

Definition at line 567 of file shape/geometric_shapes.h.

◆ isEqual() [8/10]

virtual bool hpp::fcl::ConvexBase::isEqual ( const CollisionGeometry other) const
inlineprivatevirtual

equal operator with another object of derived type.

Implements hpp::fcl::CollisionGeometry.

Definition at line 699 of file shape/geometric_shapes.h.

◆ isEqual() [9/10]

virtual bool hpp::fcl::Halfspace::isEqual ( const CollisionGeometry other) const
inlineprivatevirtual

equal operator with another object of derived type.

Implements hpp::fcl::CollisionGeometry.

Definition at line 797 of file shape/geometric_shapes.h.

◆ isEqual() [10/10]

virtual bool hpp::fcl::Plane::isEqual ( const CollisionGeometry other) const
inlineprivatevirtual

equal operator with another object of derived type.

Implements hpp::fcl::CollisionGeometry.

Definition at line 858 of file shape/geometric_shapes.h.

◆ minInflationValue() [1/7]

FCL_REAL hpp::fcl::Box::minInflationValue ( ) const
inline

Definition at line 164 of file shape/geometric_shapes.h.

◆ minInflationValue() [2/7]

FCL_REAL hpp::fcl::Sphere::minInflationValue ( ) const
inline

Definition at line 227 of file shape/geometric_shapes.h.

◆ minInflationValue() [3/7]

FCL_REAL hpp::fcl::Ellipsoid::minInflationValue ( ) const
inline

Definition at line 298 of file shape/geometric_shapes.h.

◆ minInflationValue() [4/7]

FCL_REAL hpp::fcl::Capsule::minInflationValue ( ) const
inline

Definition at line 380 of file shape/geometric_shapes.h.

◆ minInflationValue() [5/7]

FCL_REAL hpp::fcl::Cone::minInflationValue ( ) const
inline

Definition at line 457 of file shape/geometric_shapes.h.

◆ minInflationValue() [6/7]

FCL_REAL hpp::fcl::Cylinder::minInflationValue ( ) const
inline

Definition at line 548 of file shape/geometric_shapes.h.

◆ minInflationValue() [7/7]

FCL_REAL hpp::fcl::Halfspace::minInflationValue ( ) const
inline

Definition at line 767 of file shape/geometric_shapes.h.

◆ operator!=()

bool hpp::fcl::ConvexBase::Neighbors::operator!= ( const Neighbors other) const
inline

Definition at line 650 of file shape/geometric_shapes.h.

◆ operator=() [1/5]

ShapeBase& hpp::fcl::ShapeBase::operator= ( const ShapeBase other)
default

◆ operator=() [2/5]

Box& hpp::fcl::Box::operator= ( const Box other)
inline

Definition at line 134 of file shape/geometric_shapes.h.

◆ operator=() [3/5]

Cylinder& hpp::fcl::Cylinder::operator= ( const Cylinder other)
inline

Definition at line 513 of file shape/geometric_shapes.h.

◆ operator=() [4/5]

Halfspace& hpp::fcl::Halfspace::operator= ( const Halfspace other)
inline

operator =

Definition at line 748 of file shape/geometric_shapes.h.

◆ operator=() [5/5]

Plane& hpp::fcl::Plane::operator= ( const Plane other)
inline

operator =

Definition at line 828 of file shape/geometric_shapes.h.

◆ operator==()

bool hpp::fcl::ConvexBase::Neighbors::operator== ( const Neighbors other) const
inline

Definition at line 640 of file shape/geometric_shapes.h.

◆ operator[]() [1/2]

unsigned int& hpp::fcl::ConvexBase::Neighbors::operator[] ( int  i)
inline

Definition at line 631 of file shape/geometric_shapes.h.

◆ operator[]() [2/2]

unsigned int const& hpp::fcl::ConvexBase::Neighbors::operator[] ( int  i) const
inline

Definition at line 635 of file shape/geometric_shapes.h.

◆ Plane() [1/4]

hpp::fcl::Plane::Plane ( const Vec3f n_,
FCL_REAL  d_ 
)
inline

Construct a plane with normal direction and offset.

Definition at line 813 of file shape/geometric_shapes.h.

◆ Plane() [2/4]

hpp::fcl::Plane::Plane ( FCL_REAL  a,
FCL_REAL  b,
FCL_REAL  c,
FCL_REAL  d_ 
)
inline

Construct a plane with normal direction and offset.

Definition at line 818 of file shape/geometric_shapes.h.

◆ Plane() [3/4]

hpp::fcl::Plane::Plane ( )
inline

Definition at line 823 of file shape/geometric_shapes.h.

◆ Plane() [4/4]

hpp::fcl::Plane::Plane ( const Plane other)
inline

Definition at line 825 of file shape/geometric_shapes.h.

◆ set()

void hpp::fcl::ConvexBase::set ( bool  ownStorage,
Vec3f points_,
unsigned int  num_points_ 
)
protected

Set the points of the convex shape.

Parameters
ownStorageweither the ConvexBase owns the data.
points_list of 3D points ///
num_points_number of 3D points

Definition at line 52 of file src/shape/geometric_shapes.cpp.

◆ ShapeBase() [1/2]

hpp::fcl::ShapeBase::ShapeBase ( )
inline

Definition at line 53 of file shape/geometric_shapes.h.

◆ ShapeBase() [2/2]

hpp::fcl::ShapeBase::ShapeBase ( const ShapeBase other)
inline

 .

Copy constructor

Definition at line 56 of file shape/geometric_shapes.h.

◆ signedDistance() [1/2]

FCL_REAL hpp::fcl::Halfspace::signedDistance ( const Vec3f p) const
inline

Definition at line 757 of file shape/geometric_shapes.h.

◆ signedDistance() [2/2]

FCL_REAL hpp::fcl::Plane::signedDistance ( const Vec3f p) const
inline

Definition at line 837 of file shape/geometric_shapes.h.

◆ Sphere() [1/3]

hpp::fcl::Sphere::Sphere ( )
inline

Default constructor.

Definition at line 199 of file shape/geometric_shapes.h.

◆ Sphere() [2/3]

hpp::fcl::Sphere::Sphere ( FCL_REAL  radius_)
inlineexplicit

Definition at line 201 of file shape/geometric_shapes.h.

◆ Sphere() [3/3]

hpp::fcl::Sphere::Sphere ( const Sphere other)
inline

Definition at line 203 of file shape/geometric_shapes.h.

◆ TriangleP() [1/3]

hpp::fcl::TriangleP::TriangleP ( )
inline

Definition at line 73 of file shape/geometric_shapes.h.

◆ TriangleP() [2/3]

hpp::fcl::TriangleP::TriangleP ( const Vec3f a_,
const Vec3f b_,
const Vec3f c_ 
)
inline

Definition at line 75 of file shape/geometric_shapes.h.

◆ TriangleP() [3/3]

hpp::fcl::TriangleP::TriangleP ( const TriangleP other)
inline

Definition at line 78 of file shape/geometric_shapes.h.

◆ unitNormalTest() [1/2]

void hpp::fcl::Halfspace::unitNormalTest ( )
protected

Turn non-unit normal into unit.

Definition at line 98 of file src/shape/geometric_shapes.cpp.

◆ unitNormalTest() [2/2]

void hpp::fcl::Plane::unitNormalTest ( )
protected

Turn non-unit normal into unit.

Definition at line 110 of file src/shape/geometric_shapes.cpp.

◆ ~ConvexBase()

hpp::fcl::ConvexBase::~ConvexBase ( )
virtual

Definition at line 85 of file src/shape/geometric_shapes.cpp.

◆ ~ShapeBase()

virtual hpp::fcl::ShapeBase::~ShapeBase ( )
inlinevirtual

Definition at line 60 of file shape/geometric_shapes.h.

Variable Documentation

◆ a

Vec3f hpp::fcl::TriangleP::a

Definition at line 109 of file shape/geometric_shapes.h.

◆ b

Vec3f hpp::fcl::TriangleP::b

Definition at line 109 of file shape/geometric_shapes.h.

◆ c

Vec3f hpp::fcl::TriangleP::c

Definition at line 109 of file shape/geometric_shapes.h.

◆ center

Vec3f hpp::fcl::ConvexBase::center

center of the convex polytope, this is used for collision: center is guaranteed in the internal of the polytope (as it is convex)

Definition at line 659 of file shape/geometric_shapes.h.

◆ count_

unsigned char hpp::fcl::ConvexBase::Neighbors::count_

Definition at line 627 of file shape/geometric_shapes.h.

◆ d [1/2]

FCL_REAL hpp::fcl::Halfspace::d

Plane offset.

Definition at line 790 of file shape/geometric_shapes.h.

◆ d [2/2]

FCL_REAL hpp::fcl::Plane::d

Plane offset.

Definition at line 851 of file shape/geometric_shapes.h.

◆ halfLength [1/3]

FCL_REAL hpp::fcl::Capsule::halfLength

Half Length along z axis.

Definition at line 352 of file shape/geometric_shapes.h.

◆ halfLength [2/3]

FCL_REAL hpp::fcl::Cone::halfLength

Half Length along z axis.

Definition at line 433 of file shape/geometric_shapes.h.

◆ halfLength [3/3]

FCL_REAL hpp::fcl::Cylinder::halfLength

Half Length along z axis.

Definition at line 528 of file shape/geometric_shapes.h.

◆ halfSide

Vec3f hpp::fcl::Box::halfSide

box side half-length

Definition at line 148 of file shape/geometric_shapes.h.

◆ n [1/2]

Vec3f hpp::fcl::Halfspace::n

Plane normal.

Definition at line 787 of file shape/geometric_shapes.h.

◆ n [2/2]

Vec3f hpp::fcl::Plane::n

Plane normal.

Definition at line 848 of file shape/geometric_shapes.h.

◆ n_

unsigned int* hpp::fcl::ConvexBase::Neighbors::n_

Definition at line 628 of file shape/geometric_shapes.h.

◆ neighbors

Neighbors* hpp::fcl::ConvexBase::neighbors

Neighbors of each vertex. It is an array of size num_points. For each vertex, it contains the number of neighbors and a list of indices to them.

Definition at line 655 of file shape/geometric_shapes.h.

◆ nneighbors_

unsigned int* hpp::fcl::ConvexBase::nneighbors_
protected

Definition at line 691 of file shape/geometric_shapes.h.

◆ num_points

unsigned int hpp::fcl::ConvexBase::num_points

Definition at line 624 of file shape/geometric_shapes.h.

◆ own_storage_

bool hpp::fcl::ConvexBase::own_storage_
protected

Definition at line 693 of file shape/geometric_shapes.h.

◆ points

Vec3f* hpp::fcl::ConvexBase::points

An array of the points of the polygon.

Definition at line 623 of file shape/geometric_shapes.h.

◆ radii

Vec3f hpp::fcl::Ellipsoid::radii

Radii of the Ellipsoid (such that on boundary: x^2/rx^2 + y^2/ry^2.

  • z^2/rz^2 = 1)

Definition at line 271 of file shape/geometric_shapes.h.

◆ radius [1/4]

FCL_REAL hpp::fcl::Sphere::radius

Radius of the sphere.

Definition at line 206 of file shape/geometric_shapes.h.

◆ radius [2/4]

FCL_REAL hpp::fcl::Capsule::radius

Radius of capsule.

Definition at line 346 of file shape/geometric_shapes.h.

◆ radius [3/4]

FCL_REAL hpp::fcl::Cone::radius

Radius of the cone.

Definition at line 427 of file shape/geometric_shapes.h.

◆ radius [4/4]

FCL_REAL hpp::fcl::Cylinder::radius

Radius of the cylinder.

Definition at line 522 of file shape/geometric_shapes.h.



hpp-fcl
Author(s):
autogenerated on Fri Jun 2 2023 02:39:02