Namespaces | Classes | Enumerations | Functions
coal::details Namespace Reference

Namespaces

 details
 

Classes

struct  bvh_shape_traits
 
struct  EPA
 class for EPA algorithm More...
 
struct  GJK
 class for GJK algorithm More...
 
struct  LargeConvex
 Cast a ConvexBase to a LargeConvex to use the log version of getShapeSupport. This is much faster than the linear version of getShapeSupport when a ConvexBase has more than a few dozen of vertices. More...
 
struct  MinkowskiDiff
 Minkowski difference class of two shapes. More...
 
struct  ShapeSupportData
 Stores temporary data for the computation of support points. More...
 
struct  SmallConvex
 See LargeConvex. More...
 
struct  UpdateBoundingVolume
 
struct  UpdateBoundingVolume< AABB >
 

Enumerations

enum  SupportOptions { NoSweptSphere = 0, WithSweptSphere = 0x1 }
 Options for the computation of support points. NoSweptSphere option is used when the support function is called by GJK or EPA. In this case, the swept sphere radius is not taken into account in the support function. It is used by GJK and EPA after they have converged to correct the solution. WithSweptSphere option is used when the support function is called directly by the user. In this case, the swept sphere radius is taken into account in the support function. More...
 

Functions

CoalScalar boxSphereDistance (const Box &b, const Transform3s &tfb, const Sphere &s, const Transform3s &tfs, Vec3s &pb, Vec3s &ps, Vec3s &normal)
 
 BVH_SHAPE_DEFAULT_TO_ORIENTED (kIOS)
 
 BVH_SHAPE_DEFAULT_TO_ORIENTED (OBB)
 
 BVH_SHAPE_DEFAULT_TO_ORIENTED (OBBRSS)
 
 BVH_SHAPE_DEFAULT_TO_ORIENTED (RSS)
 
template<typename BV >
BVHModel< BV > * BVHExtract (const BVHModel< BV > &model, const Transform3s &pose, const AABB &_aabb)
 Extract the part of the BVHModel that is inside an AABB. A triangle in collision with the AABB is considered inside. More...
 
CoalScalar computePenetration (const Vec3s &P1, const Vec3s &P2, const Vec3s &P3, const Vec3s &Q1, const Vec3s &Q2, const Vec3s &Q3, const Transform3s &tf1, const Transform3s &tf2, Vec3s &normal)
 
CoalScalar computePenetration (const Vec3s &P1, const Vec3s &P2, const Vec3s &P3, const Vec3s &Q1, const Vec3s &Q2, const Vec3s &Q3, Vec3s &normal)
 See the prototype below. More...
 
COAL_DLLAPI void 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 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)
 
CollisionGeometryextractBVH (const CollisionGeometry *model, const Transform3s &pose, const AABB &aabb)
 
template<typename NT >
CollisionGeometryextractBVHtpl (const CollisionGeometry *model, const Transform3s &pose, const AABB &aabb)
 
std::vector< Vec3sgetBoundVertices (const Box &box, const Transform3s &tf)
 
std::vector< Vec3sgetBoundVertices (const Capsule &capsule, const Transform3s &tf)
 
std::vector< Vec3sgetBoundVertices (const Cone &cone, const Transform3s &tf)
 
std::vector< Vec3sgetBoundVertices (const ConvexBase &convex, const Transform3s &tf)
 
std::vector< Vec3sgetBoundVertices (const Cylinder &cylinder, const Transform3s &tf)
 
std::vector< Vec3sgetBoundVertices (const Ellipsoid &ellipsoid, const Transform3s &tf)
 
std::vector< Vec3sgetBoundVertices (const Sphere &sphere, const Transform3s &tf)
 
std::vector< Vec3sgetBoundVertices (const TriangleP &triangle, const Transform3s &tf)
 
bool getNormalizeSupportDirection (const ShapeBase *shape)
 
void getNormalizeSupportDirectionFromShapes (const ShapeBase *shape0, const ShapeBase *shape1, bool &normalize_support_direction)
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void getShapeSupport (const Box *box, const Vec3s &dir, Vec3s &support, int &, ShapeSupportData &)
 Box support function. More...
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void getShapeSupport (const Capsule *capsule, const Vec3s &dir, Vec3s &support, int &, ShapeSupportData &)
 Capsule support function. More...
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void getShapeSupport (const Cone *cone, const Vec3s &dir, Vec3s &support, int &, ShapeSupportData &)
 Cone support function. More...
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void getShapeSupport (const ConvexBase *convex, const Vec3s &dir, Vec3s &support, int &hint, ShapeSupportData &)
 ConvexBase support function. More...
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void getShapeSupport (const Cylinder *cylinder, const Vec3s &dir, Vec3s &support, int &, ShapeSupportData &)
 Cylinder support function. More...
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void getShapeSupport (const Ellipsoid *ellipsoid, const Vec3s &dir, Vec3s &support, int &, ShapeSupportData &)
 Ellipsoid support function. More...
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void 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 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 getShapeSupport (const Sphere *sphere, const Vec3s &dir, Vec3s &support, int &, ShapeSupportData &)
 Sphere support function. More...
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void getShapeSupport (const TriangleP *triangle, const Vec3s &dir, Vec3s &support, int &, ShapeSupportData &)
 Triangle support function. More...
 
template<int _SupportOptions>
void getShapeSupportLinear (const ConvexBase *convex, const Vec3s &dir, Vec3s &support, int &hint, ShapeSupportData &)
 
template<int _SupportOptions>
void getShapeSupportLog (const ConvexBase *convex, const Vec3s &dir, Vec3s &support, int &hint, ShapeSupportData &support_data)
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void 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 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 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 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 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 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 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 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 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 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 getShapeSupportSetLinear (const ConvexBase *convex, SupportSet &support_set, int &hint, ShapeSupportData &support_data, size_t, CoalScalar tol)
 
template<int _SupportOptions>
void getShapeSupportSetLog (const ConvexBase *convex, SupportSet &support_set, int &hint, ShapeSupportData &support_data, size_t, CoalScalar tol)
 
template<typename ShapeType , int _SupportOptions = SupportOptions::NoSweptSphere>
void getShapeSupportSetTpl (const ShapeBase *shape, SupportSet &support_set, int &hint, ShapeSupportData &support_data, size_t num_sampled_supports=6, CoalScalar tol=1e-3)
 Templated shape support set functions. More...
 
 getShapeSupportSetTplInstantiation (Box)
 
 getShapeSupportSetTplInstantiation (Capsule)
 
 getShapeSupportSetTplInstantiation (Cone)
 
 getShapeSupportSetTplInstantiation (ConvexBase)
 
 getShapeSupportSetTplInstantiation (Cylinder)
 
 getShapeSupportSetTplInstantiation (Ellipsoid)
 
 getShapeSupportSetTplInstantiation (LargeConvex)
 
 getShapeSupportSetTplInstantiation (SmallConvex)
 
 getShapeSupportSetTplInstantiation (Sphere)
 
 getShapeSupportSetTplInstantiation (TriangleP)
 
 getShapeSupportTplInstantiation (Box)
 
 getShapeSupportTplInstantiation (Capsule)
 
 getShapeSupportTplInstantiation (Cone)
 
 getShapeSupportTplInstantiation (ConvexBase)
 
 getShapeSupportTplInstantiation (Cylinder)
 
 getShapeSupportTplInstantiation (Ellipsoid)
 
 getShapeSupportTplInstantiation (LargeConvex)
 
 getShapeSupportTplInstantiation (SmallConvex)
 
 getShapeSupportTplInstantiation (Sphere)
 
 getShapeSupportTplInstantiation (TriangleP)
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
Vec3s 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 getSupport< SupportOptions::NoSweptSphere > (const ShapeBase *, const Vec3s &, int &)
 
template COAL_DLLAPI Vec3s getSupport< SupportOptions::WithSweptSphere > (const ShapeBase *, const Vec3s &, int &)
 
template<typename Shape0 , typename Shape1 , bool TransformIsIdentity, int _SupportOptions>
void getSupportFuncTpl (const MinkowskiDiff &md, const Vec3s &dir, Vec3s &support0, Vec3s &support1, support_func_guess_t &hint, ShapeSupportData data[2])
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void getSupportSet (const ShapeBase *shape, const Vec3s &dir, SupportSet &support_set, int &hint, size_t num_sampled_supports=6, CoalScalar tol=1e-3)
 Same as getSupportSet(const ShapeBase*, const CoalScalar, SupportSet&, const int) but also constructs the support set frame from dir. More...
 
template<int _SupportOptions = SupportOptions::NoSweptSphere>
void 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 getSupportSet< SupportOptions::NoSweptSphere > (const ShapeBase *, SupportSet &, int &, size_t, CoalScalar)
 
template COAL_DLLAPI void getSupportSet< SupportOptions::WithSweptSphere > (const ShapeBase *, SupportSet &, int &, size_t, CoalScalar)
 
template<typename Shape0 , typename Shape1 , bool TransformIsIdentity, int _SupportOptions>
void getSupportTpl (const Shape0 *s0, const Shape1 *s1, const Matrix3s &oR1, const Vec3s &ot1, const Vec3s &dir, Vec3s &support0, Vec3s &support1, support_func_guess_t &hint, ShapeSupportData data[2])
 
CoalScalar halfspaceDistance (const Halfspace &h, const Transform3s &tf1, const ShapeBase &s, const Transform3s &tf2, Vec3s &p1, Vec3s &p2, Vec3s &normal)
 
CoalScalar halfspaceHalfspaceDistance (const Halfspace &s1, const Transform3s &tf1, const Halfspace &s2, const Transform3s &tf2, Vec3s &p1, Vec3s &p2, Vec3s &normal)
 return distance between two halfspaces More...
 
CoalScalar halfspacePlaneDistance (const Halfspace &s1, const Transform3s &tf1, const Plane &s2, const Transform3s &tf2, Vec3s &p1, Vec3s &p2, Vec3s &normal)
 return distance between plane and halfspace. More...
 
static void lineSegmentPointClosestToPoint (const Vec3s &p, const Vec3s &s1, const Vec3s &s2, Vec3s &sp)
 
template<int _SupportOptions>
MinkowskiDiff::GetSupportFunction makeGetSupportFunction0 (const ShapeBase *s0, const ShapeBase *s1, bool identity, Eigen::Array< CoalScalar, 1, 2 > &swept_sphere_radius, ShapeSupportData data[2])
 
template<typename Shape0 , int _SupportOptions>
MinkowskiDiff::GetSupportFunction makeGetSupportFunction1 (const ShapeBase *s1, bool identity, Eigen::Array< CoalScalar, 1, 2 > &swept_sphere_radius, ShapeSupportData data[2])
 
template void COAL_DLLAPI MinkowskiDiff::set< SupportOptions::NoSweptSphere > (const ShapeBase *, const ShapeBase *)
 
template void COAL_DLLAPI MinkowskiDiff::set< SupportOptions::NoSweptSphere > (const ShapeBase *, const ShapeBase *, const Transform3s &, const Transform3s &)
 
template void COAL_DLLAPI MinkowskiDiff::set< SupportOptions::WithSweptSphere > (const ShapeBase *, const ShapeBase *)
 
template void COAL_DLLAPI MinkowskiDiff::set< SupportOptions::WithSweptSphere > (const ShapeBase *, const ShapeBase *, const Transform3s &, const Transform3s &)
 
template Vec3s COAL_DLLAPI MinkowskiDiff::support0< SupportOptions::NoSweptSphere > (const Vec3s &, int &) const
 
template Vec3s COAL_DLLAPI MinkowskiDiff::support0< SupportOptions::WithSweptSphere > (const Vec3s &, int &) const
 
template Vec3s COAL_DLLAPI MinkowskiDiff::support1< SupportOptions::NoSweptSphere > (const Vec3s &, int &) const
 
template Vec3s COAL_DLLAPI MinkowskiDiff::support1< SupportOptions::WithSweptSphere > (const Vec3s &, int &) const
 
template<typename OrientedMeshShapeDistanceTraversalNode , typename T_BVH , typename T_SH >
CoalScalar orientedBVHShapeDistance (const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const GJKSolver *nsolver, const DistanceRequest &request, DistanceResult &result)
 
template<typename OrientedMeshCollisionTraversalNode , typename T_BVH >
std::size_t orientedMeshCollide (const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const CollisionRequest &request, CollisionResult &result)
 
template<typename OrientedMeshDistanceTraversalNode , typename T_BVH >
CoalScalar orientedMeshDistance (const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const DistanceRequest &request, DistanceResult &result)
 
void originToPoint (const GJK::Simplex &current, GJK::vertex_id_t a, const Vec3s &A, GJK::Simplex &next, Vec3s &ray)
 
void originToSegment (const GJK::Simplex &current, GJK::vertex_id_t a, GJK::vertex_id_t b, const Vec3s &A, const Vec3s &B, const Vec3s &AB, const CoalScalar &ABdotAO, GJK::Simplex &next, Vec3s &ray)
 
bool originToTriangle (const GJK::Simplex &current, GJK::vertex_id_t a, GJK::vertex_id_t b, GJK::vertex_id_t c, const Vec3s &ABC, const CoalScalar &ABCdotAO, GJK::Simplex &next, Vec3s &ray)
 
CoalScalar planeDistance (const Plane &plane, const Transform3s &tf1, const ShapeBase &s, const Transform3s &tf2, Vec3s &p1, Vec3s &p2, Vec3s &normal)
 
CoalScalar planePlaneDistance (const Plane &s1, const Transform3s &tf1, const Plane &s2, const Transform3s &tf2, Vec3s &p1, Vec3s &p2, Vec3s &normal)
 return distance between two planes More...
 
bool projectInTriangle (const Vec3s &p1, const Vec3s &p2, const Vec3s &p3, const Vec3s &normal, const Vec3s &p)
 Whether a point's projection is in a triangle. More...
 
CoalScalar segmentSqrDistance (const Vec3s &from, const Vec3s &to, const Vec3s &p, Vec3s &nearest)
 the minimum distance from a point to a line More...
 
CoalScalar sphereCapsuleDistance (const Sphere &s1, const Transform3s &tf1, const Capsule &s2, const Transform3s &tf2, Vec3s &p1, Vec3s &p2, Vec3s &normal)
 
CoalScalar sphereCylinderDistance (const Sphere &s1, const Transform3s &tf1, const Cylinder &s2, const Transform3s &tf2, Vec3s &p1, Vec3s &p2, Vec3s &normal)
 
CoalScalar sphereSphereDistance (const Sphere &s1, const Transform3s &tf1, const Sphere &s2, const Transform3s &tf2, Vec3s &p1, Vec3s &p2, Vec3s &normal)
 
CoalScalar sphereTriangleDistance (const Sphere &s, const Transform3s &tf1, const TriangleP &tri, const Transform3s &tf2, Vec3s &p1, Vec3s &p2, Vec3s &normal)
 

Enumeration Type Documentation

◆ SupportOptions

Options for the computation of support points. NoSweptSphere option is used when the support function is called by GJK or EPA. In this case, the swept sphere radius is not taken into account in the support function. It is used by GJK and EPA after they have converged to correct the solution. WithSweptSphere option is used when the support function is called directly by the user. In this case, the swept sphere radius is taken into account in the support function.

Enumerator
NoSweptSphere 
WithSweptSphere 

Definition at line 58 of file coal/narrowphase/support_functions.h.

Function Documentation

◆ boxSphereDistance()

CoalScalar coal::details::boxSphereDistance ( const Box b,
const Transform3s tfb,
const Sphere s,
const Transform3s tfs,
Vec3s pb,
Vec3s ps,
Vec3s normal 
)
inline

Taken from book Real Time Collision Detection, from Christer Ericson

Parameters
pbthe witness point on the box surface
psthe witness point on the sphere.
normalpointing from box to sphere
Returns
the distance between the two shapes (negative if penetration).

Definition at line 438 of file details.h.

◆ BVH_SHAPE_DEFAULT_TO_ORIENTED() [1/4]

coal::details::BVH_SHAPE_DEFAULT_TO_ORIENTED ( kIOS  )

◆ BVH_SHAPE_DEFAULT_TO_ORIENTED() [2/4]

coal::details::BVH_SHAPE_DEFAULT_TO_ORIENTED ( OBB  )

◆ BVH_SHAPE_DEFAULT_TO_ORIENTED() [3/4]

coal::details::BVH_SHAPE_DEFAULT_TO_ORIENTED ( OBBRSS  )

◆ BVH_SHAPE_DEFAULT_TO_ORIENTED() [4/4]

coal::details::BVH_SHAPE_DEFAULT_TO_ORIENTED ( RSS  )

◆ BVHExtract()

template<typename BV >
BVHModel<BV>* coal::details::BVHExtract ( const BVHModel< BV > &  model,
const Transform3s pose,
const AABB _aabb 
)

Extract the part of the BVHModel that is inside an AABB. A triangle in collision with the AABB is considered inside.

Definition at line 47 of file BVH_utility.cpp.

◆ computePenetration() [1/2]

CoalScalar coal::details::computePenetration ( const Vec3s P1,
const Vec3s P2,
const Vec3s P3,
const Vec3s Q1,
const Vec3s Q2,
const Vec3s Q3,
const Transform3s tf1,
const Transform3s tf2,
Vec3s normal 
)
inline

Definition at line 722 of file details.h.

◆ computePenetration() [2/2]

CoalScalar coal::details::computePenetration ( const Vec3s P1,
const Vec3s P2,
const Vec3s P3,
const Vec3s Q1,
const Vec3s Q2,
const Vec3s Q3,
Vec3s normal 
)
inline

See the prototype below.

Definition at line 703 of file details.h.

◆ computeSupportSetConvexHull()

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.

Parameters
[in]clouddata which contains the 2d points of the support set which convex-hull we want to compute.
[out]2dpoints of the the support set's convex-hull.

Definition at line 952 of file support_functions.cpp.

◆ convexSupportSetRecurse()

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 
)

Definition at line 838 of file support_functions.cpp.

◆ extractBVH()

CollisionGeometry* coal::details::extractBVH ( const CollisionGeometry model,
const Transform3s pose,
const AABB aabb 
)

Definition at line 41 of file collision_utility.cpp.

◆ extractBVHtpl()

template<typename NT >
CollisionGeometry* coal::details::extractBVHtpl ( const CollisionGeometry model,
const Transform3s pose,
const AABB aabb 
)
inline

Definition at line 24 of file collision_utility.cpp.

◆ getBoundVertices() [1/8]

std::vector<Vec3s> coal::details::getBoundVertices ( const Box box,
const Transform3s tf 
)

Definition at line 46 of file geometric_shapes_utility.cpp.

◆ getBoundVertices() [2/8]

std::vector<Vec3s> coal::details::getBoundVertices ( const Capsule capsule,
const Transform3s tf 
)

Definition at line 123 of file geometric_shapes_utility.cpp.

◆ getBoundVertices() [3/8]

std::vector<Vec3s> coal::details::getBoundVertices ( const Cone cone,
const Transform3s tf 
)

Definition at line 179 of file geometric_shapes_utility.cpp.

◆ getBoundVertices() [4/8]

std::vector<Vec3s> coal::details::getBoundVertices ( const ConvexBase convex,
const Transform3s tf 
)

Definition at line 225 of file geometric_shapes_utility.cpp.

◆ getBoundVertices() [5/8]

std::vector<Vec3s> coal::details::getBoundVertices ( const Cylinder cylinder,
const Transform3s tf 
)

Definition at line 199 of file geometric_shapes_utility.cpp.

◆ getBoundVertices() [6/8]

std::vector<Vec3s> coal::details::getBoundVertices ( const Ellipsoid ellipsoid,
const Transform3s tf 
)

Definition at line 89 of file geometric_shapes_utility.cpp.

◆ getBoundVertices() [7/8]

std::vector<Vec3s> coal::details::getBoundVertices ( const Sphere sphere,
const Transform3s tf 
)

Definition at line 64 of file geometric_shapes_utility.cpp.

◆ getBoundVertices() [8/8]

std::vector<Vec3s> coal::details::getBoundVertices ( const TriangleP triangle,
const Transform3s tf 
)

Definition at line 236 of file geometric_shapes_utility.cpp.

◆ getNormalizeSupportDirection()

bool coal::details::getNormalizeSupportDirection ( const ShapeBase shape)

Definition at line 228 of file minkowski_difference.cpp.

◆ getNormalizeSupportDirectionFromShapes()

void coal::details::getNormalizeSupportDirectionFromShapes ( const ShapeBase shape0,
const ShapeBase shape1,
bool &  normalize_support_direction 
)

Definition at line 260 of file minkowski_difference.cpp.

◆ getShapeSupport() [1/10]

template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupport ( const Box box,
const Vec3s dir,
Vec3s support,
int &  ,
ShapeSupportData  
)
inline

Box support function.

Definition at line 137 of file support_functions.cpp.

◆ getShapeSupport() [2/10]

template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupport ( const Capsule capsule,
const Vec3s dir,
Vec3s support,
int &  ,
ShapeSupportData  
)
inline

Capsule support function.

Definition at line 195 of file support_functions.cpp.

◆ getShapeSupport() [3/10]

template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupport ( const Cone cone,
const Vec3s dir,
Vec3s support,
int &  ,
ShapeSupportData  
)

Cone support function.

Definition at line 216 of file support_functions.cpp.

◆ getShapeSupport() [4/10]

template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupport ( const ConvexBase convex,
const Vec3s dir,
Vec3s support,
int &  hint,
ShapeSupportData support_data 
)

ConvexBase support function.

Note
See LargeConvex and SmallConvex to see how to optimize ConvexBase's support computation.

Definition at line 407 of file support_functions.cpp.

◆ getShapeSupport() [5/10]

template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupport ( const Cylinder cylinder,
const Vec3s dir,
Vec3s support,
int &  ,
ShapeSupportData  
)

Cylinder support function.

Definition at line 266 of file support_functions.cpp.

◆ getShapeSupport() [6/10]

template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupport ( const Ellipsoid ellipsoid,
const Vec3s dir,
Vec3s support,
int &  ,
ShapeSupportData  
)
inline

Ellipsoid support function.

Definition at line 174 of file support_functions.cpp.

◆ getShapeSupport() [7/10]

template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupport ( const LargeConvex convex,
const Vec3s dir,
Vec3s support,
int &  hint,
ShapeSupportData support_data 
)
inline

Support function for small ConvexBase (<32 vertices).

Definition at line 435 of file support_functions.cpp.

◆ getShapeSupport() [8/10]

template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupport ( const SmallConvex convex,
const Vec3s dir,
Vec3s support,
int &  hint,
ShapeSupportData data 
)
inline

Support function for large ConvexBase (>32 vertices).

Definition at line 424 of file support_functions.cpp.

◆ getShapeSupport() [9/10]

template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupport ( const Sphere sphere,
const Vec3s dir,
Vec3s support,
int &  ,
ShapeSupportData  
)
inline

Sphere support function.

Definition at line 157 of file support_functions.cpp.

◆ getShapeSupport() [10/10]

template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupport ( const TriangleP triangle,
const Vec3s dir,
Vec3s support,
int &  ,
ShapeSupportData  
)

Triangle support function.

Definition at line 109 of file support_functions.cpp.

◆ getShapeSupportLinear()

template<int _SupportOptions>
void coal::details::getShapeSupportLinear ( const ConvexBase convex,
const Vec3s dir,
Vec3s support,
int &  hint,
ShapeSupportData  
)

Definition at line 383 of file support_functions.cpp.

◆ getShapeSupportLog()

template<int _SupportOptions>
void coal::details::getShapeSupportLog ( const ConvexBase convex,
const Vec3s dir,
Vec3s support,
int &  hint,
ShapeSupportData support_data 
)

Definition at line 306 of file support_functions.cpp.

◆ getShapeSupportSet() [1/10]

template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupportSet ( const Box box,
SupportSet support_set,
int &  hint,
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.

Definition at line 552 of file support_functions.cpp.

◆ getShapeSupportSet() [2/10]

template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupportSet ( const Capsule capsule,
SupportSet support_set,
int &  hint,
ShapeSupportData support_data,
size_t  num_sampled_supports = 6,
CoalScalar  tol = 1e-3 
)

Capsule support set function. Assumes the support set frame has already been computed.

Definition at line 625 of file support_functions.cpp.

◆ getShapeSupportSet() [3/10]

template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupportSet ( const Cone cone,
SupportSet support_set,
int &  hint,
ShapeSupportData support_data,
size_t  num_sampled_supports = 6,
CoalScalar  tol = 1e-3 
)

Cone support set function. Assumes the support set frame has already been computed.

Definition at line 669 of file support_functions.cpp.

◆ getShapeSupportSet() [4/10]

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.

Note
See LargeConvex and SmallConvex to see how to optimize ConvexBase's support computation.

Definition at line 910 of file support_functions.cpp.

◆ getShapeSupportSet() [5/10]

template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupportSet ( const Cylinder cylinder,
SupportSet support_set,
int &  hint,
ShapeSupportData support_data,
size_t  num_sampled_supports = 6,
CoalScalar  tol = 1e-3 
)

Cylinder support set function. Assumes the support set frame has already been computed.

Definition at line 740 of file support_functions.cpp.

◆ getShapeSupportSet() [6/10]

template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupportSet ( const Ellipsoid ellipsoid,
SupportSet support_set,
int &  hint,
ShapeSupportData support_data,
size_t  num_sampled_supports = 6,
CoalScalar  tol = 1e-3 
)

Ellipsoid support set function. Assumes the support set frame has already been computed.

Definition at line 610 of file support_functions.cpp.

◆ getShapeSupportSet() [7/10]

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.

Definition at line 940 of file support_functions.cpp.

◆ getShapeSupportSet() [8/10]

template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupportSet ( const SmallConvex convex,
SupportSet support_set,
int &  hint,
ShapeSupportData support_data,
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.

Definition at line 927 of file support_functions.cpp.

◆ getShapeSupportSet() [9/10]

template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupportSet ( const Sphere sphere,
SupportSet support_set,
int &  hint,
ShapeSupportData support_data,
size_t  num_sampled_supports = 6,
CoalScalar  tol = 1e-3 
)

Sphere support set function. Assumes the support set frame has already been computed.

Definition at line 594 of file support_functions.cpp.

◆ getShapeSupportSet() [10/10]

template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupportSet ( const TriangleP triangle,
SupportSet support_set,
int &  hint,
ShapeSupportData support_data,
size_t  num_sampled_supports = 6,
CoalScalar  tol = 1e-3 
)

Triangle support set function. Assumes the support set frame has already been computed.

Definition at line 505 of file support_functions.cpp.

◆ getShapeSupportSetLinear()

template<int _SupportOptions>
void coal::details::getShapeSupportSetLinear ( const ConvexBase convex,
SupportSet support_set,
int &  hint,
ShapeSupportData support_data,
size_t  ,
CoalScalar  tol 
)

Definition at line 802 of file support_functions.cpp.

◆ getShapeSupportSetLog()

template<int _SupportOptions>
void coal::details::getShapeSupportSetLog ( const ConvexBase convex,
SupportSet support_set,
int &  hint,
ShapeSupportData support_data,
size_t  ,
CoalScalar  tol 
)

Definition at line 878 of file support_functions.cpp.

◆ getShapeSupportSetTpl()

template<typename ShapeType , int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getShapeSupportSetTpl ( const ShapeBase shape,
SupportSet support_set,
int &  hint,
ShapeSupportData support_data,
size_t  num_sampled_supports = 6,
CoalScalar  tol = 1e-3 
)

Templated shape support set functions.

Definition at line 46 of file contact_patch_solver.cpp.

◆ getShapeSupportSetTplInstantiation() [1/10]

coal::details::getShapeSupportSetTplInstantiation ( Box  )

◆ getShapeSupportSetTplInstantiation() [2/10]

coal::details::getShapeSupportSetTplInstantiation ( Capsule  )

◆ getShapeSupportSetTplInstantiation() [3/10]

coal::details::getShapeSupportSetTplInstantiation ( Cone  )

◆ getShapeSupportSetTplInstantiation() [4/10]

coal::details::getShapeSupportSetTplInstantiation ( ConvexBase  )

◆ getShapeSupportSetTplInstantiation() [5/10]

coal::details::getShapeSupportSetTplInstantiation ( Cylinder  )

◆ getShapeSupportSetTplInstantiation() [6/10]

coal::details::getShapeSupportSetTplInstantiation ( Ellipsoid  )

◆ getShapeSupportSetTplInstantiation() [7/10]

coal::details::getShapeSupportSetTplInstantiation ( LargeConvex  )

◆ getShapeSupportSetTplInstantiation() [8/10]

coal::details::getShapeSupportSetTplInstantiation ( SmallConvex  )

◆ getShapeSupportSetTplInstantiation() [9/10]

coal::details::getShapeSupportSetTplInstantiation ( Sphere  )

◆ getShapeSupportSetTplInstantiation() [10/10]

coal::details::getShapeSupportSetTplInstantiation ( TriangleP  )

◆ getShapeSupportTplInstantiation() [1/10]

coal::details::getShapeSupportTplInstantiation ( Box  )

◆ getShapeSupportTplInstantiation() [2/10]

coal::details::getShapeSupportTplInstantiation ( Capsule  )

◆ getShapeSupportTplInstantiation() [3/10]

coal::details::getShapeSupportTplInstantiation ( Cone  )

◆ getShapeSupportTplInstantiation() [4/10]

coal::details::getShapeSupportTplInstantiation ( ConvexBase  )

◆ getShapeSupportTplInstantiation() [5/10]

coal::details::getShapeSupportTplInstantiation ( Cylinder  )

◆ getShapeSupportTplInstantiation() [6/10]

coal::details::getShapeSupportTplInstantiation ( Ellipsoid  )

◆ getShapeSupportTplInstantiation() [7/10]

coal::details::getShapeSupportTplInstantiation ( LargeConvex  )

◆ getShapeSupportTplInstantiation() [8/10]

coal::details::getShapeSupportTplInstantiation ( SmallConvex  )

◆ getShapeSupportTplInstantiation() [9/10]

coal::details::getShapeSupportTplInstantiation ( Sphere  )

◆ getShapeSupportTplInstantiation() [10/10]

coal::details::getShapeSupportTplInstantiation ( TriangleP  )

◆ getSupport()

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.

Returns
a point which belongs to the set {argmax_{v in shape} v.dot(dir)}.
Parameters
shapethe shape.
dirsupport direction.
hintused to initialize the search when shape is a ConvexBase object.
Template Parameters
SupportOptionsis a value of the SupportOptions enum. If set to WithSweptSphere, the support functions take into account the shapes' swept sphere radii. Please see MinkowskiDiff::set(const ShapeBase*, const ShapeBase*) for more details.

Definition at line 51 of file support_functions.cpp.

◆ getSupport< SupportOptions::NoSweptSphere >()

template COAL_DLLAPI Vec3s coal::details::getSupport< SupportOptions::NoSweptSphere > ( const ShapeBase ,
const Vec3s ,
int &   
)

◆ getSupport< SupportOptions::WithSweptSphere >()

template COAL_DLLAPI Vec3s coal::details::getSupport< SupportOptions::WithSweptSphere > ( const ShapeBase ,
const Vec3s ,
int &   
)

◆ getSupportFuncTpl()

template<typename Shape0 , typename Shape1 , bool TransformIsIdentity, int _SupportOptions>
void coal::details::getSupportFuncTpl ( const MinkowskiDiff md,
const Vec3s dir,
Vec3s support0,
Vec3s support1,
support_func_guess_t hint,
ShapeSupportData  data[2] 
)

Definition at line 67 of file minkowski_difference.cpp.

◆ getSupportSet() [1/2]

template<int _SupportOptions = SupportOptions::NoSweptSphere>
void coal::details::getSupportSet ( const ShapeBase shape,
const Vec3s dir,
SupportSet support_set,
int &  hint,
size_t  num_sampled_supports = 6,
CoalScalar  tol = 1e-3 
)

Same as getSupportSet(const ShapeBase*, const CoalScalar, SupportSet&, const int) but also constructs the support set frame from dir.

Note
The support direction dir is expressed in the local frame of the shape.
This function automatically deals with the direction of the SupportSet.

Definition at line 206 of file coal/narrowphase/support_functions.h.

◆ getSupportSet() [2/2]

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).

Returns
an approximation of the set {argmax_{v in shape} v.dot(dir)}, where dir is the support set's support direction. The support set is a plane passing by the origin of the support set frame and supported by the direction dir. As a consequence, any point added to the set is automatically projected onto this plane.
Parameters
[in]shapethe shape.
[in/out]support_set of shape.
[in/out]hint used to initialize the search when shape is a ConvexBase object.
[in]num_sampled_supportsis only used for shapes with smooth non-strictly convex bases like cones and cylinders (their bases are circles). In such a case, if the support direction points to their base, we have to choose which points we want to add to the set. This is not needed for boxes or ConvexBase for example. Indeed, because their support sets are always polygons, we can characterize the entire support set with the vertices of the polygon.
[in]tolgiven a point v on the shape, if max_{p in shape}(p.dot(dir)) - v.dot(dir) <= tol, where dir is the set's support direction, then v is added to the support set. Otherwise said, if a point p of the shape is at a distance tol from the support plane, it is added to the set. Thus, tol can be seen as the "thickness" of the support plane.
Template Parameters
SupportOptionsis a value of the SupportOptions enum. If set to WithSweptSphere, the support functions take into account the shapes' swept sphere radii.

Definition at line 450 of file support_functions.cpp.

◆ getSupportSet< SupportOptions::NoSweptSphere >()

template COAL_DLLAPI void coal::details::getSupportSet< SupportOptions::NoSweptSphere > ( const ShapeBase ,
SupportSet ,
int &  ,
size_t  ,
CoalScalar   
)

◆ getSupportSet< SupportOptions::WithSweptSphere >()

template COAL_DLLAPI void coal::details::getSupportSet< SupportOptions::WithSweptSphere > ( const ShapeBase ,
SupportSet ,
int &  ,
size_t  ,
CoalScalar   
)

◆ getSupportTpl()

template<typename Shape0 , typename Shape1 , bool TransformIsIdentity, int _SupportOptions>
void coal::details::getSupportTpl ( const Shape0 *  s0,
const Shape1 *  s1,
const Matrix3s oR1,
const Vec3s ot1,
const Vec3s dir,
Vec3s support0,
Vec3s support1,
support_func_guess_t hint,
ShapeSupportData  data[2] 
)

Definition at line 48 of file minkowski_difference.cpp.

◆ halfspaceDistance()

CoalScalar coal::details::halfspaceDistance ( const Halfspace h,
const Transform3s tf1,
const ShapeBase s,
const Transform3s tf2,
Vec3s p1,
Vec3s p2,
Vec3s normal 
)
inline
Parameters
p1closest (or most penetrating) point on the Halfspace,
p2closest (or most penetrating) point on the shape,
normalthe halfspace normal.
Returns
the distance between the two shapes (negative if penetration).

Definition at line 350 of file details.h.

◆ halfspaceHalfspaceDistance()

CoalScalar coal::details::halfspaceHalfspaceDistance ( const Halfspace s1,
const Transform3s tf1,
const Halfspace s2,
const Transform3s tf2,
Vec3s p1,
Vec3s p2,
Vec3s normal 
)
inline

return distance between two halfspaces

Parameters
p1the witness point on the first halfspace.
p2the witness point on the second halfspace.
normalpointing from first to second halfspace.
Returns
the distance between the two shapes (negative if penetration).
Note
If the two halfspaces don't have the same normal (or opposed normals), they collide and their distance is set to -infinity as there is no translation that can separate them; they have infinite penetration depth. The points p1 and p2 are the same point and represent the origin of the intersection line between the objects. The normal is the direction of this line.

Definition at line 512 of file details.h.

◆ halfspacePlaneDistance()

CoalScalar coal::details::halfspacePlaneDistance ( const Halfspace s1,
const Transform3s tf1,
const Plane s2,
const Transform3s tf2,
Vec3s p1,
Vec3s p2,
Vec3s normal 
)
inline

return distance between plane and halfspace.

Parameters
p1the witness point on the halfspace.
p2the witness point on the plane.
normalpointing from halfspace to plane.
Returns
the distance between the two shapes (negative if penetration).
Note
If plane and halfspace don't have the same normal (or opposed normals), they collide and their distance is set to -infinity as there is no translation that can separate them; they have infinite penetration depth. The points p1 and p2 are the same point and represent the origin of the intersection line between the objects. The normal is the direction of this line.

Definition at line 588 of file details.h.

◆ lineSegmentPointClosestToPoint()

static void coal::details::lineSegmentPointClosestToPoint ( const Vec3s p,
const Vec3s s1,
const Vec3s s2,
Vec3s sp 
)
inlinestatic

Definition at line 51 of file details.h.

◆ makeGetSupportFunction0()

template<int _SupportOptions>
MinkowskiDiff::GetSupportFunction coal::details::makeGetSupportFunction0 ( const ShapeBase s0,
const ShapeBase s1,
bool  identity,
Eigen::Array< CoalScalar, 1, 2 > &  swept_sphere_radius,
ShapeSupportData  data[2] 
)

Definition at line 159 of file minkowski_difference.cpp.

◆ makeGetSupportFunction1()

template<typename Shape0 , int _SupportOptions>
MinkowskiDiff::GetSupportFunction coal::details::makeGetSupportFunction1 ( const ShapeBase s1,
bool  identity,
Eigen::Array< CoalScalar, 1, 2 > &  swept_sphere_radius,
ShapeSupportData  data[2] 
)

Definition at line 78 of file minkowski_difference.cpp.

◆ MinkowskiDiff::set< SupportOptions::NoSweptSphere >() [1/2]

template void COAL_DLLAPI coal::details::MinkowskiDiff::set< SupportOptions::NoSweptSphere > ( const ShapeBase ,
const ShapeBase  
)

◆ MinkowskiDiff::set< SupportOptions::NoSweptSphere >() [2/2]

template void COAL_DLLAPI coal::details::MinkowskiDiff::set< SupportOptions::NoSweptSphere > ( const ShapeBase ,
const ShapeBase ,
const Transform3s ,
const Transform3s  
)

◆ MinkowskiDiff::set< SupportOptions::WithSweptSphere >() [1/2]

template void COAL_DLLAPI coal::details::MinkowskiDiff::set< SupportOptions::WithSweptSphere > ( const ShapeBase ,
const ShapeBase  
)

◆ MinkowskiDiff::set< SupportOptions::WithSweptSphere >() [2/2]

template void COAL_DLLAPI coal::details::MinkowskiDiff::set< SupportOptions::WithSweptSphere > ( const ShapeBase ,
const ShapeBase ,
const Transform3s ,
const Transform3s  
)

◆ MinkowskiDiff::support0< SupportOptions::NoSweptSphere >()

template Vec3s COAL_DLLAPI coal::details::MinkowskiDiff::support0< SupportOptions::NoSweptSphere > ( const Vec3s ,
int &   
) const

◆ MinkowskiDiff::support0< SupportOptions::WithSweptSphere >()

template Vec3s COAL_DLLAPI coal::details::MinkowskiDiff::support0< SupportOptions::WithSweptSphere > ( const Vec3s ,
int &   
) const

◆ MinkowskiDiff::support1< SupportOptions::NoSweptSphere >()

template Vec3s COAL_DLLAPI coal::details::MinkowskiDiff::support1< SupportOptions::NoSweptSphere > ( const Vec3s ,
int &   
) const

◆ MinkowskiDiff::support1< SupportOptions::WithSweptSphere >()

template Vec3s COAL_DLLAPI coal::details::MinkowskiDiff::support1< SupportOptions::WithSweptSphere > ( const Vec3s ,
int &   
) const

◆ orientedBVHShapeDistance()

template<typename OrientedMeshShapeDistanceTraversalNode , typename T_BVH , typename T_SH >
CoalScalar coal::details::orientedBVHShapeDistance ( const CollisionGeometry o1,
const Transform3s tf1,
const CollisionGeometry o2,
const Transform3s tf2,
const GJKSolver nsolver,
const DistanceRequest request,
DistanceResult result 
)

Definition at line 111 of file distance_func_matrix.cpp.

◆ orientedMeshCollide()

template<typename OrientedMeshCollisionTraversalNode , typename T_BVH >
std::size_t coal::details::orientedMeshCollide ( const CollisionGeometry o1,
const Transform3s tf1,
const CollisionGeometry o2,
const Transform3s tf2,
const CollisionRequest request,
CollisionResult result 
)

Definition at line 186 of file collision_func_matrix.cpp.

◆ orientedMeshDistance()

template<typename OrientedMeshDistanceTraversalNode , typename T_BVH >
CoalScalar coal::details::orientedMeshDistance ( const CollisionGeometry o1,
const Transform3s tf1,
const CollisionGeometry o2,
const Transform3s tf2,
const DistanceRequest request,
DistanceResult result 
)

Definition at line 225 of file distance_func_matrix.cpp.

◆ originToPoint()

void coal::details::originToPoint ( const GJK::Simplex current,
GJK::vertex_id_t  a,
const Vec3s A,
GJK::Simplex next,
Vec3s ray 
)
inline

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

◆ originToSegment()

void coal::details::originToSegment ( const GJK::Simplex current,
GJK::vertex_id_t  a,
GJK::vertex_id_t  b,
const Vec3s A,
const Vec3s B,
const Vec3s AB,
const CoalScalar ABdotAO,
GJK::Simplex next,
Vec3s ray 
)
inline

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

◆ originToTriangle()

bool coal::details::originToTriangle ( const GJK::Simplex current,
GJK::vertex_id_t  a,
GJK::vertex_id_t  b,
GJK::vertex_id_t  c,
const Vec3s ABC,
const CoalScalar ABCdotAO,
GJK::Simplex next,
Vec3s ray 
)
inline

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

◆ planeDistance()

CoalScalar coal::details::planeDistance ( const Plane plane,
const Transform3s tf1,
const ShapeBase s,
const Transform3s tf2,
Vec3s p1,
Vec3s p2,
Vec3s normal 
)
inline
Parameters
p1closest (or most penetrating) point on the Plane,
p2closest (or most penetrating) point on the shape,
normalthe halfspace normal.
Returns
the distance between the two shapes (negative if penetration).

Definition at line 384 of file details.h.

◆ planePlaneDistance()

CoalScalar coal::details::planePlaneDistance ( const Plane s1,
const Transform3s tf1,
const Plane s2,
const Transform3s tf2,
Vec3s p1,
Vec3s p2,
Vec3s normal 
)
inline

return distance between two planes

Parameters
p1the witness point on the first plane.
p2the witness point on the second plane.
normalpointing from first to second plane.
Returns
the distance between the two shapes (negative if penetration).
Note
If the two planes don't have the same normal (or opposed normals), they collide and their distance is set to -infinity as there is no translation that can separate them; they have infinite penetration depth. The points p1 and p2 are the same point and represent the origin of the intersection line between the objects. The normal is the direction of this line.

Definition at line 650 of file details.h.

◆ projectInTriangle()

bool coal::details::projectInTriangle ( const Vec3s p1,
const Vec3s p2,
const Vec3s p3,
const Vec3s normal,
const Vec3s p 
)
inline

Whether a point's projection is in a triangle.

Definition at line 260 of file details.h.

◆ segmentSqrDistance()

CoalScalar coal::details::segmentSqrDistance ( const Vec3s from,
const Vec3s to,
const Vec3s p,
Vec3s nearest 
)
inline

the minimum distance from a point to a line

Definition at line 237 of file details.h.

◆ sphereCapsuleDistance()

CoalScalar coal::details::sphereCapsuleDistance ( const Sphere s1,
const Transform3s tf1,
const Capsule s2,
const Transform3s tf2,
Vec3s p1,
Vec3s p2,
Vec3s normal 
)
inline
Parameters
p1witness point on the Sphere.
p2witness point on the Capsule.
normalpointing from shape 1 to shape 2 (sphere to capsule).
Returns
the distance between the two shapes (negative if penetration).

Definition at line 75 of file details.h.

◆ sphereCylinderDistance()

CoalScalar coal::details::sphereCylinderDistance ( const Sphere s1,
const Transform3s tf1,
const Cylinder s2,
const Transform3s tf2,
Vec3s p1,
Vec3s p2,
Vec3s normal 
)
inline
Parameters
p1witness point on the Sphere.
p2witness point on the Cylinder.
normalpointing from shape 1 to shape 2 (sphere to cylinder).
Returns
the distance between the two shapes (negative if penetration).
Todo:
a tiny performance improvement could be achieved using the abscissa with S as the origin

Definition at line 108 of file details.h.

◆ sphereSphereDistance()

CoalScalar coal::details::sphereSphereDistance ( const Sphere s1,
const Transform3s tf1,
const Sphere s2,
const Transform3s tf2,
Vec3s p1,
Vec3s p2,
Vec3s normal 
)
inline
Parameters
p1witness point on the first Sphere.
p2witness point on the second Sphere.
normalpointing from shape 1 to shape 2 (sphere1 to sphere2).
Returns
the distance between the two spheres (negative if penetration).

Definition at line 217 of file details.h.

◆ sphereTriangleDistance()

CoalScalar coal::details::sphereTriangleDistance ( const Sphere s,
const Transform3s tf1,
const TriangleP tri,
const Transform3s tf2,
Vec3s p1,
Vec3s p2,
Vec3s normal 
)
inline
Parameters
p1witness point on the first Sphere.
p2witness point on the second Sphere.
normalpointing from shape 1 to shape 2 (sphere1 to sphere2).
Returns
the distance between the two shapes (negative if penetration).

Definition at line 288 of file details.h.



hpp-fcl
Author(s):
autogenerated on Sat Nov 23 2024 03:45:00