Classes | Functions | Variables
Geometric shapes

Classes of different types of geometric shapes. More...

Classes

class  coal::Box
 Center at zero point, axis aligned box. More...
 
class  coal::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  coal::Cone
 Cone The base of the cone is at $ z = - halfLength $ and the top is at $ z = halfLength $. More...
 
class  coal::Convex< PolygonT >
 Convex polytope. More...
 
class  coal::ConvexBase
 Base for convex polytope. More...
 
class  coal::Cylinder
 Cylinder along Z axis. The cylinder is defined at its centroid. More...
 
class  coal::Ellipsoid
 Ellipsoid centered at point zero. More...
 
class  coal::Halfspace
 Half Space: this is equivalent to the Plane in ODE. A Half space has a priviledged direction: the direction of the normal. 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. Note: prefer using a Halfspace instead of a Plane if possible, it has better behavior w.r.t. collision detection algorithms. More...
 
struct  coal::ConvexBase::Neighbors
 
class  coal::Plane
 Infinite plane. A plane can be viewed as two half spaces; it has no priviledged direction. Note: prefer using a Halfspace instead of a Plane if possible, it has better behavior w.r.t. collision detection algorithms. More...
 
class  coal::Sphere
 Center at zero point sphere. More...
 
struct  coal::ConvexBase::SupportWarmStartPolytope
 The support warm start polytope contains certain points of this which are support points in specific directions of space. This struct is used to warm start the support function computation for large meshes (num_points > 32). More...
 
class  coal::TriangleP
 Triangle stores the points instead of only indices of points. More...
 

Functions

 coal::Box::Box ()
 Default constructor. More...
 
 coal::Box::Box (CoalScalar x, CoalScalar y, CoalScalar z)
 
 coal::Box::Box (const Box &other)
 
 coal::Box::Box (const Vec3s &side_)
 
void coal::ConvexBase::buildSupportWarmStart ()
 Build the support points warm starts. More...
 
 coal::Capsule::Capsule ()
 Default constructor. More...
 
 coal::Capsule::Capsule (CoalScalar radius_, CoalScalar lz_)
 
 coal::Capsule::Capsule (const Capsule &other)
 
virtual TrianglePcoal::TriangleP::clone () const
 Clone *this into a new TriangleP. More...
 
virtual Boxcoal::Box::clone () const
 Clone *this into a new Box. More...
 
virtual Spherecoal::Sphere::clone () const
 Clone *this into a new Sphere. More...
 
virtual Ellipsoidcoal::Ellipsoid::clone () const
 Clone *this into a new Ellipsoid. More...
 
virtual Capsulecoal::Capsule::clone () const
 Clone *this into a new Capsule. More...
 
virtual Conecoal::Cone::clone () const
 Clone *this into a new Cone. More...
 
virtual Cylindercoal::Cylinder::clone () const
 Clone *this into a new Cylinder. More...
 
virtual ConvexBasecoal::ConvexBase::clone () const
 Clone (deep copy). This method is consistent with BVHModel clone method. The copy constructor is called, which duplicates the data. More...
 
virtual Halfspacecoal::Halfspace::clone () const
 Clone *this into a new Halfspace. More...
 
virtual Planecoal::Plane::clone () const
 Clone *this into a new Plane. More...
 
void coal::ConvexBase::computeCenter ()
 
Vec3s coal::Cone::computeCOM () const
 compute center of mass More...
 
void coal::TriangleP::computeLocalAABB ()
 virtual function of compute AABB in local coordinate More...
 
void coal::Box::computeLocalAABB ()
 Compute AABB. More...
 
void coal::Sphere::computeLocalAABB ()
 Compute AABB. More...
 
void coal::Ellipsoid::computeLocalAABB ()
 Compute AABB. More...
 
void coal::Capsule::computeLocalAABB ()
 Compute AABB. More...
 
void coal::Cone::computeLocalAABB ()
 Compute AABB. More...
 
void coal::Cylinder::computeLocalAABB ()
 Compute AABB. More...
 
void coal::ConvexBase::computeLocalAABB ()
 Compute AABB. More...
 
void coal::Halfspace::computeLocalAABB ()
 Compute AABB. More...
 
void coal::Plane::computeLocalAABB ()
 Compute AABB. More...
 
Matrix3s coal::Box::computeMomentofInertia () const
 compute the inertia matrix, related to the origin More...
 
Matrix3s coal::Sphere::computeMomentofInertia () const
 compute the inertia matrix, related to the origin More...
 
Matrix3s coal::Ellipsoid::computeMomentofInertia () const
 compute the inertia matrix, related to the origin More...
 
Matrix3s coal::Capsule::computeMomentofInertia () const
 compute the inertia matrix, related to the origin More...
 
Matrix3s coal::Cone::computeMomentofInertia () const
 compute the inertia matrix, related to the origin More...
 
Matrix3s coal::Cylinder::computeMomentofInertia () const
 compute the inertia matrix, related to the origin More...
 
CoalScalar coal::Box::computeVolume () const
 compute the volume More...
 
CoalScalar coal::Sphere::computeVolume () const
 compute the volume More...
 
CoalScalar coal::Ellipsoid::computeVolume () const
 compute the volume More...
 
CoalScalar coal::Capsule::computeVolume () const
 compute the volume More...
 
CoalScalar coal::Cone::computeVolume () const
 compute the volume More...
 
CoalScalar coal::Cylinder::computeVolume () const
 compute the volume More...
 
 coal::Cone::Cone ()
 Default constructor. More...
 
 coal::Cone::Cone (CoalScalar radius_, CoalScalar lz_)
 
 coal::Cone::Cone (const Cone &other)
 
 coal::ConvexBase::ConvexBase ()
 Construct an uninitialized convex object Initialization is done with ConvexBase::initialize. More...
 
 coal::ConvexBase::ConvexBase (const ConvexBase &other)
 Copy constructor Only the list of neighbors is copied. More...
 
static COAL_DEPRECATED ConvexBasecoal::ConvexBase::convexHull (const Vec3s *points, unsigned int num_points, bool keepTriangles, const char *qhullCommand=NULL)
 
static ConvexBasecoal::ConvexBase::convexHull (std::shared_ptr< std::vector< Vec3s >> &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 & coal::ConvexBase::Neighbors::count () const
 
 coal::Cylinder::Cylinder ()
 Default constructor. More...
 
 coal::Cylinder::Cylinder (CoalScalar radius_, CoalScalar lz_)
 
 coal::Cylinder::Cylinder (const Cylinder &other)
 
CoalScalar coal::Halfspace::distance (const Vec3s &p) const
 
CoalScalar coal::Plane::distance (const Vec3s &p) const
 
 coal::Ellipsoid::Ellipsoid ()
 Default constructor. More...
 
 coal::Ellipsoid::Ellipsoid (CoalScalar rx, CoalScalar ry, CoalScalar rz)
 
 coal::Ellipsoid::Ellipsoid (const Ellipsoid &other)
 
 coal::Ellipsoid::Ellipsoid (const Vec3s &radii)
 
NODE_TYPE coal::TriangleP::getNodeType () const
 get the node type More...
 
NODE_TYPE coal::Box::getNodeType () const
 Get node type: a box. More...
 
NODE_TYPE coal::Sphere::getNodeType () const
 Get node type: a sphere. More...
 
NODE_TYPE coal::Ellipsoid::getNodeType () const
 Get node type: an ellipsoid. More...
 
NODE_TYPE coal::Capsule::getNodeType () const
 Get node type: a capsule. More...
 
NODE_TYPE coal::Cone::getNodeType () const
 Get node type: a cone. More...
 
NODE_TYPE coal::Cylinder::getNodeType () const
 Get node type: a cylinder. More...
 
NODE_TYPE coal::ConvexBase::getNodeType () const
 Get node type: a convex polytope. More...
 
NODE_TYPE coal::Halfspace::getNodeType () const
 Get node type: a half space. More...
 
NODE_TYPE coal::Plane::getNodeType () const
 Get node type: a plane. More...
 
OBJECT_TYPE coal::ShapeBase::getObjectType () const
 Get object type: a geometric shape. More...
 
CoalScalar coal::ShapeBase::getSweptSphereRadius () const
 Get radius of sphere swept around the shape. This radius is always >= 0. More...
 
 coal::Halfspace::Halfspace ()
 
 coal::Halfspace::Halfspace (CoalScalar a, CoalScalar b, CoalScalar c, CoalScalar d_)
 Construct a plane with normal direction and offset. More...
 
 coal::Halfspace::Halfspace (const Halfspace &other)
 
 coal::Halfspace::Halfspace (const Vec3s &n_, CoalScalar d_)
 Construct a half space with normal direction and offset. More...
 
std::pair< Box, Transform3scoal::Box::inflated (const CoalScalar value) const
 Inflate the box by an amount given by value. This value can be positive or negative but must always >= minInflationValue(). More...
 
std::pair< Sphere, Transform3scoal::Sphere::inflated (const CoalScalar value) const
 Inflate the sphere by an amount given by value. This value can be positive or negative but must always >= minInflationValue(). More...
 
std::pair< Ellipsoid, Transform3scoal::Ellipsoid::inflated (const CoalScalar value) const
 Inflate the ellipsoid by an amount given by value. This value can be positive or negative but must always >= minInflationValue(). More...
 
std::pair< Capsule, Transform3scoal::Capsule::inflated (const CoalScalar value) const
 Inflate the capsule by an amount given by value. This value can be positive or negative but must always >= minInflationValue(). More...
 
std::pair< Cone, Transform3scoal::Cone::inflated (const CoalScalar value) const
 Inflate the cone by an amount given by value. This value can be positive or negative but must always >= minInflationValue(). More...
 
std::pair< Cylinder, Transform3scoal::Cylinder::inflated (const CoalScalar value) const
 Inflate the cylinder by an amount given by value. This value can be positive or negative but must always >= minInflationValue(). More...
 
std::pair< Halfspace, Transform3scoal::Halfspace::inflated (const CoalScalar value) const
 Inflate the halfspace by an amount given by value. This value can be positive or negative but must always >= minInflationValue(). More...
 
void coal::ConvexBase::initialize (std::shared_ptr< std::vector< Vec3s >> points_, unsigned int num_points_)
 Initialize the points of the convex shape This also initializes the ConvexBase::center. More...
 
virtual bool coal::TriangleP::isEqual (const CollisionGeometry &_other) const
 equal operator with another object of derived type. More...
 
virtual bool coal::Box::isEqual (const CollisionGeometry &_other) const
 equal operator with another object of derived type. More...
 
virtual bool coal::Sphere::isEqual (const CollisionGeometry &_other) const
 equal operator with another object of derived type. More...
 
virtual bool coal::Ellipsoid::isEqual (const CollisionGeometry &_other) const
 equal operator with another object of derived type. More...
 
virtual bool coal::Capsule::isEqual (const CollisionGeometry &_other) const
 equal operator with another object of derived type. More...
 
virtual bool coal::Cone::isEqual (const CollisionGeometry &_other) const
 equal operator with another object of derived type. More...
 
virtual bool coal::Cylinder::isEqual (const CollisionGeometry &_other) const
 equal operator with another object of derived type. More...
 
virtual bool coal::ConvexBase::isEqual (const CollisionGeometry &_other) const
 equal operator with another object of derived type. More...
 
virtual bool coal::Halfspace::isEqual (const CollisionGeometry &_other) const
 equal operator with another object of derived type. More...
 
virtual bool coal::Plane::isEqual (const CollisionGeometry &_other) const
 equal operator with another object of derived type. More...
 
CoalScalar coal::Box::minInflationValue () const
 
CoalScalar coal::Sphere::minInflationValue () const
 
CoalScalar coal::Ellipsoid::minInflationValue () const
 
CoalScalar coal::Capsule::minInflationValue () const
 
CoalScalar coal::Cone::minInflationValue () const
 
CoalScalar coal::Cylinder::minInflationValue () const
 
CoalScalar coal::Halfspace::minInflationValue () const
 
bool coal::ConvexBase::Neighbors::operator!= (const Neighbors &other) const
 
Boxcoal::Box::operator= (const Box &other)
 
Cylindercoal::Cylinder::operator= (const Cylinder &other)
 
Halfspacecoal::Halfspace::operator= (const Halfspace &other)
 operator = More...
 
Planecoal::Plane::operator= (const Plane &other)
 operator = More...
 
ShapeBasecoal::ShapeBase::operator= (const ShapeBase &other)=default
 
bool coal::ConvexBase::Neighbors::operator== (const Neighbors &other) const
 
unsigned int & coal::ConvexBase::Neighbors::operator[] (int i)
 
unsigned int const & coal::ConvexBase::Neighbors::operator[] (int i) const
 
 coal::Plane::Plane ()
 
 coal::Plane::Plane (CoalScalar a, CoalScalar b, CoalScalar c, CoalScalar d_)
 Construct a plane with normal direction and offset. More...
 
 coal::Plane::Plane (const Plane &other)
 
 coal::Plane::Plane (const Vec3s &n_, CoalScalar d_)
 Construct a plane with normal direction and offset. More...
 
void coal::ConvexBase::set (std::shared_ptr< std::vector< Vec3s >> points_, unsigned int num_points_)
 Set the points of the convex shape. More...
 
void coal::ShapeBase::setSweptSphereRadius (CoalScalar radius)
 Set radius of sphere swept around the shape. Must be >= 0. More...
 
 coal::ShapeBase::ShapeBase ()
 
 coal::ShapeBase::ShapeBase (const ShapeBase &other)
   More...
 
CoalScalar coal::Halfspace::signedDistance (const Vec3s &p) const
 
CoalScalar coal::Plane::signedDistance (const Vec3s &p) const
 
 coal::Sphere::Sphere ()
 Default constructor. More...
 
 coal::Sphere::Sphere (CoalScalar radius_)
 
 coal::Sphere::Sphere (const Sphere &other)
 
 coal::TriangleP::TriangleP ()
 
 coal::TriangleP::TriangleP (const TriangleP &other)
 
 coal::TriangleP::TriangleP (const Vec3s &a_, const Vec3s &b_, const Vec3s &c_)
 
void coal::Halfspace::unitNormalTest ()
 Turn non-unit normal into unit. More...
 
void coal::Plane::unitNormalTest ()
 Turn non-unit normal into unit. More...
 
virtual coal::ConvexBase::~ConvexBase ()
 
virtual coal::ShapeBase::~ShapeBase ()
 

Variables

Vec3s coal::TriangleP::a
 
Vec3s coal::TriangleP::b
 
Vec3s coal::TriangleP::c
 
Vec3s coal::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 coal::ConvexBase::Neighbors::count_
 
CoalScalar coal::Halfspace::d
 Plane offset. More...
 
CoalScalar coal::Plane::d
 Plane offset. More...
 
CoalScalar coal::Capsule::halfLength
 Half Length along z axis. More...
 
CoalScalar coal::Cone::halfLength
 Half Length along z axis. More...
 
CoalScalar coal::Cylinder::halfLength
 Half Length along z axis. More...
 
Vec3s coal::Box::halfSide
 box side half-length More...
 
std::vector< int > coal::ConvexBase::SupportWarmStartPolytope::indices
 Indices of the support points warm starts. These are the indices of the real convex, not the indices of points in the warm start polytope. More...
 
CoalScalar coal::ShapeBase::m_swept_sphere_radius {0}
 Radius of the sphere swept around the shape. Default value is 0. Note: this property differs from inflated method of certain derived classes (e.g. Box, Sphere, Ellipsoid, Capsule, Cone, Cylinder) in the sense that inflated returns a new shape which can be inflated but also deflated. Also, an inflated shape is not rounded. It simply has a different size. Sweeping a shape with a sphere is a different operation (a Minkowski sum), which rounds the sharp corners of a shape. The swept sphere radius is a property of the shape itself and can be manually updated between collision checks. More...
 
Vec3s coal::Halfspace::n
 Plane normal. More...
 
Vec3s coal::Plane::n
 Plane normal. More...
 
unsigned int * coal::ConvexBase::Neighbors::n_
 
std::shared_ptr< std::vector< Neighbors > > coal::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 pointing to them. More...
 
std::shared_ptr< std::vector< unsigned int > > coal::ConvexBase::nneighbors_
 Array of indices of the neighbors of each vertex. Since we don't know a priori the number of neighbors of each vertex, we store the indices of the neighbors in a single array. The neighbors attribute, an array of Neighbors, is used to point each vertex to the right indices in the nneighbors_ array. More...
 
std::shared_ptr< std::vector< Vec3s > > coal::ConvexBase::normals
 An array of the normals of the polygon. More...
 
unsigned int coal::ConvexBase::num_normals_and_offsets
 
unsigned int coal::ConvexBase::num_points
 
static constexpr size_t coal::ConvexBase::num_support_warm_starts = 14
 Number of support warm starts. More...
 
static constexpr size_t coal::ConvexBase::num_vertices_large_convex_threshold = 32
 Above this threshold, the convex polytope is considered large. This influcences the way the support function is computed. More...
 
std::shared_ptr< std::vector< double > > coal::ConvexBase::offsets
 An array of the offsets to the normals of the polygon. Note: there are as many offsets as normals. More...
 
std::shared_ptr< std::vector< Vec3s > > coal::ConvexBase::points
 An array of the points of the polygon. More...
 
std::vector< Vec3scoal::ConvexBase::SupportWarmStartPolytope::points
 Array of support points to warm start the support function computation. More...
 
Vec3s coal::Ellipsoid::radii
 Radii of the Ellipsoid (such that on boundary: x^2/rx^2 + y^2/ry^2. More...
 
CoalScalar coal::Sphere::radius
 Radius of the sphere. More...
 
CoalScalar coal::Capsule::radius
 Radius of capsule. More...
 
CoalScalar coal::Cone::radius
 Radius of the cone. More...
 
CoalScalar coal::Cylinder::radius
 Radius of the cylinder. More...
 
SupportWarmStartPolytope coal::ConvexBase::support_warm_starts
 Support warm start polytopes. More...
 

Detailed Description

Classes of different types of geometric shapes.

Function Documentation

◆ Box() [1/4]

coal::Box::Box ( )
inline

Default constructor.

Definition at line 186 of file coal/shape/geometric_shapes.h.

◆ Box() [2/4]

coal::Box::Box ( CoalScalar  x,
CoalScalar  y,
CoalScalar  z 
)
inline

Definition at line 168 of file coal/shape/geometric_shapes.h.

◆ Box() [3/4]

coal::Box::Box ( const Box other)
inline

Definition at line 173 of file coal/shape/geometric_shapes.h.

◆ Box() [4/4]

coal::Box::Box ( const Vec3s side_)
inline

Definition at line 171 of file coal/shape/geometric_shapes.h.

◆ buildSupportWarmStart()

void coal::ConvexBase::buildSupportWarmStart ( )
protected

Build the support points warm starts.

Definition at line 1471 of file src/narrowphase/gjk.cpp.

◆ Capsule() [1/3]

coal::Capsule::Capsule ( )
inline

Default constructor.

Definition at line 386 of file coal/shape/geometric_shapes.h.

◆ Capsule() [2/3]

coal::Capsule::Capsule ( CoalScalar  radius_,
CoalScalar  lz_ 
)
inline

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

◆ Capsule() [3/3]

coal::Capsule::Capsule ( const Capsule other)
inline

Definition at line 392 of file coal/shape/geometric_shapes.h.

◆ clone() [1/10]

virtual TriangleP* coal::TriangleP::clone ( ) const
inlinevirtual

Clone *this into a new TriangleP.

Implements coal::CollisionGeometry.

Definition at line 121 of file coal/shape/geometric_shapes.h.

◆ clone() [2/10]

virtual Box* coal::Box::clone ( ) const
inlinevirtual

Clone *this into a new Box.

Implements coal::CollisionGeometry.

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

◆ clone() [3/10]

virtual Sphere* coal::Sphere::clone ( ) const
inlinevirtual

Clone *this into a new Sphere.

Implements coal::CollisionGeometry.

Definition at line 250 of file coal/shape/geometric_shapes.h.

◆ clone() [4/10]

virtual Ellipsoid* coal::Ellipsoid::clone ( ) const
inlinevirtual

Clone *this into a new Ellipsoid.

Implements coal::CollisionGeometry.

Definition at line 318 of file coal/shape/geometric_shapes.h.

◆ clone() [5/10]

virtual Capsule* coal::Capsule::clone ( ) const
inlinevirtual

Clone *this into a new Capsule.

Implements coal::CollisionGeometry.

Definition at line 396 of file coal/shape/geometric_shapes.h.

◆ clone() [6/10]

virtual Cone* coal::Cone::clone ( ) const
inlinevirtual

Clone *this into a new Cone.

Implements coal::CollisionGeometry.

Definition at line 480 of file coal/shape/geometric_shapes.h.

◆ clone() [7/10]

virtual Cylinder* coal::Cylinder::clone ( ) const
inlinevirtual

Clone *this into a new Cylinder.

Implements coal::CollisionGeometry.

Definition at line 581 of file coal/shape/geometric_shapes.h.

◆ clone() [8/10]

virtual ConvexBase* coal::ConvexBase::clone ( ) const
inlinevirtual

Clone (deep copy). This method is consistent with BVHModel clone method. The copy constructor is called, which duplicates the data.

Implements coal::CollisionGeometry.

Definition at line 673 of file coal/shape/geometric_shapes.h.

◆ clone() [9/10]

virtual Halfspace* coal::Halfspace::clone ( ) const
inlinevirtual

Clone *this into a new Halfspace.

Implements coal::CollisionGeometry.

Definition at line 918 of file coal/shape/geometric_shapes.h.

◆ clone() [10/10]

virtual Plane* coal::Plane::clone ( ) const
inlinevirtual

Clone *this into a new Plane.

Implements coal::CollisionGeometry.

Definition at line 1008 of file coal/shape/geometric_shapes.h.

◆ computeCenter()

void coal::ConvexBase::computeCenter ( )
private

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

◆ computeCOM()

Vec3s coal::Cone::computeCOM ( ) const
inlinevirtual

compute center of mass

Reimplemented from coal::CollisionGeometry.

Definition at line 508 of file coal/shape/geometric_shapes.h.

◆ computeLocalAABB() [1/10]

void coal::TriangleP::computeLocalAABB ( )
virtual

virtual function of compute AABB in local coordinate

Implements coal::CollisionGeometry.

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

◆ computeLocalAABB() [2/10]

void coal::Box::computeLocalAABB ( )
virtual

Compute AABB.

Implements coal::CollisionGeometry.

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

◆ computeLocalAABB() [3/10]

void coal::Sphere::computeLocalAABB ( )
virtual

Compute AABB.

Implements coal::CollisionGeometry.

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

◆ computeLocalAABB() [4/10]

void coal::Ellipsoid::computeLocalAABB ( )
virtual

Compute AABB.

Implements coal::CollisionGeometry.

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

◆ computeLocalAABB() [5/10]

void coal::Capsule::computeLocalAABB ( )
virtual

Compute AABB.

Implements coal::CollisionGeometry.

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

◆ computeLocalAABB() [6/10]

void coal::Cone::computeLocalAABB ( )
virtual

Compute AABB.

Implements coal::CollisionGeometry.

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

◆ computeLocalAABB() [7/10]

void coal::Cylinder::computeLocalAABB ( )
virtual

Compute AABB.

Implements coal::CollisionGeometry.

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

◆ computeLocalAABB() [8/10]

void coal::ConvexBase::computeLocalAABB ( )
virtual

Compute AABB.

Implements coal::CollisionGeometry.

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

◆ computeLocalAABB() [9/10]

void coal::Halfspace::computeLocalAABB ( )
virtual

Compute AABB.

Implements coal::CollisionGeometry.

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

◆ computeLocalAABB() [10/10]

void coal::Plane::computeLocalAABB ( )
virtual

Compute AABB.

Implements coal::CollisionGeometry.

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

◆ computeMomentofInertia() [1/6]

Matrix3s coal::Box::computeMomentofInertia ( ) const
inlinevirtual

compute the inertia matrix, related to the origin

Reimplemented from coal::CollisionGeometry.

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

◆ computeMomentofInertia() [2/6]

Matrix3s coal::Sphere::computeMomentofInertia ( ) const
inlinevirtual

compute the inertia matrix, related to the origin

Reimplemented from coal::CollisionGeometry.

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

◆ computeMomentofInertia() [3/6]

Matrix3s coal::Ellipsoid::computeMomentofInertia ( ) const
inlinevirtual

compute the inertia matrix, related to the origin

Reimplemented from coal::CollisionGeometry.

Definition at line 330 of file coal/shape/geometric_shapes.h.

◆ computeMomentofInertia() [4/6]

Matrix3s coal::Capsule::computeMomentofInertia ( ) const
inlinevirtual

compute the inertia matrix, related to the origin

Reimplemented from coal::CollisionGeometry.

Definition at line 415 of file coal/shape/geometric_shapes.h.

◆ computeMomentofInertia() [5/6]

Matrix3s coal::Cone::computeMomentofInertia ( ) const
inlinevirtual

compute the inertia matrix, related to the origin

Reimplemented from coal::CollisionGeometry.

Definition at line 499 of file coal/shape/geometric_shapes.h.

◆ computeMomentofInertia() [6/6]

Matrix3s coal::Cylinder::computeMomentofInertia ( ) const
inlinevirtual

compute the inertia matrix, related to the origin

Reimplemented from coal::CollisionGeometry.

Definition at line 600 of file coal/shape/geometric_shapes.h.

◆ computeVolume() [1/6]

CoalScalar coal::Box::computeVolume ( ) const
inlinevirtual

compute the volume

Reimplemented from coal::CollisionGeometry.

Definition at line 197 of file coal/shape/geometric_shapes.h.

◆ computeVolume() [2/6]

CoalScalar coal::Sphere::computeVolume ( ) const
inlinevirtual

compute the volume

Reimplemented from coal::CollisionGeometry.

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

◆ computeVolume() [3/6]

CoalScalar coal::Ellipsoid::computeVolume ( ) const
inlinevirtual

compute the volume

Reimplemented from coal::CollisionGeometry.

Definition at line 340 of file coal/shape/geometric_shapes.h.

◆ computeVolume() [4/6]

CoalScalar coal::Capsule::computeVolume ( ) const
inlinevirtual

compute the volume

Reimplemented from coal::CollisionGeometry.

Definition at line 410 of file coal/shape/geometric_shapes.h.

◆ computeVolume() [5/6]

CoalScalar coal::Cone::computeVolume ( ) const
inlinevirtual

compute the volume

Reimplemented from coal::CollisionGeometry.

Definition at line 494 of file coal/shape/geometric_shapes.h.

◆ computeVolume() [6/6]

CoalScalar coal::Cylinder::computeVolume ( ) const
inlinevirtual

compute the volume

Reimplemented from coal::CollisionGeometry.

Definition at line 595 of file coal/shape/geometric_shapes.h.

◆ Cone() [1/3]

coal::Cone::Cone ( )
inline

Default constructor.

Definition at line 470 of file coal/shape/geometric_shapes.h.

◆ Cone() [2/3]

coal::Cone::Cone ( CoalScalar  radius_,
CoalScalar  lz_ 
)
inline

Definition at line 472 of file coal/shape/geometric_shapes.h.

◆ Cone() [3/3]

coal::Cone::Cone ( const Cone other)
inline

Definition at line 476 of file coal/shape/geometric_shapes.h.

◆ ConvexBase() [1/2]

coal::ConvexBase::ConvexBase ( )
inlineprotected

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

Definition at line 762 of file coal/shape/geometric_shapes.h.

◆ ConvexBase() [2/2]

coal::ConvexBase::ConvexBase ( const ConvexBase other)
protected

Copy constructor Only the list of neighbors is copied.

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

◆ convexHull() [1/2]

ConvexBase * coal::ConvexBase::convexHull ( const Vec3s points,
unsigned int  num_points,
bool  keepTriangles,
const char *  qhullCommand = NULL 
)
static

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

◆ convexHull() [2/2]

ConvexBase * coal::ConvexBase::convexHull ( std::shared_ptr< std::vector< Vec3s >> &  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
Coal must have been compiled with option COAL_HAS_QHULL set to ON.

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

◆ count()

unsigned char const& coal::ConvexBase::Neighbors::count ( ) const
inline

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

◆ Cylinder() [1/3]

coal::Cylinder::Cylinder ( )
inline

Default constructor.

Definition at line 563 of file coal/shape/geometric_shapes.h.

◆ Cylinder() [2/3]

coal::Cylinder::Cylinder ( CoalScalar  radius_,
CoalScalar  lz_ 
)
inline

Definition at line 565 of file coal/shape/geometric_shapes.h.

◆ Cylinder() [3/3]

coal::Cylinder::Cylinder ( const Cylinder other)
inline

Definition at line 569 of file coal/shape/geometric_shapes.h.

◆ distance() [1/2]

CoalScalar coal::Halfspace::distance ( const Vec3s p) const
inline

Definition at line 924 of file coal/shape/geometric_shapes.h.

◆ distance() [2/2]

CoalScalar coal::Plane::distance ( const Vec3s p) const
inline

Definition at line 1023 of file coal/shape/geometric_shapes.h.

◆ Ellipsoid() [1/4]

coal::Ellipsoid::Ellipsoid ( )
inline

Default constructor.

Definition at line 308 of file coal/shape/geometric_shapes.h.

◆ Ellipsoid() [2/4]

coal::Ellipsoid::Ellipsoid ( CoalScalar  rx,
CoalScalar  ry,
CoalScalar  rz 
)
inline

Definition at line 310 of file coal/shape/geometric_shapes.h.

◆ Ellipsoid() [3/4]

coal::Ellipsoid::Ellipsoid ( const Ellipsoid other)
inline

Definition at line 315 of file coal/shape/geometric_shapes.h.

◆ Ellipsoid() [4/4]

coal::Ellipsoid::Ellipsoid ( const Vec3s radii)
inlineexplicit

Definition at line 313 of file coal/shape/geometric_shapes.h.

◆ getNodeType() [1/10]

NODE_TYPE coal::TriangleP::getNodeType ( ) const
inlinevirtual

get the node type

Reimplemented from coal::CollisionGeometry.

Definition at line 126 of file coal/shape/geometric_shapes.h.

◆ getNodeType() [2/10]

NODE_TYPE coal::Box::getNodeType ( ) const
inlinevirtual

Get node type: a box.

Reimplemented from coal::CollisionGeometry.

Definition at line 195 of file coal/shape/geometric_shapes.h.

◆ getNodeType() [3/10]

NODE_TYPE coal::Sphere::getNodeType ( ) const
inlinevirtual

Get node type: a sphere.

Reimplemented from coal::CollisionGeometry.

Definition at line 259 of file coal/shape/geometric_shapes.h.

◆ getNodeType() [4/10]

NODE_TYPE coal::Ellipsoid::getNodeType ( ) const
inlinevirtual

Get node type: an ellipsoid.

Reimplemented from coal::CollisionGeometry.

Definition at line 328 of file coal/shape/geometric_shapes.h.

◆ getNodeType() [5/10]

NODE_TYPE coal::Capsule::getNodeType ( ) const
inlinevirtual

Get node type: a capsule.

Reimplemented from coal::CollisionGeometry.

Definition at line 408 of file coal/shape/geometric_shapes.h.

◆ getNodeType() [6/10]

NODE_TYPE coal::Cone::getNodeType ( ) const
inlinevirtual

Get node type: a cone.

Reimplemented from coal::CollisionGeometry.

Definition at line 492 of file coal/shape/geometric_shapes.h.

◆ getNodeType() [7/10]

NODE_TYPE coal::Cylinder::getNodeType ( ) const
inlinevirtual

Get node type: a cylinder.

Reimplemented from coal::CollisionGeometry.

Definition at line 593 of file coal/shape/geometric_shapes.h.

◆ getNodeType() [8/10]

NODE_TYPE coal::ConvexBase::getNodeType ( ) const
inlinevirtual

Get node type: a convex polytope.

Reimplemented from coal::CollisionGeometry.

Definition at line 679 of file coal/shape/geometric_shapes.h.

◆ getNodeType() [9/10]

NODE_TYPE coal::Halfspace::getNodeType ( ) const
inlinevirtual

Get node type: a half space.

Reimplemented from coal::CollisionGeometry.

Definition at line 932 of file coal/shape/geometric_shapes.h.

◆ getNodeType() [10/10]

NODE_TYPE coal::Plane::getNodeType ( ) const
inlinevirtual

Get node type: a plane.

Reimplemented from coal::CollisionGeometry.

Definition at line 1031 of file coal/shape/geometric_shapes.h.

◆ getObjectType()

OBJECT_TYPE coal::ShapeBase::getObjectType ( ) const
inlinevirtual

Get object type: a geometric shape.

Reimplemented from coal::CollisionGeometry.

Definition at line 72 of file coal/shape/geometric_shapes.h.

◆ getSweptSphereRadius()

CoalScalar coal::ShapeBase::getSweptSphereRadius ( ) const
inline

Get radius of sphere swept around the shape. This radius is always >= 0.

Definition at line 86 of file coal/shape/geometric_shapes.h.

◆ Halfspace() [1/4]

coal::Halfspace::Halfspace ( )
inline

Definition at line 905 of file coal/shape/geometric_shapes.h.

◆ Halfspace() [2/4]

coal::Halfspace::Halfspace ( CoalScalar  a,
CoalScalar  b,
CoalScalar  c,
CoalScalar  d_ 
)
inline

Construct a plane with normal direction and offset.

Definition at line 900 of file coal/shape/geometric_shapes.h.

◆ Halfspace() [3/4]

coal::Halfspace::Halfspace ( const Halfspace other)
inline

Definition at line 907 of file coal/shape/geometric_shapes.h.

◆ Halfspace() [4/4]

coal::Halfspace::Halfspace ( const Vec3s n_,
CoalScalar  d_ 
)
inline

Construct a half space with normal direction and offset.

Definition at line 895 of file coal/shape/geometric_shapes.h.

◆ inflated() [1/7]

std::pair<Box, Transform3s> coal::Box::inflated ( const CoalScalar  value) const
inline

Inflate the box by an amount given by value. This value can be positive or negative but must always >= minInflationValue().

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 215 of file coal/shape/geometric_shapes.h.

◆ inflated() [2/7]

std::pair<Sphere, Transform3s> coal::Sphere::inflated ( const CoalScalar  value) const
inline

Inflate the sphere by an amount given by value. This value can be positive or negative but must always >= minInflationValue().

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 281 of file coal/shape/geometric_shapes.h.

◆ inflated() [3/7]

std::pair<Ellipsoid, Transform3s> coal::Ellipsoid::inflated ( const CoalScalar  value) const
inline

Inflate the ellipsoid by an amount given by value. This value can be positive or negative but must always >= minInflationValue().

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 355 of file coal/shape/geometric_shapes.h.

◆ inflated() [4/7]

std::pair<Capsule, Transform3s> coal::Capsule::inflated ( const CoalScalar  value) const
inline

Inflate the capsule by an amount given by value. This value can be positive or negative but must always >= minInflationValue().

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 440 of file coal/shape/geometric_shapes.h.

◆ inflated() [5/7]

std::pair<Cone, Transform3s> coal::Cone::inflated ( const CoalScalar  value) const
inline

Inflate the cone by an amount given by value. This value can be positive or negative but must always >= minInflationValue().

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 522 of file coal/shape/geometric_shapes.h.

◆ inflated() [6/7]

std::pair<Cylinder, Transform3s> coal::Cylinder::inflated ( const CoalScalar  value) const
inline

Inflate the cylinder by an amount given by value. This value can be positive or negative but must always >= minInflationValue().

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 619 of file coal/shape/geometric_shapes.h.

◆ inflated() [7/7]

std::pair<Halfspace, Transform3s> coal::Halfspace::inflated ( const CoalScalar  value) const
inline

Inflate the halfspace by an amount given by value. This value can be positive or negative but must always >= minInflationValue().

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

Definition at line 946 of file coal/shape/geometric_shapes.h.

◆ initialize()

void coal::ConvexBase::initialize ( std::shared_ptr< std::vector< Vec3s >>  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 43 of file src/shape/geometric_shapes.cpp.

◆ isEqual() [1/10]

virtual bool coal::TriangleP::isEqual ( const CollisionGeometry other) const
inlineprivatevirtual

equal operator with another object of derived type.

Implements coal::CollisionGeometry.

Definition at line 152 of file coal/shape/geometric_shapes.h.

◆ isEqual() [2/10]

virtual bool coal::Box::isEqual ( const CollisionGeometry other) const
inlineprivatevirtual

equal operator with another object of derived type.

Implements coal::CollisionGeometry.

Definition at line 226 of file coal/shape/geometric_shapes.h.

◆ isEqual() [3/10]

virtual bool coal::Sphere::isEqual ( const CollisionGeometry other) const
inlineprivatevirtual

equal operator with another object of derived type.

Implements coal::CollisionGeometry.

Definition at line 291 of file coal/shape/geometric_shapes.h.

◆ isEqual() [4/10]

virtual bool coal::Ellipsoid::isEqual ( const CollisionGeometry other) const
inlineprivatevirtual

equal operator with another object of derived type.

Implements coal::CollisionGeometry.

Definition at line 366 of file coal/shape/geometric_shapes.h.

◆ isEqual() [5/10]

virtual bool coal::Capsule::isEqual ( const CollisionGeometry other) const
inlineprivatevirtual

equal operator with another object of derived type.

Implements coal::CollisionGeometry.

Definition at line 451 of file coal/shape/geometric_shapes.h.

◆ isEqual() [6/10]

virtual bool coal::Cone::isEqual ( const CollisionGeometry other) const
inlineprivatevirtual

equal operator with another object of derived type.

Implements coal::CollisionGeometry.

Definition at line 545 of file coal/shape/geometric_shapes.h.

◆ isEqual() [7/10]

virtual bool coal::Cylinder::isEqual ( const CollisionGeometry other) const
inlineprivatevirtual

equal operator with another object of derived type.

Implements coal::CollisionGeometry.

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

◆ isEqual() [8/10]

virtual bool coal::ConvexBase::isEqual ( const CollisionGeometry other) const
inlineprivatevirtual

equal operator with another object of derived type.

Implements coal::CollisionGeometry.

Definition at line 806 of file coal/shape/geometric_shapes.h.

◆ isEqual() [9/10]

virtual bool coal::Halfspace::isEqual ( const CollisionGeometry other) const
inlineprivatevirtual

equal operator with another object of derived type.

Implements coal::CollisionGeometry.

Definition at line 966 of file coal/shape/geometric_shapes.h.

◆ isEqual() [10/10]

virtual bool coal::Plane::isEqual ( const CollisionGeometry other) const
inlineprivatevirtual

equal operator with another object of derived type.

Implements coal::CollisionGeometry.

Definition at line 1044 of file coal/shape/geometric_shapes.h.

◆ minInflationValue() [1/7]

CoalScalar coal::Box::minInflationValue ( ) const
inline

Definition at line 205 of file coal/shape/geometric_shapes.h.

◆ minInflationValue() [2/7]

CoalScalar coal::Sphere::minInflationValue ( ) const
inline

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

◆ minInflationValue() [3/7]

CoalScalar coal::Ellipsoid::minInflationValue ( ) const
inline

Definition at line 345 of file coal/shape/geometric_shapes.h.

◆ minInflationValue() [4/7]

CoalScalar coal::Capsule::minInflationValue ( ) const
inline

Definition at line 430 of file coal/shape/geometric_shapes.h.

◆ minInflationValue() [5/7]

CoalScalar coal::Cone::minInflationValue ( ) const
inline

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

◆ minInflationValue() [6/7]

CoalScalar coal::Cylinder::minInflationValue ( ) const
inline

Definition at line 607 of file coal/shape/geometric_shapes.h.

◆ minInflationValue() [7/7]

CoalScalar coal::Halfspace::minInflationValue ( ) const
inline

Definition at line 934 of file coal/shape/geometric_shapes.h.

◆ operator!=()

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

Definition at line 711 of file coal/shape/geometric_shapes.h.

◆ operator=() [1/5]

Box& coal::Box::operator= ( const Box other)
inline

Definition at line 175 of file coal/shape/geometric_shapes.h.

◆ operator=() [2/5]

Cylinder& coal::Cylinder::operator= ( const Cylinder other)
inline

Definition at line 572 of file coal/shape/geometric_shapes.h.

◆ operator=() [3/5]

Halfspace& coal::Halfspace::operator= ( const Halfspace other)
inline

operator =

Definition at line 911 of file coal/shape/geometric_shapes.h.

◆ operator=() [4/5]

Plane& coal::Plane::operator= ( const Plane other)
inline

operator =

Definition at line 1001 of file coal/shape/geometric_shapes.h.

◆ operator=() [5/5]

ShapeBase& coal::ShapeBase::operator= ( const ShapeBase other)
default

◆ operator==()

bool coal::ConvexBase::Neighbors::operator== ( const Neighbors other) const
inline

Definition at line 701 of file coal/shape/geometric_shapes.h.

◆ operator[]() [1/2]

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

Definition at line 692 of file coal/shape/geometric_shapes.h.

◆ operator[]() [2/2]

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

Definition at line 696 of file coal/shape/geometric_shapes.h.

◆ Plane() [1/4]

coal::Plane::Plane ( )
inline

Definition at line 996 of file coal/shape/geometric_shapes.h.

◆ Plane() [2/4]

coal::Plane::Plane ( CoalScalar  a,
CoalScalar  b,
CoalScalar  c,
CoalScalar  d_ 
)
inline

Construct a plane with normal direction and offset.

Definition at line 991 of file coal/shape/geometric_shapes.h.

◆ Plane() [3/4]

coal::Plane::Plane ( const Plane other)
inline

Definition at line 998 of file coal/shape/geometric_shapes.h.

◆ Plane() [4/4]

coal::Plane::Plane ( const Vec3s n_,
CoalScalar  d_ 
)
inline

Construct a plane with normal direction and offset.

Definition at line 986 of file coal/shape/geometric_shapes.h.

◆ set()

void coal::ConvexBase::set ( std::shared_ptr< std::vector< Vec3s >>  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 57 of file src/shape/geometric_shapes.cpp.

◆ setSweptSphereRadius()

void coal::ShapeBase::setSweptSphereRadius ( CoalScalar  radius)
inline

Set radius of sphere swept around the shape. Must be >= 0.

Definition at line 76 of file coal/shape/geometric_shapes.h.

◆ ShapeBase() [1/2]

coal::ShapeBase::ShapeBase ( )
inline

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

◆ ShapeBase() [2/2]

coal::ShapeBase::ShapeBase ( const ShapeBase other)
inline

 

Copy constructor

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

◆ signedDistance() [1/2]

CoalScalar coal::Halfspace::signedDistance ( const Vec3s p) const
inline

Definition at line 920 of file coal/shape/geometric_shapes.h.

◆ signedDistance() [2/2]

CoalScalar coal::Plane::signedDistance ( const Vec3s p) const
inline

Definition at line 1010 of file coal/shape/geometric_shapes.h.

◆ Sphere() [1/3]

coal::Sphere::Sphere ( )
inline

Default constructor.

Definition at line 243 of file coal/shape/geometric_shapes.h.

◆ Sphere() [2/3]

coal::Sphere::Sphere ( CoalScalar  radius_)
inlineexplicit

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

◆ Sphere() [3/3]

coal::Sphere::Sphere ( const Sphere other)
inline

Definition at line 247 of file coal/shape/geometric_shapes.h.

◆ TriangleP() [1/3]

coal::TriangleP::TriangleP ( )
inline

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

◆ TriangleP() [2/3]

coal::TriangleP::TriangleP ( const TriangleP other)
inline

Definition at line 117 of file coal/shape/geometric_shapes.h.

◆ TriangleP() [3/3]

coal::TriangleP::TriangleP ( const Vec3s a_,
const Vec3s b_,
const Vec3s c_ 
)
inline

Definition at line 114 of file coal/shape/geometric_shapes.h.

◆ unitNormalTest() [1/2]

void coal::Halfspace::unitNormalTest ( )
protected

Turn non-unit normal into unit.

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

◆ unitNormalTest() [2/2]

void coal::Plane::unitNormalTest ( )
protected

Turn non-unit normal into unit.

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

◆ ~ConvexBase()

coal::ConvexBase::~ConvexBase ( )
virtual

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

◆ ~ShapeBase()

virtual coal::ShapeBase::~ShapeBase ( )
inlinevirtual

Definition at line 69 of file coal/shape/geometric_shapes.h.

Variable Documentation

◆ a

Vec3s coal::TriangleP::a

Definition at line 149 of file coal/shape/geometric_shapes.h.

◆ b

Vec3s coal::TriangleP::b

Definition at line 149 of file coal/shape/geometric_shapes.h.

◆ c

Vec3s coal::TriangleP::c

Definition at line 149 of file coal/shape/geometric_shapes.h.

◆ center

Vec3s coal::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 736 of file coal/shape/geometric_shapes.h.

◆ count_

unsigned char coal::ConvexBase::Neighbors::count_

Definition at line 688 of file coal/shape/geometric_shapes.h.

◆ d [1/2]

CoalScalar coal::Halfspace::d

Plane offset.

Definition at line 959 of file coal/shape/geometric_shapes.h.

◆ d [2/2]

CoalScalar coal::Plane::d

Plane offset.

Definition at line 1037 of file coal/shape/geometric_shapes.h.

◆ halfLength [1/3]

CoalScalar coal::Capsule::halfLength

Half Length along z axis.

Definition at line 402 of file coal/shape/geometric_shapes.h.

◆ halfLength [2/3]

CoalScalar coal::Cone::halfLength

Half Length along z axis.

Definition at line 486 of file coal/shape/geometric_shapes.h.

◆ halfLength [3/3]

CoalScalar coal::Cylinder::halfLength

Half Length along z axis.

Definition at line 587 of file coal/shape/geometric_shapes.h.

◆ halfSide

Vec3s coal::Box::halfSide

box side half-length

Definition at line 189 of file coal/shape/geometric_shapes.h.

◆ indices

std::vector<int> coal::ConvexBase::SupportWarmStartPolytope::indices

Indices of the support points warm starts. These are the indices of the real convex, not the indices of points in the warm start polytope.

Definition at line 750 of file coal/shape/geometric_shapes.h.

◆ m_swept_sphere_radius

CoalScalar coal::ShapeBase::m_swept_sphere_radius {0}
protected

Radius of the sphere swept around the shape. Default value is 0. Note: this property differs from inflated method of certain derived classes (e.g. Box, Sphere, Ellipsoid, Capsule, Cone, Cylinder) in the sense that inflated returns a new shape which can be inflated but also deflated. Also, an inflated shape is not rounded. It simply has a different size. Sweeping a shape with a sphere is a different operation (a Minkowski sum), which rounds the sharp corners of a shape. The swept sphere radius is a property of the shape itself and can be manually updated between collision checks.

Definition at line 102 of file coal/shape/geometric_shapes.h.

◆ n [1/2]

Vec3s coal::Halfspace::n

Plane normal.

Definition at line 956 of file coal/shape/geometric_shapes.h.

◆ n [2/2]

Vec3s coal::Plane::n

Plane normal.

Definition at line 1034 of file coal/shape/geometric_shapes.h.

◆ n_

unsigned int* coal::ConvexBase::Neighbors::n_

Definition at line 689 of file coal/shape/geometric_shapes.h.

◆ neighbors

std::shared_ptr<std::vector<Neighbors> > coal::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 pointing to them.

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

◆ nneighbors_

std::shared_ptr<std::vector<unsigned int> > coal::ConvexBase::nneighbors_
protected

Array of indices of the neighbors of each vertex. Since we don't know a priori the number of neighbors of each vertex, we store the indices of the neighbors in a single array. The neighbors attribute, an array of Neighbors, is used to point each vertex to the right indices in the nneighbors_ array.

Definition at line 801 of file coal/shape/geometric_shapes.h.

◆ normals

std::shared_ptr<std::vector<Vec3s> > coal::ConvexBase::normals

An array of the normals of the polygon.

Definition at line 723 of file coal/shape/geometric_shapes.h.

◆ num_normals_and_offsets

unsigned int coal::ConvexBase::num_normals_and_offsets

Definition at line 727 of file coal/shape/geometric_shapes.h.

◆ num_points

unsigned int coal::ConvexBase::num_points

Definition at line 720 of file coal/shape/geometric_shapes.h.

◆ num_support_warm_starts

constexpr size_t coal::ConvexBase::num_support_warm_starts = 14
staticconstexpr

Number of support warm starts.

Definition at line 754 of file coal/shape/geometric_shapes.h.

◆ num_vertices_large_convex_threshold

constexpr size_t coal::ConvexBase::num_vertices_large_convex_threshold = 32
staticconstexpr

Above this threshold, the convex polytope is considered large. This influcences the way the support function is computed.

Definition at line 716 of file coal/shape/geometric_shapes.h.

◆ offsets

std::shared_ptr<std::vector<double> > coal::ConvexBase::offsets

An array of the offsets to the normals of the polygon. Note: there are as many offsets as normals.

Definition at line 726 of file coal/shape/geometric_shapes.h.

◆ points [1/2]

std::shared_ptr<std::vector<Vec3s> > coal::ConvexBase::points

An array of the points of the polygon.

Definition at line 719 of file coal/shape/geometric_shapes.h.

◆ points [2/2]

std::vector<Vec3s> coal::ConvexBase::SupportWarmStartPolytope::points

Array of support points to warm start the support function computation.

Definition at line 745 of file coal/shape/geometric_shapes.h.

◆ radii

Vec3s coal::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 318 of file coal/shape/geometric_shapes.h.

◆ radius [1/4]

CoalScalar coal::Sphere::radius

Radius of the sphere.

Definition at line 250 of file coal/shape/geometric_shapes.h.

◆ radius [2/4]

CoalScalar coal::Capsule::radius

Radius of capsule.

Definition at line 396 of file coal/shape/geometric_shapes.h.

◆ radius [3/4]

CoalScalar coal::Cone::radius

Radius of the cone.

Definition at line 480 of file coal/shape/geometric_shapes.h.

◆ radius [4/4]

CoalScalar coal::Cylinder::radius

Radius of the cylinder.

Definition at line 581 of file coal/shape/geometric_shapes.h.

◆ support_warm_starts

SupportWarmStartPolytope coal::ConvexBase::support_warm_starts

Support warm start polytopes.

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



hpp-fcl
Author(s):
autogenerated on Sat Nov 23 2024 03:44:59