Namespaces | Macros | Functions
support_functions.cpp File Reference
#include "coal/narrowphase/support_functions.h"
#include <algorithm>
Include dependency graph for support_functions.cpp:

Go to the source code of this file.

Namespaces

 coal
 Main namespace.
 
 coal::details
 

Macros

#define CALL_GET_SHAPE_SUPPORT(ShapeType)
 
#define CALL_GET_SHAPE_SUPPORT_SET(ShapeType)
 
#define getShapeSupportSetTplInstantiation(ShapeType)
 
#define getShapeSupportTplInstantiation(ShapeType)
 

Functions

COAL_DLLAPI void coal::details::computeSupportSetConvexHull (SupportSet::Polygon &cloud, SupportSet::Polygon &cvx_hull)
 Computes the convex-hull of support_set. For now, this function is only needed for Box and ConvexBase. More...
 
template<int _SupportOptions>
void coal::details::convexSupportSetRecurse (const std::vector< Vec3s > &points, const std::vector< ConvexBase::Neighbors > &neighbors, const CoalScalar swept_sphere_radius, const size_t vertex_idx, const Vec3s &support_dir, const CoalScalar support_value, const Transform3s &tf, std::vector< int8_t > &visited, SupportSet::Polygon &polygon, CoalScalar tol)
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupport (const Box *box, const Vec3s &dir, Vec3s &support, int &, ShapeSupportData &)
 Box support function. More...
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupport (const Capsule *capsule, const Vec3s &dir, Vec3s &support, int &, ShapeSupportData &)
 Capsule support function. More...
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupport (const Cone *cone, const Vec3s &dir, Vec3s &support, int &, ShapeSupportData &)
 Cone support function. More...
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupport (const ConvexBase *convex, const Vec3s &dir, Vec3s &support, int &hint, ShapeSupportData &)
 ConvexBase support function. More...
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupport (const Cylinder *cylinder, const Vec3s &dir, Vec3s &support, int &, ShapeSupportData &)
 Cylinder support function. More...
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupport (const Ellipsoid *ellipsoid, const Vec3s &dir, Vec3s &support, int &, ShapeSupportData &)
 Ellipsoid support function. More...
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupport (const LargeConvex *convex, const Vec3s &dir, Vec3s &support, int &hint, ShapeSupportData &support_data)
 Support function for small ConvexBase (<32 vertices). More...
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupport (const SmallConvex *convex, const Vec3s &dir, Vec3s &support, int &hint, ShapeSupportData &data)
 Support function for large ConvexBase (>32 vertices). More...
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupport (const Sphere *sphere, const Vec3s &dir, Vec3s &support, int &, ShapeSupportData &)
 Sphere support function. More...
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupport (const TriangleP *triangle, const Vec3s &dir, Vec3s &support, int &, ShapeSupportData &)
 Triangle support function. More...
 
template<int _SupportOptions>
void coal::details::getShapeSupportLinear (const ConvexBase *convex, const Vec3s &dir, Vec3s &support, int &hint, ShapeSupportData &)
 
template<int _SupportOptions>
void coal::details::getShapeSupportLog (const ConvexBase *convex, const Vec3s &dir, Vec3s &support, int &hint, ShapeSupportData &support_data)
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupportSet (const Box *box, SupportSet &support_set, int &, ShapeSupportData &support_data, size_t num_sampled_supports=6, CoalScalar tol=1e-3)
 Box support set function. Assumes the support set frame has already been computed. More...
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupportSet (const Capsule *capsule, SupportSet &support_set, int &, ShapeSupportData &, size_t num_sampled_supports=6, CoalScalar tol=1e-3)
 Capsule support set function. Assumes the support set frame has already been computed. More...
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupportSet (const Cone *cone, SupportSet &support_set, int &, ShapeSupportData &, size_t num_sampled_supports=6, CoalScalar tol=1e-3)
 Cone support set function. Assumes the support set frame has already been computed. More...
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupportSet (const ConvexBase *convex, SupportSet &support_set, int &hint, ShapeSupportData &support_data, size_t num_sampled_supports=6, CoalScalar tol=1e-3)
 ConvexBase support set function. Assumes the support set frame has already been computed. More...
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupportSet (const Cylinder *cylinder, SupportSet &support_set, int &, ShapeSupportData &, size_t num_sampled_supports=6, CoalScalar tol=1e-3)
 Cylinder support set function. Assumes the support set frame has already been computed. More...
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupportSet (const Ellipsoid *ellipsoid, SupportSet &support_set, int &, ShapeSupportData &, size_t num_sampled_supports=6, CoalScalar tol=1e-3)
 Ellipsoid support set function. Assumes the support set frame has already been computed. More...
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupportSet (const LargeConvex *convex, SupportSet &support_set, int &hint, ShapeSupportData &support_data, size_t num_sampled_supports=6, CoalScalar tol=1e-3)
 Support set function for small ConvexBase (<32 vertices). Assumes the support set frame has already been computed. More...
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupportSet (const SmallConvex *convex, SupportSet &support_set, int &, ShapeSupportData &, size_t num_sampled_supports=6, CoalScalar tol=1e-3)
 Support set function for large ConvexBase (>32 vertices). Assumes the support set frame has already been computed. More...
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupportSet (const Sphere *sphere, SupportSet &support_set, int &, ShapeSupportData &, size_t num_sampled_supports=6, CoalScalar tol=1e-3)
 Sphere support set function. Assumes the support set frame has already been computed. More...
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupportSet (const TriangleP *triangle, SupportSet &support_set, int &, ShapeSupportData &, size_t num_sampled_supports=6, CoalScalar tol=1e-3)
 Triangle support set function. Assumes the support set frame has already been computed. More...
 
template<int _SupportOptions>
void coal::details::getShapeSupportSetLinear (const ConvexBase *convex, SupportSet &support_set, int &hint, ShapeSupportData &support_data, size_t, CoalScalar tol)
 
template<int _SupportOptions>
void coal::details::getShapeSupportSetLog (const ConvexBase *convex, SupportSet &support_set, int &hint, ShapeSupportData &support_data, size_t, CoalScalar tol)
 
 coal::details::getShapeSupportSetTplInstantiation (Box)
 
 coal::details::getShapeSupportSetTplInstantiation (Capsule)
 
 coal::details::getShapeSupportSetTplInstantiation (Cone)
 
 coal::details::getShapeSupportSetTplInstantiation (ConvexBase)
 
 coal::details::getShapeSupportSetTplInstantiation (Cylinder)
 
 coal::details::getShapeSupportSetTplInstantiation (Ellipsoid)
 
 coal::details::getShapeSupportSetTplInstantiation (LargeConvex)
 
 coal::details::getShapeSupportSetTplInstantiation (SmallConvex)
 
 coal::details::getShapeSupportSetTplInstantiation (Sphere)
 
 coal::details::getShapeSupportSetTplInstantiation (TriangleP)
 
 coal::details::getShapeSupportTplInstantiation (Box)
 
 coal::details::getShapeSupportTplInstantiation (Capsule)
 
 coal::details::getShapeSupportTplInstantiation (Cone)
 
 coal::details::getShapeSupportTplInstantiation (ConvexBase)
 
 coal::details::getShapeSupportTplInstantiation (Cylinder)
 
 coal::details::getShapeSupportTplInstantiation (Ellipsoid)
 
 coal::details::getShapeSupportTplInstantiation (LargeConvex)
 
 coal::details::getShapeSupportTplInstantiation (SmallConvex)
 
 coal::details::getShapeSupportTplInstantiation (Sphere)
 
 coal::details::getShapeSupportTplInstantiation (TriangleP)
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
Vec3s coal::details::getSupport (const ShapeBase *shape, const Vec3s &dir, int &hint)
 the support function for shape. The output support point is expressed in the local frame of the shape. More...
 
template COAL_DLLAPI Vec3s coal::details::getSupport< SupportOptions::NoSweptSphere > (const ShapeBase *, const Vec3s &, int &)
 
template COAL_DLLAPI Vec3s coal::details::getSupport< SupportOptions::WithSweptSphere > (const ShapeBase *, const Vec3s &, int &)
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getSupportSet (const ShapeBase *shape, SupportSet &support_set, int &hint, size_t num_sampled_supports=6, CoalScalar tol=1e-3)
 Computes the support set for shape. This function assumes the frame of the support set has already been computed and that this frame is expressed w.r.t the local frame of the shape (i.e. the local frame of the shape is the WORLD frame of the support set). The support direction used to compute the support set is the positive z-axis if the support set has the DEFAULT direction; negative z-axis if it has the INVERTED direction. (In short, a shape's support set is has the DEFAULT direction if the shape is the first shape in a collision pair. It has the INVERTED direction if the shape is the second one in the collision pair). More...
 
template COAL_DLLAPI void coal::details::getSupportSet< SupportOptions::NoSweptSphere > (const ShapeBase *, SupportSet &, int &, size_t, CoalScalar)
 
template COAL_DLLAPI void coal::details::getSupportSet< SupportOptions::WithSweptSphere > (const ShapeBase *, SupportSet &, int &, size_t, CoalScalar)
 

Macro Definition Documentation

◆ CALL_GET_SHAPE_SUPPORT

#define CALL_GET_SHAPE_SUPPORT (   ShapeType)
Value:
getShapeSupport<_SupportOptions>(static_cast<const ShapeType*>(shape), dir, \
support, hint, support_data)

Definition at line 47 of file support_functions.cpp.

◆ CALL_GET_SHAPE_SUPPORT_SET

#define CALL_GET_SHAPE_SUPPORT_SET (   ShapeType)
Value:
getShapeSupportSet<_SupportOptions>(static_cast<const ShapeType*>(shape), \
support_set, hint, support_data, \
max_num_supports, tol)

Definition at line 445 of file support_functions.cpp.

◆ getShapeSupportSetTplInstantiation

#define getShapeSupportSetTplInstantiation (   ShapeType)
Value:
template COAL_DLLAPI void getShapeSupportSet<SupportOptions::NoSweptSphere>( \
const ShapeType* shape_, SupportSet& support_set, int& hint, \
ShapeSupportData& data, size_t num_sampled_supports, CoalScalar tol); \
\
template COAL_DLLAPI void \
getShapeSupportSet<SupportOptions::WithSweptSphere>( \
const ShapeType* shape_, SupportSet& support_set, int& hint, \
ShapeSupportData& data, size_t num_sampled_supports, CoalScalar tol);

Definition at line 493 of file support_functions.cpp.

◆ getShapeSupportTplInstantiation

#define getShapeSupportTplInstantiation (   ShapeType)
Value:
template COAL_DLLAPI void getShapeSupport<SupportOptions::NoSweptSphere>( \
const ShapeType* shape_, const Vec3s& dir, Vec3s& support, int& hint, \
ShapeSupportData& support_data); \
\
template COAL_DLLAPI void getShapeSupport<SupportOptions::WithSweptSphere>( \
const ShapeType* shape_, const Vec3s& dir, Vec3s& support, int& hint, \
ShapeSupportData& support_data);

Definition at line 98 of file support_functions.cpp.

coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
coal::SupportSet
ContactPatch SupportSet
Structure used for internal computations. A support set and a contact patch can be represented by the...
Definition: coal/collision_data.h:721
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76


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