38 #ifndef FCL_NARROWPHASE_DETAIL_INTERSECT_INL_H
39 #define FCL_NARROWPHASE_DETAIL_INTERSECT_INL_H
57 return (v < getNearZeroThreshold()) && (v > -getNearZeroThreshold());
71 unsigned char min3, min2, min1, max3, max2, max1;
73 min3= *((
unsigned char*)&coeffs[3]+7)>>7; max3=min3^1;
74 min2= *((
unsigned char*)&coeffs[2]+7)>>7; max2=min2^1;
75 min1= *((
unsigned char*)&coeffs[1]+7)>>7; max1=min1^1;
79 S minor = coeffs[3]*v2[min3]*v[min3]+coeffs[2]*v2[min2]+coeffs[1]*v[min1]+coeffs[0];
80 S major = coeffs[3]*v2[max3]*v[max3]+coeffs[2]*v2[max2]+coeffs[1]*v[max1]+coeffs[0];
82 if(major<0)
return false;
83 if(minor>0)
return false;
89 S dminor = 3.0*coeffs[3]*v2[min3]+2.0*coeffs[2]*v[min2]+coeffs[1];
90 S dmajor = 3.0*coeffs[3]*v2[max3]+2.0*coeffs[2]*v[max2]+coeffs[1];
92 if((dminor > 0)||(dmajor < 0))
95 S fm = coeffs[3]*m2*m+coeffs[2]*m2+coeffs[1]*m+coeffs[0];
111 if(nl>
r)
return false;
112 if(nu<l)
return false;
115 if(nu<
r) { l=nl;
r=nu; m=0.5*(l+
r); }
116 else { l=nl; m=0.5*(l+
r); }
120 if(nu<
r) {
r=nu; m=0.5*(l+
r); }
125 if((
r-l)< getCcdResolution())
128 return checkRootValidity_VF(a0, b0, c0, d0, va, vb, vc, vd,
r);
130 return checkRootValidity_EE(a0, b0, c0, d0, va, vb, vc, vd,
r, data);
134 if(solveCubicWithIntervalNewton(a0, b0, c0, d0, va, vb, vc, vd, l,
r, bVF, coeffs, data))
138 return solveCubicWithIntervalNewton(a0, b0, c0, d0, va, vb, vc, vd, l,
r, bVF, coeffs, data);
142 template <
typename S>
153 if((pb.cross(pc)).dot(n) < -getEpsilon())
return false;
154 if((pc.cross(pa)).dot(n) < -getEpsilon())
return false;
155 if((pa.cross(pb)).dot(n) < -getEpsilon())
return false;
161 template <
typename S>
164 return (p - a).dot(p - b) <= 0;
173 template <
typename S>
179 if(fabs(p34[0]) < getEpsilon() && fabs(p34[1]) < getEpsilon() && fabs(p34[2]) < getEpsilon())
183 if(fabs(p12[0]) < getEpsilon() && fabs(p12[1]) < getEpsilon() && fabs(p12[2]) < getEpsilon())
186 S d3134 = p31.dot(p34);
187 S d3412 = p34.dot(p12);
188 S d3112 = p31.dot(p12);
189 S d3434 = p34.dot(p34);
190 S d1212 = p12.dot(p12);
192 S denom = d1212 * d3434 - d3412 * d3412;
193 if(fabs(denom) < getEpsilon())
195 S numer = d3134 * d3412 - d3112 * d3434;
197 *mua = numer / denom;
198 if(*mua < 0 || *mua > 1)
201 *mub = (d3134 + d3412 * (*mua)) / d3434;
202 if(*mub < 0 || *mub > 1)
205 *pa = p1 + p12 * (*mua);
206 *pb = p3 + p34 * (*mub);
211 template <
typename S>
216 return insideTriangle(a0 + va * t, b0 + vb * t, c0 + vc * t, p0 + vp * t);
220 template <
typename S>
231 if(linelineIntersect(a, b, c, d, &p1, &p2, &t_ab, &t_cd))
241 template <
typename S>
246 return insideLineSegment(a0 + va * t, b0 + vb * t, p0 + vp * t);
250 template <
typename S>
257 S discriminant = b * b - 4 * a * c;
261 S sqrt_dis = sqrt(discriminant);
262 S r1 = (-b + sqrt_dis) / (2 * a);
263 bool v1 = (r1 >= 0.0 && r1 <= 1.0) ? ((bVF) ? checkRootValidity_VF(a0, b0, c0, d0, va, vb, vc, vd, r1) : checkRootValidity_EE(a0, b0, c0, d0, va, vb, vc, vd, r1)) :
false;
265 S r2 = (-b - sqrt_dis) / (2 * a);
266 bool v2 = (r2 >= 0.0 && r2 <= 1.0) ? ((bVF) ? checkRootValidity_VF(a0, b0, c0, d0, va, vb, vc, vd, r2) : checkRootValidity_EE(a0, b0, c0, d0, va, vb, vc, vd, r2)) :
false;
270 *ret = (r1 > r2) ? r2 : r1;
288 template <
typename S>
296 return (t >= 0 && t <= 1) ? checkRootValidity_VE(a0, b0, p0, va, vb, vp, t) :
false;
299 S discriminant = b*b-4*a*c;
303 S sqrt_dis = sqrt(discriminant);
305 S r1 = (-b+sqrt_dis) / (2 * a);
306 bool v1 = (r1 >= 0.0 && r1 <= 1.0) ? checkRootValidity_VE(a0, b0, p0, va, vb, vp, r1) :
false;
309 S r2 = (-b-sqrt_dis) / (2 * a);
310 bool v2 = (r2 >= 0.0 && r2 <= 1.0) ? checkRootValidity_VE(a0, b0, p0, va, vb, vp, r2) :
false;
317 template <
typename S>
320 S* a, S* b, S* c, S* d)
329 Vector3<S> vavb_cross_vavc = vavb.cross(vavc);
330 Vector3<S> vavb_cross_a0c0 = vavb.cross(a0c0);
331 Vector3<S> a0b0_cross_vavc = a0b0.cross(vavc);
332 Vector3<S> a0b0_cross_a0c0 = a0b0.cross(a0c0);
334 *a = vavp.dot(vavb_cross_vavc);
335 *b = a0p0.dot(vavb_cross_vavc) + vavp.dot(vavb_cross_a0c0 + a0b0_cross_vavc);
336 *c = vavp.dot(a0b0_cross_a0c0) + a0p0.dot(vavb_cross_a0c0 + a0b0_cross_vavc);
337 *d = a0p0.dot(a0b0_cross_a0c0);
341 template <
typename S>
344 S* a, S* b, S* c, S* d)
352 Vector3<S> vavb_cross_vcvd = vavb.cross(vcvd);
353 Vector3<S> vavb_cross_c0d0 = vavb.cross(c0d0);
354 Vector3<S> a0b0_cross_vcvd = a0b0.cross(vcvd);
355 Vector3<S> a0b0_cross_c0d0 = a0b0.cross(c0d0);
357 *a = vavc.dot(vavb_cross_vcvd);
358 *b = a0c0.dot(vavb_cross_vcvd) + vavc.dot(vavb_cross_c0d0 + a0b0_cross_vcvd);
359 *c = vavc.dot(a0b0_cross_c0d0) + a0c0.dot(vavb_cross_c0d0 + a0b0_cross_vcvd);
360 *d = a0c0.dot(a0b0_cross_c0d0);
364 template <
typename S>
378 *a = L_cross_vbvp.dot(vbva);
379 *b = L_cross_vbvp.dot(b0a0) + L_cross_b0p0.dot(vbva);
380 *c = L_cross_b0p0.dot(b0a0);
384 template <
typename S>
387 S* collision_time,
Vector3<S>* p_i,
bool useNewton)
389 *collision_time = 2.0;
398 computeCubicCoeff_VF(a0, b0, c0, p0, va, vb, vc, vp, &a, &b, &c, &d);
400 if(isZero(a) && isZero(b) && isZero(c) && isZero(d))
412 coeffs[3] = a, coeffs[2] = b, coeffs[1] = c, coeffs[0] = d;
419 if(solveCubicWithIntervalNewton(a0, b0, c0, p0, va, vb, vc, vp, l,
r,
true, coeffs))
421 *collision_time = 0.5 * (l +
r);
428 for(
int i = 0; i < num; ++i)
431 if(r < 0 || r > 1)
continue;
432 if(checkRootValidity_VF(a0, b0, c0, p0, va, vb, vc, vp,
r))
440 if(*collision_time > 1)
445 *p_i = vp * (*collision_time) + p0;
450 template <
typename S>
453 S* collision_time,
Vector3<S>* p_i,
bool useNewton)
455 *collision_time = 2.0;
464 computeCubicCoeff_EE(a0, b0, c0, d0, va, vb, vc, vd, &a, &b, &c, &d);
466 if(isZero(a) && isZero(b) && isZero(c) && isZero(d))
478 coeffs[3] = a, coeffs[2] = b, coeffs[1] = c, coeffs[0] = d;
485 if(solveCubicWithIntervalNewton(a0, b0, c0, d0, va, vb, vc, vd, l,
r,
false, coeffs, p_i))
487 *collision_time = (l +
r) * 0.5;
494 for(
int i = 0; i < num; ++i)
497 if(r < 0 || r > 1)
continue;
499 if(checkRootValidity_EE(a0, b0, c0, d0, va, vb, vc, vd,
r, p_i))
507 if(*collision_time > 1)
516 template <
typename S>
527 computeCubicCoeff_VE(a0, b0, p0, va, vb, vp, L, &a, &b, &c);
529 if(isZero(a) && isZero(b) && isZero(c))
532 return solveSquare(a, b, c, a0, b0, p0, va, vb, vp);
538 template <
typename S>
547 Vector3<S> delta = (b0b1 - a0a1).cross(c0c1 - a0a1);
560 if(A > 0 && B > 0 && (2*C +F) > 0 && (2*D+E) > 0)
562 if(A < 0 && B < 0 && (2*C +F) < 0 && (2*D+E) < 0)
569 template <
typename S>
572 S* collision_time,
Vector3<S>* p_i,
bool useNewton)
574 if(intersectPreFiltering(a0, b0, c0, p0, a1, b1, c1, p1))
576 return intersect_VF(a0, b0, c0, p0, a1, b1, c1, p1, collision_time, p_i, useNewton);
583 template <
typename S>
586 S* collision_time,
Vector3<S>* p_i,
bool useNewton)
588 if(intersectPreFiltering(a0, b0, c0, d0, a1, b1, c1, d1))
590 return intersect_EE(a0, b0, c0, d0, a1, b1, c1, d1, collision_time, p_i, useNewton);
597 template <
typename S>
608 unsigned int* num_contact_points,
609 S* penetration_depth,
616 return intersect_Triangle(P1, P2, P3, Q1_, Q2_, Q3_, contact_points, num_contact_points, penetration_depth, normal);
620 template <
typename S>
630 unsigned int* num_contact_points,
631 S* penetration_depth,
638 return intersect_Triangle(P1, P2, P3, Q1_, Q2_, Q3_, contact_points, num_contact_points, penetration_depth, normal);
642 template <
typename S>
647 unsigned int* num_contact_points,
648 S* penetration_depth,
653 bool b1 = buildTrianglePlane(P1, P2, P3, &n1, &t1);
654 if(!b1)
return false;
658 bool b2 = buildTrianglePlane(Q1, Q2, Q3, &n2, &t2);
659 if(!b2)
return false;
661 if(sameSideOfPlane(P1, P2, P3, n2, t2))
664 if(sameSideOfPlane(Q1, Q2, Q3, n1, t1))
667 Vector3<S> clipped_points1[getMaxTriangleClips()];
668 unsigned int num_clipped_points1 = 0;
669 Vector3<S> clipped_points2[getMaxTriangleClips()];
670 unsigned int num_clipped_points2 = 0;
672 Vector3<S> deepest_points1[getMaxTriangleClips()];
673 unsigned int num_deepest_points1 = 0;
674 Vector3<S> deepest_points2[getMaxTriangleClips()];
675 unsigned int num_deepest_points2 = 0;
676 S penetration_depth1 = -1, penetration_depth2 = -1;
678 clipTriangleByTriangleAndEdgePlanes(Q1, Q2, Q3, P1, P2, P3, n1, t1, clipped_points2, &num_clipped_points2);
680 if(num_clipped_points2 == 0)
683 computeDeepestPoints(clipped_points2, num_clipped_points2, n1, t1, &penetration_depth2, deepest_points2, &num_deepest_points2);
684 if(num_deepest_points2 == 0)
687 clipTriangleByTriangleAndEdgePlanes(P1, P2, P3, Q1, Q2, Q3, n2, t2, clipped_points1, &num_clipped_points1);
688 if(num_clipped_points1 == 0)
691 computeDeepestPoints(clipped_points1, num_clipped_points1, n2, t2, &penetration_depth1, deepest_points1, &num_deepest_points1);
692 if(num_deepest_points1 == 0)
697 if(contact_points && num_contact_points && penetration_depth && normal)
699 if(penetration_depth1 > penetration_depth2)
701 *num_contact_points = num_deepest_points2;
702 for(
unsigned int i = 0; i < num_deepest_points2; ++i)
704 contact_points[i] = deepest_points2[i];
708 *penetration_depth = penetration_depth2;
712 *num_contact_points = num_deepest_points1;
713 for(
unsigned int i = 0; i < num_deepest_points1; ++i)
715 contact_points[i] = deepest_points1[i];
719 *penetration_depth = penetration_depth1;
727 template <
typename S>
732 unsigned int* num_contact_points,
733 S* penetration_depth,
746 if (!project6(n1, p1, p2, p3, q1, q2, q3))
return false;
751 if (!project6(m1, p1, p2, p3, q1, q2, q3))
return false;
754 if (!project6(ef11, p1, p2, p3, q1, q2, q3))
return false;
757 if (!project6(ef12, p1, p2, p3, q1, q2, q3))
return false;
761 if (!project6(ef13, p1, p2, p3, q1, q2, q3))
return false;
764 if (!project6(ef21, p1, p2, p3, q1, q2, q3))
return false;
767 if (!project6(ef22, p1, p2, p3, q1, q2, q3))
return false;
770 if (!project6(ef23, p1, p2, p3, q1, q2, q3))
return false;
774 if (!project6(ef31, p1, p2, p3, q1, q2, q3))
return false;
777 if (!project6(ef32, p1, p2, p3, q1, q2, q3))
return false;
780 if (!project6(ef33, p1, p2, p3, q1, q2, q3))
return false;
783 if (!project6(g1, p1, p2, p3, q1, q2, q3))
return false;
786 if (!project6(g2, p1, p2, p3, q1, q2, q3))
return false;
789 if (!project6(g3, p1, p2, p3, q1, q2, q3))
return false;
792 if (!project6(h1, p1, p2, p3, q1, q2, q3))
return false;
795 if (!project6(h2, p1, p2, p3, q1, q2, q3))
return false;
798 if (!project6(h3, p1, p2, p3, q1, q2, q3))
return false;
800 if(contact_points && num_contact_points && penetration_depth && normal)
804 buildTrianglePlane(P1, P2, P3, &n1, &t1);
805 buildTrianglePlane(Q1, Q2, Q3, &n2, &t2);
808 unsigned int num_deepest_points1 = 0;
810 unsigned int num_deepest_points2 = 0;
811 S penetration_depth1, penetration_depth2;
816 computeDeepestPoints(Q, 3, n1, t1, &penetration_depth2, deepest_points2, &num_deepest_points2);
817 computeDeepestPoints(P, 3, n2, t2, &penetration_depth1, deepest_points1, &num_deepest_points1);
820 if(penetration_depth1 > penetration_depth2)
822 *num_contact_points =
std::min(num_deepest_points2, (
unsigned int)2);
823 for(
unsigned int i = 0; i < *num_contact_points; ++i)
825 contact_points[i] = deepest_points2[i];
829 *penetration_depth = penetration_depth2;
833 *num_contact_points =
std::min(num_deepest_points1, (
unsigned int)2);
834 for(
unsigned int i = 0; i < *num_contact_points; ++i)
836 contact_points[i] = deepest_points1[i];
840 *penetration_depth = penetration_depth1;
848 template <
typename S>
851 *num_deepest_points = 0;
853 unsigned int num_deepest_points_ = 0;
854 unsigned int num_neg = 0;
855 unsigned int num_pos = 0;
856 unsigned int num_zero = 0;
858 for(
unsigned int i = 0; i < num_clipped_points; ++i)
860 S dist = -distanceToPlane(n, t, clipped_points[i]);
861 if(dist > getEpsilon()) num_pos++;
862 else if(dist < -getEpsilon()) num_neg++;
867 num_deepest_points_ = 1;
868 deepest_points[num_deepest_points_ - 1] = clipped_points[i];
870 else if(dist + 1e-6 >= max_depth)
872 num_deepest_points_++;
873 deepest_points[num_deepest_points_ - 1] = clipped_points[i];
877 if(max_depth < -getEpsilon())
878 num_deepest_points_ = 0;
880 if(num_zero == 0 && ((num_neg == 0) || (num_pos == 0)))
881 num_deepest_points_ = 0;
883 *penetration_depth = max_depth;
884 *num_deepest_points = num_deepest_points_;
888 template <
typename S>
892 Vector3<S> clipped_points[],
unsigned int* num_clipped_points,
895 *num_clipped_points = 0;
898 unsigned int num_temp_clip = 0;
899 unsigned int num_temp_clip2 = 0;
905 if(buildEdgePlane(t1, t2, tn, &plane_n, &plane_dist))
907 clipPolygonByPlane(v, 3, plane_n, plane_dist, temp_clip, &num_temp_clip);
908 if(num_temp_clip > 0)
910 if(buildEdgePlane(t2, t3, tn, &plane_n, &plane_dist))
912 clipPolygonByPlane(temp_clip, num_temp_clip, plane_n, plane_dist, temp_clip2, &num_temp_clip2);
913 if(num_temp_clip2 > 0)
915 if(buildEdgePlane(t3, t1, tn, &plane_n, &plane_dist))
920 clipPolygonByPlane(temp_clip2, num_temp_clip2, plane_n, plane_dist, temp_clip, &num_temp_clip);
921 if(num_temp_clip > 0)
923 clipPolygonByPlane(temp_clip, num_temp_clip, tn, to, clipped_points, num_clipped_points);
928 clipPolygonByPlane(temp_clip2, num_temp_clip2, plane_n, plane_dist, clipped_points, num_clipped_points);
938 template <
typename S>
941 *num_clipped_points = 0;
943 unsigned int num_clipped_points_ = 0;
945 unsigned int prev_classify = 2;
946 unsigned int classify;
947 for(
unsigned int i = 0; i <= num_polygon_points; ++i)
949 vi = (i % num_polygon_points);
950 S d = distanceToPlane(n, t, polygon_points[i]);
951 classify = ((d > getEpsilon()) ? 1 : 0);
954 if(prev_classify == 1)
956 if(num_clipped_points_ < getMaxTriangleClips())
959 clipSegmentByPlane(polygon_points[i - 1], polygon_points[vi], n, t, &tmp);
960 if(num_clipped_points_ > 0)
962 if((tmp - clipped_points[num_clipped_points_ - 1]).squaredNorm() > getEpsilon())
964 clipped_points[num_clipped_points_] = tmp;
965 num_clipped_points_++;
970 clipped_points[num_clipped_points_] = tmp;
971 num_clipped_points_++;
976 if(num_clipped_points_ < getMaxTriangleClips() && i < num_polygon_points)
978 clipped_points[num_clipped_points_] = polygon_points[vi];
979 num_clipped_points_++;
984 if(prev_classify == 0)
986 if(num_clipped_points_ < getMaxTriangleClips())
989 clipSegmentByPlane(polygon_points[i - 1], polygon_points[vi], n, t, &tmp);
990 if(num_clipped_points_ > 0)
992 if((tmp - clipped_points[num_clipped_points_ - 1]).squaredNorm() > getEpsilon())
994 clipped_points[num_clipped_points_] = tmp;
995 num_clipped_points_++;
1000 clipped_points[num_clipped_points_] = tmp;
1001 num_clipped_points_++;
1007 prev_classify = classify;
1010 if(num_clipped_points_ > 2)
1012 if((clipped_points[0] - clipped_points[num_clipped_points_ - 1]).squaredNorm() < getEpsilon())
1014 num_clipped_points_--;
1018 *num_clipped_points = num_clipped_points_;
1022 template <
typename S>
1025 S dist1 = distanceToPlane(n, t, v1);
1027 S dist2 = tmp.dot(n);
1028 *clipped_point = tmp * (-dist1 / dist2) + v1;
1032 template <
typename S>
1035 return n.dot(v) - t;
1039 template <
typename S>
1043 bool can_normalize =
false;
1056 template <
typename S>
1060 bool can_normalize =
false;
1073 template <
typename S>
1076 S dist1 = distanceToPlane(n, t, v1);
1077 S dist2 = dist1 * distanceToPlane(n, t, v2);
1078 S dist3 = dist1 * distanceToPlane(n, t, v3);
1079 if((dist2 > 0) && (dist3 > 0))
1085 template <
typename S>
1099 if(mn1 > mx2)
return 0;
1104 if(mn2 > mx1)
return 0;
1109 template <
typename S>
1112 return 0.5 * std::erfc(-x / sqrt(2.0));
1116 template <
typename S>
1123 template <
typename S>
1130 template <
typename S>
1137 template <
typename S>