$search
CCD intersect kernel among primitives. More...
#include <intersect.h>
Static Public Member Functions | |
static bool | intersect_EE (const Vec3f &a0, const Vec3f &b0, const Vec3f &c0, const Vec3f &d0, const Vec3f &a1, const Vec3f &b1, const Vec3f &c1, const Vec3f &d1, BVH_REAL *collision_time, Vec3f *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. | |
static bool | intersect_EE_filtered (const Vec3f &a0, const Vec3f &b0, const Vec3f &c0, const Vec3f &d0, const Vec3f &a1, const Vec3f &b1, const Vec3f &c1, const Vec3f &d1, BVH_REAL *collision_time, Vec3f *p_i, bool useNewton=true) |
CCD intersect between two edges, using additional filter. | |
static bool | intersect_Triangle (const Vec3f &P1, const Vec3f &P2, const Vec3f &P3, const Vec3f &Q1, const Vec3f &Q2, const Vec3f &Q3, const Vec3f R[3], const Vec3f &T, Vec3f *contact_points=NULL, unsigned int *num_contact_points=NULL, BVH_REAL *penetration_depth=NULL, Vec3f *normal=NULL) |
static bool | intersect_Triangle (const Vec3f &P1, const Vec3f &P2, const Vec3f &P3, const Vec3f &Q1, const Vec3f &Q2, const Vec3f &Q3, Vec3f *contact_points=NULL, unsigned int *num_contact_points=NULL, BVH_REAL *penetration_depth=NULL, Vec3f *normal=NULL) |
CD intersect between two triangles [P1, P2, P3] and [Q1, Q2, Q3]. | |
static bool | intersect_VE (const Vec3f &a0, const Vec3f &b0, const Vec3f &p0, const Vec3f &a1, const Vec3f &b1, const Vec3f &p1, const Vec3f &L) |
CCD intersect between one vertex and and one edge. | |
static bool | intersect_VF (const Vec3f &a0, const Vec3f &b0, const Vec3f &c0, const Vec3f &p0, const Vec3f &a1, const Vec3f &b1, const Vec3f &c1, const Vec3f &p1, BVH_REAL *collision_time, Vec3f *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. | |
static bool | intersect_VF_filtered (const Vec3f &a0, const Vec3f &b0, const Vec3f &c0, const Vec3f &p0, const Vec3f &a1, const Vec3f &b1, const Vec3f &c1, const Vec3f &p1, BVH_REAL *collision_time, Vec3f *p_i, bool useNewton=true) |
CCD intersect between one vertex and one face, using additional filter. | |
Static Private Member Functions | |
static bool | buildEdgePlane (const Vec3f &v1, const Vec3f &v2, const Vec3f &tn, Vec3f *n, BVH_REAL *t) |
static bool | buildTrianglePlane (const Vec3f &v1, const Vec3f &v2, const Vec3f &v3, Vec3f *n, BVH_REAL *t) |
static bool | checkRootValidity_EE (const Vec3f &a0, const Vec3f &b0, const Vec3f &c0, const Vec3f &d0, const Vec3f &va, const Vec3f &vb, const Vec3f &vc, const Vec3f &vd, BVH_REAL t, Vec3f *q_i=NULL) |
Check whether a root for EE intersection is valid (i.e. within the two edges intersected at the given time. | |
static bool | checkRootValidity_VE (const Vec3f &a0, const Vec3f &b0, const Vec3f &p0, const Vec3f &va, const Vec3f &vb, const Vec3f &vp, BVH_REAL t) |
Check whether a root for VE intersection is valid. | |
static bool | checkRootValidity_VF (const Vec3f &a0, const Vec3f &b0, const Vec3f &c0, const Vec3f &p0, const Vec3f &va, const Vec3f &vb, const Vec3f &vc, const Vec3f &vp, BVH_REAL t) |
Check whether a root for VF intersection is valid (i.e. within the triangle at intersection t. | |
static void | clipPolygonByPlane (Vec3f *polygon_points, unsigned int num_polygon_points, const Vec3f &n, BVH_REAL t, Vec3f clipped_points[], unsigned int *num_clipped_points) |
static void | clipSegmentByPlane (const Vec3f &v1, const Vec3f &v2, const Vec3f &n, BVH_REAL t, Vec3f *clipped_point) |
static void | clipTriangleByTriangleAndEdgePlanes (const Vec3f &v1, const Vec3f &v2, const Vec3f &v3, const Vec3f &t1, const Vec3f &t2, const Vec3f &t3, const Vec3f &tn, BVH_REAL to, Vec3f clipped_points[], unsigned int *num_clipped_points, bool clip_triangle=false) |
static void | computeCubicCoeff_EE (const Vec3f &a0, const Vec3f &b0, const Vec3f &c0, const Vec3f &d0, const Vec3f &va, const Vec3f &vb, const Vec3f &vc, const Vec3f &vd, BVH_REAL *a, BVH_REAL *b, BVH_REAL *c, BVH_REAL *d) |
Compute the cubic coefficients for EE intersection. | |
static void | computeCubicCoeff_VE (const Vec3f &a0, const Vec3f &b0, const Vec3f &p0, const Vec3f &va, const Vec3f &vb, const Vec3f &vp, const Vec3f &L, BVH_REAL *a, BVH_REAL *b, BVH_REAL *c) |
Compute the cubic coefficients for VE intersection. | |
static void | computeCubicCoeff_VF (const Vec3f &a0, const Vec3f &b0, const Vec3f &c0, const Vec3f &p0, const Vec3f &va, const Vec3f &vb, const Vec3f &vc, const Vec3f &vp, BVH_REAL *a, BVH_REAL *b, BVH_REAL *c, BVH_REAL *d) |
Compute the cubic coefficients for VF intersection See Paper "Interactive Continuous Collision Detection between Deformable Models using Connectivity-Based Culling", Equation 1. | |
static void | computeDeepestPoints (Vec3f *clipped_points, unsigned int num_clipped_points, const Vec3f &n, BVH_REAL t, BVH_REAL *penetration_depth, Vec3f *deepest_points, unsigned int *num_deepest_points) |
static BVH_REAL | distanceToPlane (const Vec3f &n, BVH_REAL t, const Vec3f &v) |
static bool | insideLineSegment (const Vec3f &a, const Vec3f &b, const Vec3f &p) |
Check whether one point p is within a line segment [a, b]. | |
static bool | insideTriangle (const Vec3f &a, const Vec3f &b, const Vec3f &c, const Vec3f &p) |
Check whether one point p is within triangle [a, b, c]. | |
static bool | intersectPreFiltering (const Vec3f &a0, const Vec3f &b0, const Vec3f &c0, const Vec3f &d0, const Vec3f &a1, const Vec3f &b1, const Vec3f &c1, const Vec3f &d1) |
filter for intersection, works for both VF and EE | |
static bool | isZero (BVH_REAL v) |
Check whether one value is zero. | |
static bool | linelineIntersect (const Vec3f &p1, const Vec3f &p2, const Vec3f &p3, const Vec3f &p4, Vec3f *pa, Vec3f *pb, BVH_REAL *mua, BVH_REAL *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. | |
static int | project6 (const Vec3f &ax, const Vec3f &p1, const Vec3f &p2, const Vec3f &p3, const Vec3f &q1, const Vec3f &q2, const Vec3f &q3) |
Project function used in intersect_Triangle(). | |
static bool | sameSideOfPlane (const Vec3f &v1, const Vec3f &v2, const Vec3f &v3, const Vec3f &n, BVH_REAL t) |
static bool | solveCubicWithIntervalNewton (const Vec3f &a0, const Vec3f &b0, const Vec3f &c0, const Vec3f &d0, const Vec3f &va, const Vec3f &vb, const Vec3f &vc, const Vec3f &vd, BVH_REAL &l, BVH_REAL &r, bool bVF, BVH_REAL coeffs[], Vec3f *data=NULL) |
Solve the cubic function using Newton method, also satisfies the interval restriction. | |
static bool | solveSquare (BVH_REAL a, BVH_REAL b, BVH_REAL c, const Vec3f &a0, const Vec3f &b0, const Vec3f &p0, const Vec3f &va, const Vec3f &vb, const Vec3f &vp) |
Solve a square function for VE intersection (with interval restriction). | |
static bool | solveSquare (BVH_REAL a, BVH_REAL b, BVH_REAL c, const Vec3f &a0, const Vec3f &b0, const Vec3f &c0, const Vec3f &d0, const Vec3f &va, const Vec3f &vb, const Vec3f &vc, const Vec3f &vd, bool bVF, BVH_REAL *ret) |
Solve a square function for EE intersection (with interval restriction). | |
Static Private Attributes | |
static const BVH_REAL | CCD_RESOLUTION = 1e-7 |
static const BVH_REAL | EPSILON = 1e-5 |
static const unsigned int | MAX_TRIANGLE_CLIPS = 8 |
static const BVH_REAL | NEAR_ZERO_THRESHOLD = 1e-7 |
CCD intersect kernel among primitives.
Definition at line 73 of file intersect.h.
bool collision_checking::Intersect::buildEdgePlane | ( | const Vec3f & | v1, | |
const Vec3f & | v2, | |||
const Vec3f & | tn, | |||
Vec3f * | n, | |||
BVH_REAL * | t | |||
) | [static, private] |
Definition at line 1100 of file intersect.cpp.
bool collision_checking::Intersect::buildTrianglePlane | ( | const Vec3f & | v1, | |
const Vec3f & | v2, | |||
const Vec3f & | v3, | |||
Vec3f * | n, | |||
BVH_REAL * | t | |||
) | [static, private] |
Definition at line 1087 of file intersect.cpp.
bool collision_checking::Intersect::checkRootValidity_EE | ( | const Vec3f & | a0, | |
const Vec3f & | b0, | |||
const Vec3f & | c0, | |||
const Vec3f & | d0, | |||
const Vec3f & | va, | |||
const Vec3f & | vb, | |||
const Vec3f & | vc, | |||
const Vec3f & | vd, | |||
BVH_REAL | t, | |||
Vec3f * | q_i = NULL | |||
) | [static, private] |
Check whether a root for EE intersection is valid (i.e. within the two edges intersected at the given time.
Definition at line 336 of file intersect.cpp.
bool collision_checking::Intersect::checkRootValidity_VE | ( | const Vec3f & | a0, | |
const Vec3f & | b0, | |||
const Vec3f & | p0, | |||
const Vec3f & | va, | |||
const Vec3f & | vb, | |||
const Vec3f & | vp, | |||
BVH_REAL | t | |||
) | [static, private] |
Check whether a root for VE intersection is valid.
Definition at line 355 of file intersect.cpp.
bool collision_checking::Intersect::checkRootValidity_VF | ( | const Vec3f & | a0, | |
const Vec3f & | b0, | |||
const Vec3f & | c0, | |||
const Vec3f & | p0, | |||
const Vec3f & | va, | |||
const Vec3f & | vb, | |||
const Vec3f & | vc, | |||
const Vec3f & | vp, | |||
BVH_REAL | t | |||
) | [static, private] |
Check whether a root for VF intersection is valid (i.e. within the triangle at intersection t.
Definition at line 329 of file intersect.cpp.
void collision_checking::Intersect::clipPolygonByPlane | ( | Vec3f * | polygon_points, | |
unsigned int | num_polygon_points, | |||
const Vec3f & | n, | |||
BVH_REAL | t, | |||
Vec3f | clipped_points[], | |||
unsigned int * | num_clipped_points | |||
) | [static, private] |
Definition at line 992 of file intersect.cpp.
void collision_checking::Intersect::clipSegmentByPlane | ( | const Vec3f & | v1, | |
const Vec3f & | v2, | |||
const Vec3f & | n, | |||
BVH_REAL | t, | |||
Vec3f * | clipped_point | |||
) | [static, private] |
Definition at line 1074 of file intersect.cpp.
void collision_checking::Intersect::clipTriangleByTriangleAndEdgePlanes | ( | const Vec3f & | v1, | |
const Vec3f & | v2, | |||
const Vec3f & | v3, | |||
const Vec3f & | t1, | |||
const Vec3f & | t2, | |||
const Vec3f & | t3, | |||
const Vec3f & | tn, | |||
BVH_REAL | to, | |||
Vec3f | clipped_points[], | |||
unsigned int * | num_clipped_points, | |||
bool | clip_triangle = false | |||
) | [static, private] |
Definition at line 944 of file intersect.cpp.
void collision_checking::Intersect::computeCubicCoeff_EE | ( | const Vec3f & | a0, | |
const Vec3f & | b0, | |||
const Vec3f & | c0, | |||
const Vec3f & | d0, | |||
const Vec3f & | va, | |||
const Vec3f & | vb, | |||
const Vec3f & | vc, | |||
const Vec3f & | vd, | |||
BVH_REAL * | a, | |||
BVH_REAL * | b, | |||
BVH_REAL * | c, | |||
BVH_REAL * | d | |||
) | [static, private] |
Compute the cubic coefficients for EE intersection.
Definition at line 450 of file intersect.cpp.
void collision_checking::Intersect::computeCubicCoeff_VE | ( | const Vec3f & | a0, | |
const Vec3f & | b0, | |||
const Vec3f & | p0, | |||
const Vec3f & | va, | |||
const Vec3f & | vb, | |||
const Vec3f & | vp, | |||
const Vec3f & | L, | |||
BVH_REAL * | a, | |||
BVH_REAL * | b, | |||
BVH_REAL * | c | |||
) | [static, private] |
Compute the cubic coefficients for VE intersection.
Definition at line 471 of file intersect.cpp.
void collision_checking::Intersect::computeCubicCoeff_VF | ( | const Vec3f & | a0, | |
const Vec3f & | b0, | |||
const Vec3f & | c0, | |||
const Vec3f & | p0, | |||
const Vec3f & | va, | |||
const Vec3f & | vb, | |||
const Vec3f & | vc, | |||
const Vec3f & | vp, | |||
BVH_REAL * | a, | |||
BVH_REAL * | b, | |||
BVH_REAL * | c, | |||
BVH_REAL * | d | |||
) | [static, private] |
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 428 of file intersect.cpp.
void collision_checking::Intersect::computeDeepestPoints | ( | Vec3f * | clipped_points, | |
unsigned int | num_clipped_points, | |||
const Vec3f & | n, | |||
BVH_REAL | t, | |||
BVH_REAL * | penetration_depth, | |||
Vec3f * | deepest_points, | |||
unsigned int * | num_deepest_points | |||
) | [static, private] |
Definition at line 906 of file intersect.cpp.
BVH_REAL collision_checking::Intersect::distanceToPlane | ( | const Vec3f & | n, | |
BVH_REAL | t, | |||
const Vec3f & | v | |||
) | [static, private] |
Definition at line 1082 of file intersect.cpp.
bool collision_checking::Intersect::insideLineSegment | ( | const Vec3f & | a, | |
const Vec3f & | b, | |||
const Vec3f & | p | |||
) | [static, private] |
Check whether one point p is within a line segment [a, b].
Definition at line 282 of file intersect.cpp.
bool collision_checking::Intersect::insideTriangle | ( | const Vec3f & | a, | |
const Vec3f & | b, | |||
const Vec3f & | c, | |||
const Vec3f & | p | |||
) | [static, private] |
Check whether one point p is within triangle [a, b, c].
Definition at line 265 of file intersect.cpp.
bool collision_checking::Intersect::intersect_EE | ( | const Vec3f & | a0, | |
const Vec3f & | b0, | |||
const Vec3f & | c0, | |||
const Vec3f & | d0, | |||
const Vec3f & | a1, | |||
const Vec3f & | b1, | |||
const Vec3f & | c1, | |||
const Vec3f & | d1, | |||
BVH_REAL * | collision_time, | |||
Vec3f * | 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.
Definition at line 556 of file intersect.cpp.
bool collision_checking::Intersect::intersect_EE_filtered | ( | const Vec3f & | a0, | |
const Vec3f & | b0, | |||
const Vec3f & | c0, | |||
const Vec3f & | d0, | |||
const Vec3f & | a1, | |||
const Vec3f & | b1, | |||
const Vec3f & | c1, | |||
const Vec3f & | d1, | |||
BVH_REAL * | collision_time, | |||
Vec3f * | p_i, | |||
bool | useNewton = true | |||
) | [static] |
CCD intersect between two edges, using additional filter.
Definition at line 683 of file intersect.cpp.
bool collision_checking::Intersect::intersect_Triangle | ( | const Vec3f & | P1, | |
const Vec3f & | P2, | |||
const Vec3f & | P3, | |||
const Vec3f & | Q1, | |||
const Vec3f & | Q2, | |||
const Vec3f & | Q3, | |||
const Vec3f | R[3], | |||
const Vec3f & | T, | |||
Vec3f * | contact_points = NULL , |
|||
unsigned int * | num_contact_points = NULL , |
|||
BVH_REAL * | penetration_depth = NULL , |
|||
Vec3f * | normal = NULL | |||
) | [static] |
Definition at line 695 of file intersect.cpp.
bool collision_checking::Intersect::intersect_Triangle | ( | const Vec3f & | P1, | |
const Vec3f & | P2, | |||
const Vec3f & | P3, | |||
const Vec3f & | Q1, | |||
const Vec3f & | Q2, | |||
const Vec3f & | Q3, | |||
Vec3f * | contact_points = NULL , |
|||
unsigned int * | num_contact_points = NULL , |
|||
BVH_REAL * | penetration_depth = NULL , |
|||
Vec3f * | normal = NULL | |||
) | [static] |
CD intersect between two triangles [P1, P2, P3] and [Q1, Q2, Q3].
Definition at line 795 of file intersect.cpp.
bool collision_checking::Intersect::intersect_VE | ( | const Vec3f & | a0, | |
const Vec3f & | b0, | |||
const Vec3f & | p0, | |||
const Vec3f & | a1, | |||
const Vec3f & | b1, | |||
const Vec3f & | p1, | |||
const Vec3f & | L | |||
) | [static] |
CCD intersect between one vertex and and one edge.
Definition at line 621 of file intersect.cpp.
bool collision_checking::Intersect::intersect_VF | ( | const Vec3f & | a0, | |
const Vec3f & | b0, | |||
const Vec3f & | c0, | |||
const Vec3f & | p0, | |||
const Vec3f & | a1, | |||
const Vec3f & | b1, | |||
const Vec3f & | c1, | |||
const Vec3f & | p1, | |||
BVH_REAL * | collision_time, | |||
Vec3f * | 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.
Definition at line 490 of file intersect.cpp.
bool collision_checking::Intersect::intersect_VF_filtered | ( | const Vec3f & | a0, | |
const Vec3f & | b0, | |||
const Vec3f & | c0, | |||
const Vec3f & | p0, | |||
const Vec3f & | a1, | |||
const Vec3f & | b1, | |||
const Vec3f & | c1, | |||
const Vec3f & | p1, | |||
BVH_REAL * | collision_time, | |||
Vec3f * | p_i, | |||
bool | useNewton = true | |||
) | [static] |
CCD intersect between one vertex and one face, using additional filter.
Definition at line 671 of file intersect.cpp.
bool collision_checking::Intersect::intersectPreFiltering | ( | const Vec3f & | a0, | |
const Vec3f & | b0, | |||
const Vec3f & | c0, | |||
const Vec3f & | d0, | |||
const Vec3f & | a1, | |||
const Vec3f & | b1, | |||
const Vec3f & | c1, | |||
const Vec3f & | d1 | |||
) | [static, private] |
filter for intersection, works for both VF and EE
Prefilter for intersection, works for both VF and EE.
Definition at line 642 of file intersect.cpp.
bool collision_checking::Intersect::isZero | ( | BVH_REAL | v | ) | [inline, static, private] |
Check whether one value is zero.
Definition at line 177 of file intersect.cpp.
bool collision_checking::Intersect::linelineIntersect | ( | const Vec3f & | p1, | |
const Vec3f & | p2, | |||
const Vec3f & | p3, | |||
const Vec3f & | p4, | |||
Vec3f * | pa, | |||
Vec3f * | pb, | |||
BVH_REAL * | mua, | |||
BVH_REAL * | mub | |||
) | [static, private] |
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 293 of file intersect.cpp.
int collision_checking::Intersect::project6 | ( | const Vec3f & | ax, | |
const Vec3f & | p1, | |||
const Vec3f & | p2, | |||
const Vec3f & | p3, | |||
const Vec3f & | q1, | |||
const Vec3f & | q2, | |||
const Vec3f & | q3 | |||
) | [static, private] |
Project function used in intersect_Triangle().
Definition at line 1123 of file intersect.cpp.
bool collision_checking::Intersect::sameSideOfPlane | ( | const Vec3f & | v1, | |
const Vec3f & | v2, | |||
const Vec3f & | v3, | |||
const Vec3f & | n, | |||
BVH_REAL | t | |||
) | [static, private] |
Definition at line 1113 of file intersect.cpp.
bool collision_checking::Intersect::solveCubicWithIntervalNewton | ( | const Vec3f & | a0, | |
const Vec3f & | b0, | |||
const Vec3f & | c0, | |||
const Vec3f & | d0, | |||
const Vec3f & | va, | |||
const Vec3f & | vb, | |||
const Vec3f & | vc, | |||
const Vec3f & | vd, | |||
BVH_REAL & | l, | |||
BVH_REAL & | r, | |||
bool | bVF, | |||
BVH_REAL | coeffs[], | |||
Vec3f * | data = NULL | |||
) | [static, private] |
Solve the cubic function using Newton method, also satisfies the interval restriction.
data: only used for EE, return the intersect point
Definition at line 185 of file intersect.cpp.
bool collision_checking::Intersect::solveSquare | ( | BVH_REAL | a, | |
BVH_REAL | b, | |||
BVH_REAL | c, | |||
const Vec3f & | a0, | |||
const Vec3f & | b0, | |||
const Vec3f & | p0, | |||
const Vec3f & | va, | |||
const Vec3f & | vb, | |||
const Vec3f & | vp | |||
) | [static, private] |
Solve a square function for VE intersection (with interval restriction).
Definition at line 398 of file intersect.cpp.
bool collision_checking::Intersect::solveSquare | ( | BVH_REAL | a, | |
BVH_REAL | b, | |||
BVH_REAL | c, | |||
const Vec3f & | a0, | |||
const Vec3f & | b0, | |||
const Vec3f & | c0, | |||
const Vec3f & | d0, | |||
const Vec3f & | va, | |||
const Vec3f & | vb, | |||
const Vec3f & | vc, | |||
const Vec3f & | vd, | |||
bool | bVF, | |||
BVH_REAL * | ret | |||
) | [static, private] |
Solve a square function for EE intersection (with interval restriction).
Definition at line 362 of file intersect.cpp.
const BVH_REAL collision_checking::Intersect::CCD_RESOLUTION = 1e-7 [static, private] |
Definition at line 229 of file intersect.h.
const BVH_REAL collision_checking::Intersect::EPSILON = 1e-5 [static, private] |
Definition at line 227 of file intersect.h.
const unsigned int collision_checking::Intersect::MAX_TRIANGLE_CLIPS = 8 [static, private] |
Definition at line 230 of file intersect.h.
const BVH_REAL collision_checking::Intersect::NEAR_ZERO_THRESHOLD = 1e-7 [static, private] |
Definition at line 228 of file intersect.h.