Static Public Member Functions | Static Private Member Functions | List of all members
fcl::detail::Intersect< S > Class Template Reference

CCD intersect kernel among primitives. More...

#include <intersect.h>

Static Public Member Functions

static bool intersect_EE (const Vector3< S > &a0, const Vector3< S > &b0, const Vector3< S > &c0, const Vector3< S > &d0, const Vector3< S > &a1, const Vector3< S > &b1, const Vector3< S > &c1, const Vector3< S > &d1, S *collision_time, Vector3< S > *p_i, bool useNewton=true)
 CCD intersect between two edges [a0, b0] and [a1, b1] are points for one edge in time t0 and t1 [c0, d0] and [c1, d1] are points for the other edge in time t0 and t1 p_i returns the coordinate of the collision point. More...
 
static bool intersect_EE_filtered (const Vector3< S > &a0, const Vector3< S > &b0, const Vector3< S > &c0, const Vector3< S > &d0, const Vector3< S > &a1, const Vector3< S > &b1, const Vector3< S > &c1, const Vector3< S > &d1, S *collision_time, Vector3< S > *p_i, bool useNewton=true)
 CCD intersect between two edges, using additional filter. More...
 
static bool intersect_Triangle (const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, const Vector3< S > &Q1, const Vector3< S > &Q2, const Vector3< S > &Q3, const Matrix3< S > &R, const Vector3< S > &T, Vector3< S > *contact_points=nullptr, unsigned int *num_contact_points=nullptr, S *penetration_depth=nullptr, Vector3< S > *normal=nullptr)
 
static bool intersect_Triangle (const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, const Vector3< S > &Q1, const Vector3< S > &Q2, const Vector3< S > &Q3, const Transform3< S > &tf, Vector3< S > *contact_points=nullptr, unsigned int *num_contact_points=nullptr, S *penetration_depth=nullptr, Vector3< S > *normal=nullptr)
 
static bool intersect_Triangle (const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, const Vector3< S > &Q1, const Vector3< S > &Q2, const Vector3< S > &Q3, Vector3< S > *contact_points=nullptr, unsigned int *num_contact_points=nullptr, S *penetration_depth=nullptr, Vector3< S > *normal=nullptr)
 CD intersect between two triangles [P1, P2, P3] and [Q1, Q2, Q3]. More...
 
static bool intersect_Triangle_ODE_style (const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, const Vector3< S > &Q1, const Vector3< S > &Q2, const Vector3< S > &Q3, Vector3< S > *contact_points=nullptr, unsigned int *num_contact_points=nullptr, S *penetration_depth=nullptr, Vector3< S > *normal=nullptr)
 CD intersect between two triangles [P1, P2, P3] and [Q1, Q2, Q3]. More...
 
static bool intersect_VE (const Vector3< S > &a0, const Vector3< S > &b0, const Vector3< S > &p0, const Vector3< S > &a1, const Vector3< S > &b1, const Vector3< S > &p1, const Vector3< S > &L)
 CCD intersect between one vertex and and one edge. More...
 
static bool intersect_VF (const Vector3< S > &a0, const Vector3< S > &b0, const Vector3< S > &c0, const Vector3< S > &p0, const Vector3< S > &a1, const Vector3< S > &b1, const Vector3< S > &c1, const Vector3< S > &p1, S *collision_time, Vector3< S > *p_i, bool useNewton=true)
 CCD intersect between one vertex and one face [a0, b0, c0] and [a1, b1, c1] are points for the triangle face in time t0 and t1 p0 and p1 are points for vertex in time t0 and t1 p_i returns the coordinate of the collision point. More...
 
static bool intersect_VF_filtered (const Vector3< S > &a0, const Vector3< S > &b0, const Vector3< S > &c0, const Vector3< S > &p0, const Vector3< S > &a1, const Vector3< S > &b1, const Vector3< S > &c1, const Vector3< S > &p1, S *collision_time, Vector3< S > *p_i, bool useNewton=true)
 CCD intersect between one vertex and one face, using additional filter. More...
 

Static Private Member Functions

static bool buildEdgePlane (const Vector3< S > &v1, const Vector3< S > &v2, const Vector3< S > &tn, Vector3< S > *n, S *t)
 build a plane pass through edge v1 and v2, normal is tn More...
 
static bool buildTrianglePlane (const Vector3< S > &v1, const Vector3< S > &v2, const Vector3< S > &v3, Vector3< S > *n, S *t)
 build a plane passed through triangle v1 v2 v3 More...
 
static bool checkRootValidity_EE (const Vector3< S > &a0, const Vector3< S > &b0, const Vector3< S > &c0, const Vector3< S > &d0, const Vector3< S > &va, const Vector3< S > &vb, const Vector3< S > &vc, const Vector3< S > &vd, S t, Vector3< S > *q_i=nullptr)
 Check whether a root for EE intersection is valid (i.e. within the two edges intersected at the given time. More...
 
static bool checkRootValidity_VE (const Vector3< S > &a0, const Vector3< S > &b0, const Vector3< S > &p0, const Vector3< S > &va, const Vector3< S > &vb, const Vector3< S > &vp, S t)
 Check whether a root for VE intersection is valid. More...
 
static bool checkRootValidity_VF (const Vector3< S > &a0, const Vector3< S > &b0, const Vector3< S > &c0, const Vector3< S > &p0, const Vector3< S > &va, const Vector3< S > &vb, const Vector3< S > &vc, const Vector3< S > &vp, S t)
 Check whether a root for VF intersection is valid (i.e. within the triangle at intersection t. More...
 
static void clipPolygonByPlane (Vector3< S > *polygon_points, unsigned int num_polygon_points, const Vector3< S > &n, S t, Vector3< S > clipped_points[], unsigned int *num_clipped_points)
 clip polygon by plane More...
 
static void clipSegmentByPlane (const Vector3< S > &v1, const Vector3< S > &v2, const Vector3< S > &n, S t, Vector3< S > *clipped_point)
 clip a line segment by plane More...
 
static void clipTriangleByTriangleAndEdgePlanes (const Vector3< S > &v1, const Vector3< S > &v2, const Vector3< S > &v3, const Vector3< S > &t1, const Vector3< S > &t2, const Vector3< S > &t3, const Vector3< S > &tn, S to, Vector3< S > clipped_points[], unsigned int *num_clipped_points, bool clip_triangle=false)
 clip triangle v1, v2, v3 by the prism made by t1, t2 and t3. The normal of the prism is tn and is cutted up by to More...
 
static void computeCubicCoeff_EE (const Vector3< S > &a0, const Vector3< S > &b0, const Vector3< S > &c0, const Vector3< S > &d0, const Vector3< S > &va, const Vector3< S > &vb, const Vector3< S > &vc, const Vector3< S > &vd, S *a, S *b, S *c, S *d)
 Compute the cubic coefficients for EE intersection. More...
 
static void computeCubicCoeff_VE (const Vector3< S > &a0, const Vector3< S > &b0, const Vector3< S > &p0, const Vector3< S > &va, const Vector3< S > &vb, const Vector3< S > &vp, const Vector3< S > &L, S *a, S *b, S *c)
 Compute the cubic coefficients for VE intersection. More...
 
static void computeCubicCoeff_VF (const Vector3< S > &a0, const Vector3< S > &b0, const Vector3< S > &c0, const Vector3< S > &p0, const Vector3< S > &va, const Vector3< S > &vb, const Vector3< S > &vc, const Vector3< S > &vp, S *a, S *b, S *c, S *d)
 Compute the cubic coefficients for VF intersection See Paper "Interactive Continuous Collision Detection between Deformable Models using Connectivity-Based Culling", Equation 1. More...
 
static void computeDeepestPoints (Vector3< S > *clipped_points, unsigned int num_clipped_points, const Vector3< S > &n, S t, S *penetration_depth, Vector3< S > *deepest_points, unsigned int *num_deepest_points)
 compute the points which has deepest penetration depth More...
 
static S distanceToPlane (const Vector3< S > &n, S t, const Vector3< S > &v)
 distance of point v to a plane n * x - t = 0 More...
 
static S gaussianCDF (S x)
 compute the cdf(x) More...
 
static constexpr S getCcdResolution ()
 
static constexpr S getEpsilon ()
 
static constexpr unsigned int getMaxTriangleClips ()
 
static constexpr S getNearZeroThreshold ()
 
static bool insideLineSegment (const Vector3< S > &a, const Vector3< S > &b, const Vector3< S > &p)
 Check whether one point p is within a line segment [a, b]. More...
 
static bool insideTriangle (const Vector3< S > &a, const Vector3< S > &b, const Vector3< S > &c, const Vector3< S > &p)
 Check whether one point p is within triangle [a, b, c]. More...
 
static bool intersectPreFiltering (const Vector3< S > &a0, const Vector3< S > &b0, const Vector3< S > &c0, const Vector3< S > &d0, const Vector3< S > &a1, const Vector3< S > &b1, const Vector3< S > &c1, const Vector3< S > &d1)
 filter for intersection, works for both VF and EE More...
 
static bool isZero (S v)
 Check whether one value is zero. More...
 
static bool linelineIntersect (const Vector3< S > &p1, const Vector3< S > &p2, const Vector3< S > &p3, const Vector3< S > &p4, Vector3< S > *pa, Vector3< S > *pb, S *mua, S *mub)
 Calculate the line segment papb that is the shortest route between two lines p1p2 and p3p4. Calculate also the values of mua and mub where pa = p1 + mua (p2 - p1) pb = p3 + mub (p4 - p3) return FALSE if no solution exists. More...
 
static int project6 (const Vector3< S > &ax, const Vector3< S > &p1, const Vector3< S > &p2, const Vector3< S > &p3, const Vector3< S > &q1, const Vector3< S > &q2, const Vector3< S > &q3)
 Project function used in intersect_Triangle() More...
 
static bool sameSideOfPlane (const Vector3< S > &v1, const Vector3< S > &v2, const Vector3< S > &v3, const Vector3< S > &n, S t)
 check wether points v1, v2, v2 are on the same side of plane n * x - t = 0 More...
 
static bool solveCubicWithIntervalNewton (const Vector3< S > &a0, const Vector3< S > &b0, const Vector3< S > &c0, const Vector3< S > &d0, const Vector3< S > &va, const Vector3< S > &vb, const Vector3< S > &vc, const Vector3< S > &vd, S &l, S &r, bool bVF, S coeffs[], Vector3< S > *data=nullptr)
 Solve the cubic function using Newton method, also satisfies the interval restriction. More...
 
static bool solveSquare (S a, S b, S c, const Vector3< S > &a0, const Vector3< S > &b0, const Vector3< S > &c0, const Vector3< S > &d0, const Vector3< S > &va, const Vector3< S > &vb, const Vector3< S > &vc, const Vector3< S > &vd, bool bVF, S *ret)
 Solve a square function for EE intersection (with interval restriction) More...
 
static bool solveSquare (S a, S b, S c, const Vector3< S > &a0, const Vector3< S > &b0, const Vector3< S > &p0, const Vector3< S > &va, const Vector3< S > &vb, const Vector3< S > &vp)
 Solve a square function for VE intersection (with interval restriction) More...
 

Detailed Description

template<typename S>
class fcl::detail::Intersect< S >

CCD intersect kernel among primitives.

Definition at line 54 of file intersect.h.

Member Function Documentation

◆ buildEdgePlane()

template<typename S >
bool fcl::detail::Intersect< S >::buildEdgePlane ( const Vector3< S > &  v1,
const Vector3< S > &  v2,
const Vector3< S > &  tn,
Vector3< S > *  n,
S *  t 
)
staticprivate

build a plane pass through edge v1 and v2, normal is tn

Definition at line 1057 of file intersect-inl.h.

◆ buildTrianglePlane()

template<typename S >
bool fcl::detail::Intersect< S >::buildTrianglePlane ( const Vector3< S > &  v1,
const Vector3< S > &  v2,
const Vector3< S > &  v3,
Vector3< S > *  n,
S *  t 
)
staticprivate

build a plane passed through triangle v1 v2 v3

Definition at line 1040 of file intersect-inl.h.

◆ checkRootValidity_EE()

template<typename S >
bool fcl::detail::Intersect< S >::checkRootValidity_EE ( const Vector3< S > &  a0,
const Vector3< S > &  b0,
const Vector3< S > &  c0,
const Vector3< S > &  d0,
const Vector3< S > &  va,
const Vector3< S > &  vb,
const Vector3< S > &  vc,
const Vector3< S > &  vd,
t,
Vector3< S > *  q_i = nullptr 
)
staticprivate

Check whether a root for EE intersection is valid (i.e. within the two edges intersected at the given time.

Definition at line 221 of file intersect-inl.h.

◆ checkRootValidity_VE()

template<typename S >
bool fcl::detail::Intersect< S >::checkRootValidity_VE ( const Vector3< S > &  a0,
const Vector3< S > &  b0,
const Vector3< S > &  p0,
const Vector3< S > &  va,
const Vector3< S > &  vb,
const Vector3< S > &  vp,
t 
)
staticprivate

Check whether a root for VE intersection is valid.

Definition at line 242 of file intersect-inl.h.

◆ checkRootValidity_VF()

template<typename S >
bool fcl::detail::Intersect< S >::checkRootValidity_VF ( const Vector3< S > &  a0,
const Vector3< S > &  b0,
const Vector3< S > &  c0,
const Vector3< S > &  p0,
const Vector3< S > &  va,
const Vector3< S > &  vb,
const Vector3< S > &  vc,
const Vector3< S > &  vp,
t 
)
staticprivate

Check whether a root for VF intersection is valid (i.e. within the triangle at intersection t.

Definition at line 212 of file intersect-inl.h.

◆ clipPolygonByPlane()

template<typename S >
void fcl::detail::Intersect< S >::clipPolygonByPlane ( Vector3< S > *  polygon_points,
unsigned int  num_polygon_points,
const Vector3< S > &  n,
t,
Vector3< S >  clipped_points[],
unsigned int *  num_clipped_points 
)
staticprivate

clip polygon by plane

Definition at line 939 of file intersect-inl.h.

◆ clipSegmentByPlane()

template<typename S >
void fcl::detail::Intersect< S >::clipSegmentByPlane ( const Vector3< S > &  v1,
const Vector3< S > &  v2,
const Vector3< S > &  n,
t,
Vector3< S > *  clipped_point 
)
staticprivate

clip a line segment by plane

Definition at line 1023 of file intersect-inl.h.

◆ clipTriangleByTriangleAndEdgePlanes()

template<typename S >
void fcl::detail::Intersect< S >::clipTriangleByTriangleAndEdgePlanes ( const Vector3< S > &  v1,
const Vector3< S > &  v2,
const Vector3< S > &  v3,
const Vector3< S > &  t1,
const Vector3< S > &  t2,
const Vector3< S > &  t3,
const Vector3< S > &  tn,
to,
Vector3< S >  clipped_points[],
unsigned int *  num_clipped_points,
bool  clip_triangle = false 
)
staticprivate

clip triangle v1, v2, v3 by the prism made by t1, t2 and t3. The normal of the prism is tn and is cutted up by to

Definition at line 889 of file intersect-inl.h.

◆ computeCubicCoeff_EE()

template<typename S >
void fcl::detail::Intersect< S >::computeCubicCoeff_EE ( const Vector3< S > &  a0,
const Vector3< S > &  b0,
const Vector3< S > &  c0,
const Vector3< S > &  d0,
const Vector3< S > &  va,
const Vector3< S > &  vb,
const Vector3< S > &  vc,
const Vector3< S > &  vd,
S *  a,
S *  b,
S *  c,
S *  d 
)
staticprivate

Compute the cubic coefficients for EE intersection.

Definition at line 342 of file intersect-inl.h.

◆ computeCubicCoeff_VE()

template<typename S >
void fcl::detail::Intersect< S >::computeCubicCoeff_VE ( const Vector3< S > &  a0,
const Vector3< S > &  b0,
const Vector3< S > &  p0,
const Vector3< S > &  va,
const Vector3< S > &  vb,
const Vector3< S > &  vp,
const Vector3< S > &  L,
S *  a,
S *  b,
S *  c 
)
staticprivate

Compute the cubic coefficients for VE intersection.

Definition at line 365 of file intersect-inl.h.

◆ computeCubicCoeff_VF()

template<typename S >
void fcl::detail::Intersect< S >::computeCubicCoeff_VF ( const Vector3< S > &  a0,
const Vector3< S > &  b0,
const Vector3< S > &  c0,
const Vector3< S > &  p0,
const Vector3< S > &  va,
const Vector3< S > &  vb,
const Vector3< S > &  vc,
const Vector3< S > &  vp,
S *  a,
S *  b,
S *  c,
S *  d 
)
staticprivate

Compute the cubic coefficients for VF intersection See Paper "Interactive Continuous Collision Detection between Deformable Models using Connectivity-Based Culling", Equation 1.

Compute the cubic coefficients for VF case See Paper "Interactive Continuous Collision Detection between Deformable Models using Connectivity-Based Culling", Equation 1.

Definition at line 318 of file intersect-inl.h.

◆ computeDeepestPoints()

template<typename S >
void fcl::detail::Intersect< S >::computeDeepestPoints ( Vector3< S > *  clipped_points,
unsigned int  num_clipped_points,
const Vector3< S > &  n,
t,
S *  penetration_depth,
Vector3< S > *  deepest_points,
unsigned int *  num_deepest_points 
)
staticprivate

compute the points which has deepest penetration depth

Definition at line 849 of file intersect-inl.h.

◆ distanceToPlane()

template<typename S >
S fcl::detail::Intersect< S >::distanceToPlane ( const Vector3< S > &  n,
t,
const Vector3< S > &  v 
)
staticprivate

distance of point v to a plane n * x - t = 0

Definition at line 1033 of file intersect-inl.h.

◆ gaussianCDF()

template<typename S >
S fcl::detail::Intersect< S >::gaussianCDF ( x)
staticprivate

compute the cdf(x)

Definition at line 1110 of file intersect-inl.h.

◆ getCcdResolution()

template<typename S >
constexpr S fcl::detail::Intersect< S >::getCcdResolution
staticconstexprprivate

Definition at line 1131 of file intersect-inl.h.

◆ getEpsilon()

template<typename S >
constexpr S fcl::detail::Intersect< S >::getEpsilon
staticconstexprprivate

Definition at line 1117 of file intersect-inl.h.

◆ getMaxTriangleClips()

template<typename S >
constexpr unsigned int fcl::detail::Intersect< S >::getMaxTriangleClips
staticconstexprprivate

Definition at line 1138 of file intersect-inl.h.

◆ getNearZeroThreshold()

template<typename S >
constexpr S fcl::detail::Intersect< S >::getNearZeroThreshold
staticconstexprprivate

Definition at line 1124 of file intersect-inl.h.

◆ insideLineSegment()

template<typename S >
bool fcl::detail::Intersect< S >::insideLineSegment ( const Vector3< S > &  a,
const Vector3< S > &  b,
const Vector3< S > &  p 
)
staticprivate

Check whether one point p is within a line segment [a, b].

Definition at line 162 of file intersect-inl.h.

◆ insideTriangle()

template<typename S >
bool fcl::detail::Intersect< S >::insideTriangle ( const Vector3< S > &  a,
const Vector3< S > &  b,
const Vector3< S > &  c,
const Vector3< S > &  p 
)
staticprivate

Check whether one point p is within triangle [a, b, c].

Definition at line 143 of file intersect-inl.h.

◆ intersect_EE()

template<typename S >
bool fcl::detail::Intersect< S >::intersect_EE ( const Vector3< S > &  a0,
const Vector3< S > &  b0,
const Vector3< S > &  c0,
const Vector3< S > &  d0,
const Vector3< S > &  a1,
const Vector3< S > &  b1,
const Vector3< S > &  c1,
const Vector3< S > &  d1,
S *  collision_time,
Vector3< S > *  p_i,
bool  useNewton = true 
)
static

CCD intersect between two edges [a0, b0] and [a1, b1] are points for one edge in time t0 and t1 [c0, d0] and [c1, d1] are points for the other edge in time t0 and t1 p_i returns the coordinate of the collision point.

if(isZero(a)) { return solveSquare(b, c, d, a0, b0, c0, d0, va, vb, vc, vd, collision_time, false); }

Definition at line 451 of file intersect-inl.h.

◆ intersect_EE_filtered()

template<typename S >
bool fcl::detail::Intersect< S >::intersect_EE_filtered ( const Vector3< S > &  a0,
const Vector3< S > &  b0,
const Vector3< S > &  c0,
const Vector3< S > &  d0,
const Vector3< S > &  a1,
const Vector3< S > &  b1,
const Vector3< S > &  c1,
const Vector3< S > &  d1,
S *  collision_time,
Vector3< S > *  p_i,
bool  useNewton = true 
)
static

CCD intersect between two edges, using additional filter.

Definition at line 584 of file intersect-inl.h.

◆ intersect_Triangle() [1/3]

template<typename S >
bool fcl::detail::Intersect< S >::intersect_Triangle ( const Vector3< S > &  P1,
const Vector3< S > &  P2,
const Vector3< S > &  P3,
const Vector3< S > &  Q1,
const Vector3< S > &  Q2,
const Vector3< S > &  Q3,
const Matrix3< S > &  R,
const Vector3< S > &  T,
Vector3< S > *  contact_points = nullptr,
unsigned int *  num_contact_points = nullptr,
S *  penetration_depth = nullptr,
Vector3< S > *  normal = nullptr 
)
static

Definition at line 598 of file intersect-inl.h.

◆ intersect_Triangle() [2/3]

template<typename S >
bool fcl::detail::Intersect< S >::intersect_Triangle ( const Vector3< S > &  P1,
const Vector3< S > &  P2,
const Vector3< S > &  P3,
const Vector3< S > &  Q1,
const Vector3< S > &  Q2,
const Vector3< S > &  Q3,
const Transform3< S > &  tf,
Vector3< S > *  contact_points = nullptr,
unsigned int *  num_contact_points = nullptr,
S *  penetration_depth = nullptr,
Vector3< S > *  normal = nullptr 
)
static

Definition at line 621 of file intersect-inl.h.

◆ intersect_Triangle() [3/3]

template<typename S >
bool fcl::detail::Intersect< S >::intersect_Triangle ( const Vector3< S > &  P1,
const Vector3< S > &  P2,
const Vector3< S > &  P3,
const Vector3< S > &  Q1,
const Vector3< S > &  Q2,
const Vector3< S > &  Q3,
Vector3< S > *  contact_points = nullptr,
unsigned int *  num_contact_points = nullptr,
S *  penetration_depth = nullptr,
Vector3< S > *  normal = nullptr 
)
static

CD intersect between two triangles [P1, P2, P3] and [Q1, Q2, Q3].

Definition at line 728 of file intersect-inl.h.

◆ intersect_Triangle_ODE_style()

template<typename S >
bool fcl::detail::Intersect< S >::intersect_Triangle_ODE_style ( const Vector3< S > &  P1,
const Vector3< S > &  P2,
const Vector3< S > &  P3,
const Vector3< S > &  Q1,
const Vector3< S > &  Q2,
const Vector3< S > &  Q3,
Vector3< S > *  contact_points = nullptr,
unsigned int *  num_contact_points = nullptr,
S *  penetration_depth = nullptr,
Vector3< S > *  normal = nullptr 
)
static

CD intersect between two triangles [P1, P2, P3] and [Q1, Q2, Q3].

Return contact information

Definition at line 643 of file intersect-inl.h.

◆ intersect_VE()

template<typename S >
bool fcl::detail::Intersect< S >::intersect_VE ( const Vector3< S > &  a0,
const Vector3< S > &  b0,
const Vector3< S > &  p0,
const Vector3< S > &  a1,
const Vector3< S > &  b1,
const Vector3< S > &  p1,
const Vector3< S > &  L 
)
static

CCD intersect between one vertex and and one edge.

Definition at line 517 of file intersect-inl.h.

◆ intersect_VF()

template<typename S >
bool fcl::detail::Intersect< S >::intersect_VF ( const Vector3< S > &  a0,
const Vector3< S > &  b0,
const Vector3< S > &  c0,
const Vector3< S > &  p0,
const Vector3< S > &  a1,
const Vector3< S > &  b1,
const Vector3< S > &  c1,
const Vector3< S > &  p1,
S *  collision_time,
Vector3< S > *  p_i,
bool  useNewton = true 
)
static

CCD intersect between one vertex and one face [a0, b0, c0] and [a1, b1, c1] are points for the triangle face in time t0 and t1 p0 and p1 are points for vertex in time t0 and t1 p_i returns the coordinate of the collision point.

if(isZero(a)) { return solveSquare(b, c, d, a0, b0, c0, p0, va, vb, vc, vp, true, collision_time); }

Definition at line 385 of file intersect-inl.h.

◆ intersect_VF_filtered()

template<typename S >
bool fcl::detail::Intersect< S >::intersect_VF_filtered ( const Vector3< S > &  a0,
const Vector3< S > &  b0,
const Vector3< S > &  c0,
const Vector3< S > &  p0,
const Vector3< S > &  a1,
const Vector3< S > &  b1,
const Vector3< S > &  c1,
const Vector3< S > &  p1,
S *  collision_time,
Vector3< S > *  p_i,
bool  useNewton = true 
)
static

CCD intersect between one vertex and one face, using additional filter.

Definition at line 570 of file intersect-inl.h.

◆ intersectPreFiltering()

template<typename S >
bool fcl::detail::Intersect< S >::intersectPreFiltering ( const Vector3< S > &  a0,
const Vector3< S > &  b0,
const Vector3< S > &  c0,
const Vector3< S > &  d0,
const Vector3< S > &  a1,
const Vector3< S > &  b1,
const Vector3< S > &  c1,
const Vector3< S > &  d1 
)
staticprivate

filter for intersection, works for both VF and EE

Prefilter for intersection, works for both VF and EE.

Definition at line 539 of file intersect-inl.h.

◆ isZero()

template<typename S >
bool fcl::detail::Intersect< S >::isZero ( v)
staticprivate

Check whether one value is zero.

Definition at line 55 of file intersect-inl.h.

◆ linelineIntersect()

template<typename S >
bool fcl::detail::Intersect< S >::linelineIntersect ( const Vector3< S > &  p1,
const Vector3< S > &  p2,
const Vector3< S > &  p3,
const Vector3< S > &  p4,
Vector3< S > *  pa,
Vector3< S > *  pb,
S *  mua,
S *  mub 
)
staticprivate

Calculate the line segment papb that is the shortest route between two lines p1p2 and p3p4. Calculate also the values of mua and mub where pa = p1 + mua (p2 - p1) pb = p3 + mub (p4 - p3) return FALSE if no solution exists.

Calculate the line segment papb that is the shortest route between two lines p1p2 and p3p4. Calculate also the values of mua and mub where pa = p1 + mua (p2 - p1) pb = p3 + mub (p4 - p3) Return FALSE if no solution exists.

Definition at line 174 of file intersect-inl.h.

◆ project6()

template<typename S >
int fcl::detail::Intersect< S >::project6 ( const Vector3< S > &  ax,
const Vector3< S > &  p1,
const Vector3< S > &  p2,
const Vector3< S > &  p3,
const Vector3< S > &  q1,
const Vector3< S > &  q2,
const Vector3< S > &  q3 
)
staticprivate

Project function used in intersect_Triangle()

Definition at line 1086 of file intersect-inl.h.

◆ sameSideOfPlane()

template<typename S >
bool fcl::detail::Intersect< S >::sameSideOfPlane ( const Vector3< S > &  v1,
const Vector3< S > &  v2,
const Vector3< S > &  v3,
const Vector3< S > &  n,
t 
)
staticprivate

check wether points v1, v2, v2 are on the same side of plane n * x - t = 0

Definition at line 1074 of file intersect-inl.h.

◆ solveCubicWithIntervalNewton()

template<typename S >
bool fcl::detail::Intersect< S >::solveCubicWithIntervalNewton ( const Vector3< S > &  a0,
const Vector3< S > &  b0,
const Vector3< S > &  c0,
const Vector3< S > &  d0,
const Vector3< S > &  va,
const Vector3< S > &  vb,
const Vector3< S > &  vc,
const Vector3< S > &  vd,
S &  l,
S &  r,
bool  bVF,
coeffs[],
Vector3< S > *  data = nullptr 
)
staticprivate

Solve the cubic function using Newton method, also satisfies the interval restriction.

data: only used for EE, return the intersect point

Definition at line 63 of file intersect-inl.h.

◆ solveSquare() [1/2]

template<typename S >
bool fcl::detail::Intersect< S >::solveSquare ( a,
b,
c,
const Vector3< S > &  a0,
const Vector3< S > &  b0,
const Vector3< S > &  c0,
const Vector3< S > &  d0,
const Vector3< S > &  va,
const Vector3< S > &  vb,
const Vector3< S > &  vc,
const Vector3< S > &  vd,
bool  bVF,
S *  ret 
)
staticprivate

Solve a square function for EE intersection (with interval restriction)

Definition at line 251 of file intersect-inl.h.

◆ solveSquare() [2/2]

template<typename S >
bool fcl::detail::Intersect< S >::solveSquare ( a,
b,
c,
const Vector3< S > &  a0,
const Vector3< S > &  b0,
const Vector3< S > &  p0,
const Vector3< S > &  va,
const Vector3< S > &  vb,
const Vector3< S > &  vp 
)
staticprivate

Solve a square function for VE intersection (with interval restriction)

Definition at line 289 of file intersect-inl.h.


The documentation for this class was generated from the following files:


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