Functions
fcl::detail::libccd_extension Namespace Reference

Functions

static int __ccdEPA (const void *obj1, const void *obj2, const ccd_t *ccd, ccd_simplex_t *simplex, ccd_pt_t *polytope, ccd_pt_el_t **nearest)
 
static int __ccdGJK (const void *obj1, const void *obj2, const ccd_t *ccd, ccd_simplex_t *simplex)
 
static ccd_real_t _ccdDist (const void *obj1, const void *obj2, const ccd_t *ccd, ccd_simplex_t *simplex, ccd_vec3_t *p1, ccd_vec3_t *p2)
 
static bool are_coincident (const ccd_vec3_t &p, const ccd_vec3_t &q)
 
static ccd_real_t ccdGJKDist2 (const void *obj1, const void *obj2, const ccd_t *ccd, ccd_vec3_t *p1, ccd_vec3_t *p2)
 
static ccd_real_t ccdGJKSignedDist (const void *obj1, const void *obj2, const ccd_t *ccd, ccd_vec3_t *p1, ccd_vec3_t *p2)
 
static void ClassifyBorderEdge (ccd_pt_edge_t *edge, std::unordered_set< ccd_pt_edge_t * > *border_edges, std::unordered_set< ccd_pt_edge_t * > *internal_edges)
 
static void ClassifyInternalEdge (ccd_pt_edge_t *edge, std::unordered_set< ccd_pt_edge_t * > *border_edges, std::unordered_set< ccd_pt_edge_t * > *internal_edges)
 
static void ComputeVisiblePatch (const ccd_pt_t &polytope, ccd_pt_face_t &f, const ccd_vec3_t &query_point, std::unordered_set< ccd_pt_edge_t * > *border_edges, std::unordered_set< ccd_pt_face_t * > *visible_faces, std::unordered_set< ccd_pt_edge_t * > *internal_edges)
 
static void ComputeVisiblePatchRecursive (const ccd_pt_t &polytope, ccd_pt_face_t &f, int edge_index, const ccd_vec3_t &query_point, std::unordered_set< ccd_pt_edge_t * > *border_edges, std::unordered_set< ccd_pt_face_t * > *visible_faces, std::unordered_set< ccd_pt_face_t * > *hidden_faces, std::unordered_set< ccd_pt_edge_t * > *internal_edges)
 
static bool ComputeVisiblePatchRecursiveSanityCheck (const ccd_pt_t &polytope, const std::unordered_set< ccd_pt_edge_t * > &border_edges, const std::unordered_set< ccd_pt_face_t * > &visible_faces, const std::unordered_set< ccd_pt_edge_t * > &internal_edges)
 
static int convert2SimplexToTetrahedron (const void *obj1, const void *obj2, const ccd_t *ccd, const ccd_simplex_t *simplex, ccd_pt_t *polytope, ccd_pt_el_t **nearest)
 
static int doSimplex (ccd_simplex_t *simplex, ccd_vec3_t *dir)
 
static int doSimplex2 (ccd_simplex_t *simplex, ccd_vec3_t *dir)
 
static int doSimplex3 (ccd_simplex_t *simplex, ccd_vec3_t *dir)
 
static int doSimplex4 (ccd_simplex_t *simplex, ccd_vec3_t *dir)
 
static int expandPolytope (ccd_pt_t *polytope, ccd_pt_el_t *el, const ccd_support_t *newv)
 
static void extractClosestPoints (ccd_simplex_t *simplex, ccd_vec3_t *p1, ccd_vec3_t *p2, ccd_vec3_t *p)
 
static void extractObjectPointsFromPoint (ccd_support_t *q, ccd_vec3_t *p1, ccd_vec3_t *p2)
 
static void extractObjectPointsFromSegment (ccd_support_t *a, ccd_support_t *b, ccd_vec3_t *p1, ccd_vec3_t *p2, ccd_vec3_t *p)
 
static ccd_vec3_t faceNormalPointingOutward (const ccd_pt_t *polytope, const ccd_pt_face_t *face)
 
static bool isAbsValueLessThanEpsSquared (ccd_real_t val)
 
static bool isOutsidePolytopeFace (const ccd_pt_t *polytope, const ccd_pt_face_t *f, const ccd_vec3_t *pt)
 
static bool isPolytopeEmpty (const ccd_pt_t &polytope)
 
static int nextSupport (const ccd_pt_t *polytope, const void *obj1, const void *obj2, const ccd_t *ccd, const ccd_pt_el_t *el, ccd_support_t *out)
 
static int penEPAPosClosest (const ccd_pt_el_t *nearest, ccd_vec3_t *p1, ccd_vec3_t *p2)
 
static ccd_real_t simplexReduceToTriangle (ccd_simplex_t *simplex, ccd_real_t dist, ccd_vec3_t *best_witness)
 
static int simplexToPolytope2 (const void *obj1, const void *obj2, const ccd_t *ccd, const ccd_simplex_t *simplex, ccd_pt_t *pt, ccd_pt_el_t **nearest)
 
static int simplexToPolytope4 (const void *obj1, const void *obj2, const ccd_t *ccd, ccd_simplex_t *simplex, ccd_pt_t *pt, ccd_pt_el_t **nearest)
 
static ccd_vec3_t supportEPADirection (const ccd_pt_t *polytope, const ccd_pt_el_t *nearest_feature)
 
static bool triangle_area_is_zero (const ccd_vec3_t &a, const ccd_vec3_t &b, const ccd_vec3_t &c)
 
_ccd_inline void tripleCross (const ccd_vec3_t *a, const ccd_vec3_t *b, const ccd_vec3_t *c, ccd_vec3_t *d)
 
static void validateNearestFeatureOfPolytopeBeingEdge (ccd_pt_t *polytope)
 

Function Documentation

◆ __ccdEPA()

static int fcl::detail::libccd_extension::__ccdEPA ( const void *  obj1,
const void *  obj2,
const ccd_t *  ccd,
ccd_simplex_t simplex,
ccd_pt_t polytope,
ccd_pt_el_t **  nearest 
)
static

Definition at line 1747 of file gjk_libccd-inl.h.

◆ __ccdGJK()

static int fcl::detail::libccd_extension::__ccdGJK ( const void *  obj1,
const void *  obj2,
const ccd_t *  ccd,
ccd_simplex_t simplex 
)
static

Definition at line 1597 of file gjk_libccd-inl.h.

◆ _ccdDist()

static ccd_real_t fcl::detail::libccd_extension::_ccdDist ( const void *  obj1,
const void *  obj2,
const ccd_t *  ccd,
ccd_simplex_t simplex,
ccd_vec3_t *  p1,
ccd_vec3_t *  p2 
)
inlinestatic

Definition at line 2035 of file gjk_libccd-inl.h.

◆ are_coincident()

static bool fcl::detail::libccd_extension::are_coincident ( const ccd_vec3_t &  p,
const ccd_vec3_t &  q 
)
static

Reports true if p and q are coincident.

Definition at line 912 of file gjk_libccd-inl.h.

◆ ccdGJKDist2()

static ccd_real_t fcl::detail::libccd_extension::ccdGJKDist2 ( const void *  obj1,
const void *  obj2,
const ccd_t *  ccd,
ccd_vec3_t *  p1,
ccd_vec3_t *  p2 
)
inlinestatic

Definition at line 2249 of file gjk_libccd-inl.h.

◆ ccdGJKSignedDist()

static ccd_real_t fcl::detail::libccd_extension::ccdGJKSignedDist ( const void *  obj1,
const void *  obj2,
const ccd_t *  ccd,
ccd_vec3_t *  p1,
ccd_vec3_t *  p2 
)
inlinestatic

Definition at line 2186 of file gjk_libccd-inl.h.

◆ ClassifyBorderEdge()

static void fcl::detail::libccd_extension::ClassifyBorderEdge ( ccd_pt_edge_t edge,
std::unordered_set< ccd_pt_edge_t * > *  border_edges,
std::unordered_set< ccd_pt_edge_t * > *  internal_edges 
)
static

Attempts to classify the given edge as a border edge, confirming it hasn't already been classified as an internal edge.

Parameters
edgeThe edge to classify.
border_edgesThe set of edges already classified as border.
internal_edgesThe set of edges already classified as internal.
Exceptions
ThrowFailedAtThisConfigurationif the edge is being re-classified.

Definition at line 1170 of file gjk_libccd-inl.h.

◆ ClassifyInternalEdge()

static void fcl::detail::libccd_extension::ClassifyInternalEdge ( ccd_pt_edge_t edge,
std::unordered_set< ccd_pt_edge_t * > *  border_edges,
std::unordered_set< ccd_pt_edge_t * > *  internal_edges 
)
static

Attempts to classify the given edge as an internal edge, confirming it hasn't already been classified as a border edge.

Parameters
edgeThe edge to classify.
border_edgesThe set of edges already classified as border.
internal_edgesThe set of edges already classified as internal.
Exceptions
ThrowFailedAtThisConfigurationif the edge is being re-classified.

Definition at line 1188 of file gjk_libccd-inl.h.

◆ ComputeVisiblePatch()

static void fcl::detail::libccd_extension::ComputeVisiblePatch ( const ccd_pt_t polytope,
ccd_pt_face_t f,
const ccd_vec3_t &  query_point,
std::unordered_set< ccd_pt_edge_t * > *  border_edges,
std::unordered_set< ccd_pt_face_t * > *  visible_faces,
std::unordered_set< ccd_pt_edge_t * > *  internal_edges 
)
static

Defines the "visible" patch on the given convex polytope (with respect to the given query_vertex which is a point outside the polytope.)

A patch is characterized by:

  • a contiguous set of visible faces
  • internal edges (the edges for which both adjacent faces are in the patch)
  • border edges (edges for which only one adjacent face is in the patch)

A face f (with vertices (v₀, v₁, v₂) and outward pointing normal ) is "visible" and included in the patch if, for query vertex q:

n̂ ⋅ (q - v₀) > 0

Namely the query vertex q is on the "outer" side of the face f.

Parameters
polytopeThe polytope to evaluate.
fA face known to be visible to the query point.
query_pointThe point from which visibility is evaluated.
[out]border_edgesThe collection of patch border edges.
[out]visible_facesThe collection of patch faces.
[out]internal_edgesThe collection of internal edges.
Exceptions
UnexpectedConfigurationExceptionin debug builds if the resulting patch is not consistent.
Precondition
The polytope is convex.
The face f is visible from query_point.
Output parameters are non-null. TODO(hongk.nosp@m.ai.d.nosp@m.ai@tr.nosp@m.i.gl.nosp@m.obal) Replace patch computation with patch deletion and return border edges as an optimization. TODO(hongk.nosp@m.ai.d.nosp@m.ai@tr.nosp@m.i.gl.nosp@m.obal) Consider caching results of per-face visibility status to prevent redundant recalculation – or by associating the face normal with the face.

Definition at line 1315 of file gjk_libccd-inl.h.

◆ ComputeVisiblePatchRecursive()

static void fcl::detail::libccd_extension::ComputeVisiblePatchRecursive ( const ccd_pt_t polytope,
ccd_pt_face_t f,
int  edge_index,
const ccd_vec3_t &  query_point,
std::unordered_set< ccd_pt_edge_t * > *  border_edges,
std::unordered_set< ccd_pt_face_t * > *  visible_faces,
std::unordered_set< ccd_pt_face_t * > *  hidden_faces,
std::unordered_set< ccd_pt_edge_t * > *  internal_edges 
)
static

This function contains the implementation detail of ComputeVisiblePatch() function. It should not be called by any function other than ComputeVisiblePatch(). The parameters are documented as in ComputeVisiblePatch() but has the additional parameter: hidden_faces. Every visited face will be categorized explicitly as either visible or hidden. By design, whatever classification is first given to a face (visible or hidden) it can't change. This doesn't purport that the first classification is more correct than any subsequent code that might otherwise classify it differently. This simply precludes the possibility of classifying edges multiple ways.

Definition at line 1212 of file gjk_libccd-inl.h.

◆ ComputeVisiblePatchRecursiveSanityCheck()

static bool fcl::detail::libccd_extension::ComputeVisiblePatchRecursiveSanityCheck ( const ccd_pt_t polytope,
const std::unordered_set< ccd_pt_edge_t * > &  border_edges,
const std::unordered_set< ccd_pt_face_t * > &  visible_faces,
const std::unordered_set< ccd_pt_edge_t * > &  internal_edges 
)
static

Reports true if the visible patch is valid. The invariant for computing the visible patch is that for each edge in the polytope, if both neighbouring faces are visible, then the edge is an internal edge; if only one neighbouring face is visible, then the edge is a border edge. For each face, if one of its edges is an internal edge, then the face is visible.

Definition at line 1115 of file gjk_libccd-inl.h.

◆ convert2SimplexToTetrahedron()

static int fcl::detail::libccd_extension::convert2SimplexToTetrahedron ( const void *  obj1,
const void *  obj2,
const ccd_t *  ccd,
const ccd_simplex_t simplex,
ccd_pt_t polytope,
ccd_pt_el_t **  nearest 
)
static

Transforms a 2-simplex (triangle) to a polytope (tetrahedron), three vertices required. Both the simplex and the transformed polytope contain the origin. The simplex vertices lie on the surface of the Minkowski difference obj1 ⊖ obj2.

Parameters
[in]obj1object 1 on which the distance is queried.
[in]obj2object 2 on which the distance is queried.
[in]ccdThe ccd solver.
[in]simplexThe simplex (with three vertices) that contains the origin.
[out]polytopeThe polytope (tetrahedron) that also contains the origin on one of its faces. At input, the polytope should be empty.
[out]nearestIf the function detects that obj1 and obj2 are touching, then set *nearest to be the nearest points on obj1 and obj2 respectively; otherwise set *nearest to NULL.
Note
nearest cannot be NULL.
Return values
statusreturn 0 on success, -1 if touching contact is detected, and -2 on non-recoverable failure (mostly due to memory allocation bug).

Definition at line 735 of file gjk_libccd-inl.h.

◆ doSimplex()

static int fcl::detail::libccd_extension::doSimplex ( ccd_simplex_t simplex,
ccd_vec3_t *  dir 
)
static

Definition at line 573 of file gjk_libccd-inl.h.

◆ doSimplex2()

static int fcl::detail::libccd_extension::doSimplex2 ( ccd_simplex_t simplex,
ccd_vec3_t *  dir 
)
static

Definition at line 313 of file gjk_libccd-inl.h.

◆ doSimplex3()

static int fcl::detail::libccd_extension::doSimplex3 ( ccd_simplex_t simplex,
ccd_vec3_t *  dir 
)
static

Definition at line 388 of file gjk_libccd-inl.h.

◆ doSimplex4()

static int fcl::detail::libccd_extension::doSimplex4 ( ccd_simplex_t simplex,
ccd_vec3_t *  dir 
)
static

Definition at line 479 of file gjk_libccd-inl.h.

◆ expandPolytope()

static int fcl::detail::libccd_extension::expandPolytope ( ccd_pt_t polytope,
ccd_pt_el_t el,
const ccd_support_t newv 
)
static

Expands the polytope by adding a new vertex newv to the polytope. The new polytope is the convex hull of the new vertex together with the old polytope. This new polytope includes new edges (by connecting the new vertex with existing vertices) and new faces (by connecting the new vertex with existing edges). We only keep the edges and faces that are on the boundary of the new polytope. The edges/faces on the original polytope that would be interior to the new convex hull are discarded.

Parameters
[in/out]polytope The polytope.
[in]elA feature that is visible from the point newv and contains the polytope boundary point that is closest to the origin. This feature should be either a face or an edge. A face is visible from a point outside the original polytope, if the point is on the "outer" side of the face. If an edge is visible from that point, at least one of its neighbouring faces is visible. This feature contains the point that is closest to the origin on the boundary of the polytope. If the feature is an edge, and the two neighbouring faces of that edge are not co-planar, then the origin must lie on that edge. The feature should not be a vertex, as that would imply the two objects are in touching contact, causing the algorithm to exit before calling expandPolytope() function.
[in]newvThe new vertex add to the polytope.
Return values
statusReturns 0 on success. Returns -2 otherwise.
Exceptions
UnexpectedConfigurationExceptionif expanding is meaningless either because 1) the nearest feature is a vertex, 2) the new vertex lies on an edge of the current polytope, or 3) the visible feature is an edge with one or more adjacent faces with no area.

Definition at line 1371 of file gjk_libccd-inl.h.

◆ extractClosestPoints()

static void fcl::detail::libccd_extension::extractClosestPoints ( ccd_simplex_t simplex,
ccd_vec3_t *  p1,
ccd_vec3_t *  p2,
ccd_vec3_t *  p 
)
static

Returns the points p1 and p2 on the original shapes that correspond to point p in the given simplex.

Precondition
simplex size <= 3.
p lies on the simplex (i.e., within the triangle, line segment, or is coincident with the point).

Definition at line 1894 of file gjk_libccd-inl.h.

◆ extractObjectPointsFromPoint()

static void fcl::detail::libccd_extension::extractObjectPointsFromPoint ( ccd_support_t q,
ccd_vec3_t *  p1,
ccd_vec3_t *  p2 
)
static

Given a single support point, q, extract the point p1 and p2, the points on object 1 and 2, respectively, in the support data of q.

Definition at line 1805 of file gjk_libccd-inl.h.

◆ extractObjectPointsFromSegment()

static void fcl::detail::libccd_extension::extractObjectPointsFromSegment ( ccd_support_t a,
ccd_support_t b,
ccd_vec3_t *  p1,
ccd_vec3_t *  p2,
ccd_vec3_t *  p 
)
static

Given two support points which define a line segment (a and b), and a point on that line segment p, computes the points p1 and p2, the points on object 1 and 2, respectively, in the support data which correspond to p.

Precondition
p = a + s(b - a), 0 <= s <= 1

Definition at line 1818 of file gjk_libccd-inl.h.

◆ faceNormalPointingOutward()

static ccd_vec3_t fcl::detail::libccd_extension::faceNormalPointingOutward ( const ccd_pt_t polytope,
const ccd_pt_face_t face 
)
static

Computes the normal vector of a triangular face on a polytope, and the normal vector points outward from the polytope. Notice we assume that the origin lives within the polytope, and the normal vector may not have unit length.

Parameters
[in]polytopeThe polytope on which the face lives. We assume that the origin also lives inside the polytope.
[in]faceThe face for which the normal vector is computed.
Return values
dirThe vector normal to the face, and points outward from the polytope. dir is unnormalized, that it does not necessarily have a unit length.
Exceptions
UnexpectedConfigurationExceptionif built in debug mode and the triangle has zero area (either by being too small, or being co-linear).

Definition at line 982 of file gjk_libccd-inl.h.

◆ isAbsValueLessThanEpsSquared()

static bool fcl::detail::libccd_extension::isAbsValueLessThanEpsSquared ( ccd_real_t  val)
static

Definition at line 379 of file gjk_libccd-inl.h.

◆ isOutsidePolytopeFace()

static bool fcl::detail::libccd_extension::isOutsidePolytopeFace ( const ccd_pt_t polytope,
const ccd_pt_face_t f,
const ccd_vec3_t *  pt 
)
static

Definition at line 1092 of file gjk_libccd-inl.h.

◆ isPolytopeEmpty()

static bool fcl::detail::libccd_extension::isPolytopeEmpty ( const ccd_pt_t polytope)
static

Definition at line 695 of file gjk_libccd-inl.h.

◆ nextSupport()

static int fcl::detail::libccd_extension::nextSupport ( const ccd_pt_t polytope,
const void *  obj1,
const void *  obj2,
const ccd_t *  ccd,
const ccd_pt_el_t el,
ccd_support_t out 
)
static

Finds next support point (and stores it in out argument).

Parameters
[in]polytopeThe current polytope contained inside the Minkowski difference A ⊖ B.
[in]obj1Geometric object A.
[in]obj2Geometric object B.
[in]ccdThe libccd solver.
[in]elThe polytope boundary feature that contains the point nearest to the origin.
[out]outThe next support point.
Return values
statusIf the next support point is found, then returns 0; otherwise returns -1. There are several reasons why the next support point is not found:
  1. If the nearest point on the boundary of the polytope to the origin is a vertex of the polytope. Then we know the two objects A and B are in touching contact.
  2. If the difference between the upper bound and lower bound of the distance is below ccd->epa_tolerance, then we converge to a distance whose difference from the real distance is less than ccd->epa_tolerance.

Definition at line 1553 of file gjk_libccd-inl.h.

◆ penEPAPosClosest()

static int fcl::detail::libccd_extension::penEPAPosClosest ( const ccd_pt_el_t nearest,
ccd_vec3_t *  p1,
ccd_vec3_t *  p2 
)
static

Given the nearest point on the polytope inside the Minkowski difference A ⊖ B, returns the point p1 on geometric object A and p2 on geometric object B, such that p1 is the deepest penetration point on A, and p2 is the deepest penetration point on B.

Parameters
[in]nearestThe feature with the point that is nearest to the origin on the boundary of the polytope.
[out]p1the deepest penetration point on A, measured and expressed in the world frame.
[out]p2the deepest penetration point on B, measured and expressed in the world frame.
Return values
statusReturn 0 on success, and -1 on failure.

Definition at line 2131 of file gjk_libccd-inl.h.

◆ simplexReduceToTriangle()

static ccd_real_t fcl::detail::libccd_extension::simplexReduceToTriangle ( ccd_simplex_t simplex,
ccd_real_t  dist,
ccd_vec3_t *  best_witness 
)
static

Definition at line 189 of file gjk_libccd-inl.h.

◆ simplexToPolytope2()

static int fcl::detail::libccd_extension::simplexToPolytope2 ( const void *  obj1,
const void *  obj2,
const ccd_t *  ccd,
const ccd_simplex_t simplex,
ccd_pt_t pt,
ccd_pt_el_t **  nearest 
)
static

Transforms simplex to polytope, two vertices required

Definition at line 589 of file gjk_libccd-inl.h.

◆ simplexToPolytope4()

static int fcl::detail::libccd_extension::simplexToPolytope4 ( const void *  obj1,
const void *  obj2,
const ccd_t *  ccd,
ccd_simplex_t simplex,
ccd_pt_t pt,
ccd_pt_el_t **  nearest 
)
static

Transforms simplex to polytope. It is assumed that simplex has 4 vertices!

Definition at line 827 of file gjk_libccd-inl.h.

◆ supportEPADirection()

static ccd_vec3_t fcl::detail::libccd_extension::supportEPADirection ( const ccd_pt_t polytope,
const ccd_pt_el_t nearest_feature 
)
static

In each iteration of EPA algorithm, given the nearest point on the polytope boundary to the origin, a support direction will be computed, to find the support of the Minkowski difference A ⊖ B along that direction, so as to expand the polytope.

Parameters
polytopeThe polytope contained in A ⊖ B.
nearest_featureThe feature containing the nearest point on the boundary of the polytope to the origin.
Return values
dirThe support direction along which to expand the polytope. Notice that dir is a normalized vector.
Exceptions
UnexpectedConfigurationExceptionif the nearest feature is a vertex.

Definition at line 1489 of file gjk_libccd-inl.h.

◆ triangle_area_is_zero()

static bool fcl::detail::libccd_extension::triangle_area_is_zero ( const ccd_vec3_t &  a,
const ccd_vec3_t &  b,
const ccd_vec3_t &  c 
)
static

Determines if the the triangle defined by the three vertices has zero area. Area can be zero for one of two reasons:

  • the triangle is so small that the vertices are functionally coincident, or
  • the vertices are co-linear. Both conditions are computed with respect to machine precision.
    Returns
    true if the area is zero.

Definition at line 943 of file gjk_libccd-inl.h.

◆ tripleCross()

_ccd_inline void fcl::detail::libccd_extension::tripleCross ( const ccd_vec3_t *  a,
const ccd_vec3_t *  b,
const ccd_vec3_t *  c,
ccd_vec3_t *  d 
)

Definition at line 223 of file gjk_libccd-inl.h.

◆ validateNearestFeatureOfPolytopeBeingEdge()

static void fcl::detail::libccd_extension::validateNearestFeatureOfPolytopeBeingEdge ( ccd_pt_t polytope)
static

When the nearest feature of a polytope to the origin is an edge, and the origin is inside the polytope, it implies one of the following conditions

  1. The origin lies exactly on that edge
  2. The two neighbouring faces of that edge are coplanar, and the projection of the origin onto that plane is on the edge. At times libccd incorrectly claims that the nearest feature is an edge. Inside this function, we will verify if one of these two conditions are true. If not, we will modify the nearest feature stored inside polytope, such that it stores the correct nearest feature and distance.
    Note
    we assume that even if the edge is not the correct nearest feature, the correct one should be one of the neighbouring faces of that edge. Namely the libccd solution is just slightly wrong.
    Parameters
    polytopeThe polytope whose nearest feature is being verified (and corrected if the edge should not be nearest feature).
    Note
    Only call this function in the EPA functions, where the origin should be inside the polytope.

Definition at line 1670 of file gjk_libccd-inl.h.



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