TriOverlap.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, AIST, the University of Tokyo and General Robotix Inc.
00003  * All rights reserved. This program is made available under the terms of the
00004  * Eclipse Public License v1.0 which accompanies this distribution, and is
00005  * available at http://www.eclipse.org/legal/epl-v10.html
00006  * Contributors:
00007  * National Institute of Advanced Industrial Science and Technology (AIST)
00008  * General Robotix Inc. 
00009  */
00010 //
00011 // TriOverlap.cpp
00012 //
00013 
00014 #include "CollisionPairInserterBase.h"
00015 #include <cmath>
00016 #include <cstdio>
00017 #include <iostream>
00018 
00019 using namespace std;
00020 using namespace hrp;
00021 
00022 HRP_COLLISION_EXPORT int tri_tri_overlap(
00023     const Vector3& P1,
00024     const Vector3& P2,
00025     const Vector3& P3,
00026     const Vector3& Q1,
00027     const Vector3& Q2,
00028     const Vector3& Q3,
00029     collision_data* col_p,
00030     CollisionPairInserterBase* collisionPairInserter);
00031 
00032 
00033 namespace {
00034 
00035     const bool HIRUKAWA_DEBUG = false;
00036 
00037     /* used in normal_test */
00038     enum { NOT_INTERSECT = 0,
00039            EDGE1_NOT_INTERSECT = 1,
00040            EDGE2_NOT_INTERSECT = 2,
00041            EDGE3_NOT_INTERSECT = 3 };
00042 
00043     /* used in cross_test */
00044     const int INTERSECT = 1;
00045 }
00046 
00047 
00048 /**********************************************************     
00049   separability test by the supporting plane of a triangle
00050    return value 
00051    0   : not intersect
00052    1   : f1 or e1 doesn't intersect
00053    2   : f2 or e2 doesn't intersect
00054    3   : f3 or e3 doesn't intersect
00055 **********************************************************/     
00056 static int separability_test_by_face(const Vector3& nm)
00057 {
00058     if(nm[0] < 0.0 && nm[1] < 0.0 && nm[2] < 0.0 ||
00059        nm[0] > 0.0 && nm[1] > 0.0 && nm[2] > 0.0){
00060         return NOT_INTERSECT;
00061     }
00062     if(nm[0] < 0.0 && nm[1] < 0.0 && nm[2] > 0.0 ||
00063        nm[0] > 0.0 && nm[1] > 0.0 && nm[2] < 0.0){
00064         return EDGE1_NOT_INTERSECT;
00065     }
00066     if(nm[0] < 0.0 && nm[1] > 0.0 && nm[2] > 0.0 ||
00067        nm[0] > 0.0 && nm[1] < 0.0 && nm[2] < 0.0){
00068         return EDGE2_NOT_INTERSECT;
00069     }
00070     if(nm[0] > 0.0 && nm[1] < 0.0 && nm[2] > 0.0 ||
00071        nm[0] < 0.0 && nm[1] > 0.0 && nm[2] < 0.0){
00072         return EDGE3_NOT_INTERSECT;
00073     }
00074     return 0;
00075 }
00076 
00077 
00078 /**********************************************************
00079    triangle inside test:
00080    normal vector is cross product of ei*fj
00081 ***********************************************************/
00082 static int triangle_inside_test(
00083     const Vector3& ef1,
00084     const Vector3& ef2,
00085     const Vector3& ef3,
00086     const Vector3& P3,
00087     const Vector3& P1,
00088     const Vector3& P2,
00089     const Vector3& Q)
00090 {       
00091     double ef1P1 = ef1.dot(P1); /*project P1 on ef1*/
00092     double ef1P3 = ef1.dot(P3); /*project P3 on ef1*/
00093     double ef1Q  = ef1.dot(Q);  /*project Q on ef1*/
00094 
00095     double ef2P2 = ef2.dot(P2); /*project P2 on ef2*/
00096     double ef2P1 = ef2.dot(P1); /*project P1 on ef2*/   
00097     double ef2Q  = ef2.dot(Q);   /*project Q on ef2*/
00098 
00099     double ef3P3 = ef3.dot(P3);  /*project P3 on ef3*/  
00100     double ef3P2 = ef3.dot(P2);  /*project P2 on ef3*/          
00101     double ef3Q  = ef3.dot(Q);   /*project Q on ef3*/           
00102 
00103     if((ef1P3 > ef1P1 && ef1Q > ef1P1   ||
00104         ef1P3 < ef1P1 && ef1Q < ef1P1     ) 
00105        &&
00106        (ef2P1 > ef2P2 && ef2Q > ef2P2   ||
00107         ef2P1 < ef2P2 && ef2Q < ef2P2     ) 
00108        &&
00109        (ef3P2 > ef3P3 && ef3Q > ef3P3   ||
00110         ef3P2 < ef3P3 && ef3Q < ef3P3     )) {
00111         return INTERSECT;
00112     }
00113 
00114     return NOT_INTERSECT;
00115 }
00116 
00117 
00118 static void find_intersection_pt(
00119     Vector3& ipt,
00120     const Vector3& x1,
00121     const Vector3& x2,
00122     double mn1, 
00123     double mn2)
00124 {
00125     if(mn1 == mn2) /*exit(0);*/ return;
00126 
00127     if(mn1 >0 && mn2 < 0){
00128         ipt = (-(mn2*x1) + mn1*x2)/(mn1-mn2);
00129     }else if(mn1 < 0 && mn2 > 0){
00130         ipt = (mn2*x1 - mn1*x2)/(-mn1+mn2);
00131     }
00132 }
00133 
00134 
00135 static inline void find_intersection_pt(
00136     Vector3& ipt,
00137     const Vector3& x1,
00138     const Vector3& x2,
00139     double p)
00140 {
00141     ipt = (1.0 - p) * x1 + p * x2;
00142 
00143     if(HIRUKAWA_DEBUG){
00144         cout << "v1 = " << x1[0] << ", " << x1[1] << ", " << x1[2] << endl; 
00145         cout << "v2 = " << x2[0] << ", " << x2[1] << ", " << x2[2] << endl;
00146         cout << "edge = " << x2[0]-x1[0] << ", " << x2[1]-x1[1] << ", "
00147              << x2[2]-x1[2] << endl;
00148         cout << "common pt = " << ipt[0] << " " << ipt[1] << " " << ipt[2] << endl;
00149     }
00150 }
00151 
00152 
00153 //
00154 // Calculate the depth of the intersection between two triangles
00155 //
00156 static inline double calc_depth(
00157     const Vector3& ip1,
00158     const Vector3& ip2,
00159     const Vector3& n)
00160 {
00161     // vecNormalize(n);
00162 
00163     if(HIRUKAWA_DEBUG){
00164         cout << "calc_depth 1 = " << (ip1 - ip2).dot(n) << endl;
00165     }
00166     
00167     return fabs((ip1 - ip2).dot(n));
00168 }
00169 
00170 
00171 static double calc_depth(
00172     const Vector3& ip1,
00173     const Vector3& ip2,
00174     const Vector3& pt1,
00175     const Vector3& pt2,
00176     const Vector3& pt3,
00177     const Vector3& n)
00178 {
00179     // when a triangle penetrates another triangle at two intersection points
00180     // and the separating plane is the supporting plane of the penetrated triangle
00181     
00182     // vecNormalize(n);
00183     
00184     double d1 = fabs((ip1 - pt1).dot(n));
00185     double d2 = fabs((ip2 - pt2).dot(n));
00186     double d3 = fabs((ip1 - pt3).dot(n)); // ip1 can be either ip1 or ip2
00187     
00188     double depth = (d1 < d2) ? d2 : d1;
00189     if(d3 < depth){
00190         depth = d3;
00191     }
00192     
00193     if(HIRUKAWA_DEBUG){
00194         cout << "calc_depth 3 = " << depth << endl;
00195     }
00196     
00197     return depth;
00198 }
00199 
00200 
00201 static void find_foot(
00202     const Vector3& ip,
00203     const Vector3& pt1,
00204     const Vector3& pt2,
00205     Vector3& f)
00206 {
00207     /*
00208     double u, v, w, p;
00209 
00210     u = pt2[0] - pt1[0]; v = pt2[1] - pt1[1]; w = pt2[2] - pt1[2];
00211     
00212     p = u * (ip[0] - pt1[0]) + v * (ip[1] - pt1[1]) + w * (ip[2] - pt1[2]);
00213     p /= u * u + v * v + w * w;
00214     
00215     f[0] = pt1[0] + u * p; f[1] = pt1[1] + v * p; f[2] = pt1[2] + w * p;
00216     */
00217 
00218     const Vector3 pt(pt2 - pt1);
00219     const double p = pt.dot(ip - pt1) / pt.dot(pt);
00220     f = pt1 + p * pt;
00221 }
00222 
00223 
00224 static double calc_depth(
00225     const Vector3& ip,
00226     const Vector3& pt1,
00227     const Vector3& pt2,
00228     const Vector3& pt3,
00229     const Vector3& n)
00230 {
00231     Vector3 f12, f23, f31;
00232     
00233     find_foot(ip, pt1, pt2, f12);
00234     find_foot(ip, pt2, pt3, f23);
00235     find_foot(ip, pt3, pt1, f31);
00236     
00237     if(HIRUKAWA_DEBUG){
00238         cout << "ip = " << ip[0] << " " << ip[1] << " " << ip[2] << endl;
00239         cout << "f12 = " << f12[0] << " " << f12[1] << " " << f12[2] << endl;
00240         cout << "f23 = " << f23[0] << " " << f23[1] << " " << f23[2] << endl;
00241         cout << "f31 = " << f31[0] << " " << f31[1] << " " << f31[2] << endl;
00242     }
00243     
00244     // fabs() is taken to cope with numerical error of find_foot()
00245     const double d1 = fabs((f12 - ip).dot(n));
00246     const double d2 = fabs((f23 - ip).dot(n));
00247     const double d3 = fabs((f31 - ip).dot(n));
00248     
00249     // cout << "d1 d2 d3 = " << d1 << " " << d2 << " " << d3 << endl;
00250     // dsum = fabs(d1)+fabs(d2)+fabs(d3);
00251     // if(d1<0.0) d1=dsum; if(d2<0.0) d2=dsum; if(d3<0.0) d3=dsum;
00252     
00253     double depth = (d1 < d2) ? d1 : d2;
00254     if(d3 < depth){
00255         depth = d3;
00256     }
00257     
00258     if(HIRUKAWA_DEBUG){
00259         cout << "calc_depth 4 = " << depth << endl;
00260     }
00261     
00262     return depth;
00263 }
00264 
00265 
00266 static double calc_depth2(
00267     const Vector3& ip1,
00268     const Vector3& ip2,
00269     const Vector3& pt1,
00270     const Vector3& pt2,
00271     const Vector3& pt3,
00272     const Vector3& n)
00273 {
00274     // when a triangle penetrates another triangle at two intersecting points
00275     // and the separating plane is the supporting plane of the penetrating triangle
00276     
00277     const Vector3 nn(n); // vecNormalize(nn);
00278     
00279     const double depth1 = calc_depth(ip1, pt1, pt2, pt3, nn);
00280     const double depth2 = calc_depth(ip2, pt1, pt2, pt3, nn);
00281     
00282     // cout << "depth1 depth2 = " << depth1 << " " << depth2 << endl;
00283     const double depth = (depth1 < depth2) ? depth2 : depth1;
00284     
00285     if(HIRUKAWA_DEBUG){
00286         cout << "calc_depth 5 = " << depth << endl;
00287     }
00288     
00289     return depth;
00290 }
00291 
00292 
00293 static void calcNormal(
00294     Vector3& vec,
00295     const Vector3& v1,
00296     const Vector3& v2,
00297     const Vector3& v3,
00298     double sgn)
00299 {
00300     // find the vector from v1 to the mid point of v2 and v3 when 0<sgn
00301     
00302     if(sgn < 0){
00303         vec = -(v1 - 0.5 * (v2 + v3)).normalized();
00304     } else {
00305         vec =  (v1 - 0.5 * (v2 + v3)).normalized();
00306     }
00307 }
00308 
00309 
00310 static int find_common_perpendicular(
00311     const Vector3& p1,
00312     const Vector3& p2,
00313     const Vector3& q1,
00314     const Vector3& q2,
00315     const Vector3& ip1,
00316     const Vector3& ip2,
00317     const Vector3& n1,
00318     const Vector3& m1,
00319     const Vector3& n_vector,
00320     double& dp)
00321 {
00322     const double eps = 1.0e-3; // threshold to consider two edges are parallel
00323     //const double vn = 1.0e-2;  // threshold to judge an intersecting point is near a vertex
00324 
00325     const Vector3 e(p2 - p1);
00326     const Vector3 f(q2 - q1);
00327 
00328     const double c11 = e.dot(e);
00329     const double c12 = - e.dot(f);
00330     const double c21 = - c12;
00331     const double c22 = - f.dot(f);
00332 
00333     const double det = c11 * c22 - c12 * c21;
00334     // cout << "det = " << det << endl;
00335 
00336     if(fabs(det) < eps){
00337         return 0;
00338     } else {
00339         const Vector3 g(q1 - p1);
00340         const double a = e.dot(g);
00341         const double b = f.dot(g);
00342         const double t1 = ( c22 * a - c12 * b) / det;
00343         const double t2 = (-c21 * a + c11 * b) / det;
00344 
00345         // quit if the foot of the common perpendicular is not on an edge
00346         if(t1<0 || 1<t1 || t2<0 || 1<t2) return 0;
00347 
00348         // when two edges are in contact near a vertex of an edge
00349         // if(t1<vn || 1.0-vn<t1 || t2<vn || 1.0-vn<t2) return 0;
00350 
00351         // find_intersection_pt(v1, p1, p2, t1);
00352         // find_intersection_pt(v2, q1, q2, t2);
00353    
00354         dp = calc_depth(ip1, ip2, n_vector); 
00355 
00356         return 1;
00357     }
00358 }
00359     
00360 
00361 // for vertex-face contact
00362 static inline int get_normal_vector_test(
00363     const Vector3& ip1,
00364     const Vector3& v1,
00365     const Vector3& ip2,
00366     const Vector3& v2,
00367     const Vector3& n1,
00368     const Vector3& m1)
00369 {
00370     // ip1 and ip2 are the intersecting points
00371     // v1 and v2 are the vertices of the penetrating triangle
00372     // note that (v1-ip1) (v2-ip2) lies on the penetrating triangle
00373     
00374     // eps_applicability = 0.965926; // Cos(15) threshold to consider two triangles face
00375     const double eps_applicability = 0.5; // Cos(60) threshold to consider two triangles face
00376     
00377     // This condition should be checked mildly because the whole sole of a foot
00378     // may sink inside the floor and then no collision is detected.
00379     return (eps_applicability < n1.dot(m1)) ? 0 : 1;
00380 }
00381 
00382 
00383 // for edge-edge contact
00384 static int get_normal_vector_test(
00385     Vector3& n_vector,
00386     const Vector3& ef0,
00387     const Vector3& ip,
00388     const Vector3& iq,
00389     const Vector3& v1,
00390     const Vector3& v2,
00391     const Vector3& n1,
00392     const Vector3& m1,
00393     const Vector3& va1,
00394     const Vector3& va2,
00395     const Vector3& vb1,
00396     const Vector3& vb2)
00397 {
00398     // ip is the intersecting point on triangle p1p2p3
00399     // iq is the intersecting point on triangle q1q2q3
00400     // v1 is the vertex of p1p2p3 which is not on the intersecting edge
00401     // v2 is the vertex of q1q2q3 which is not on the intersecting edge
00402     // note that (v1-ip) lies on triangle p1p2p3 and (v2-iq) on q1q2q3
00403 
00404     const double eps_applicability = 0.0; // 1.52e-2; // threshold to consider two triangles face
00405     const double eps_length = 1.0e-3; // 1mm: thereshold to consider the intersecting edge is short
00406     const double eps_theta = 1.0e-1;   // threshold to consider cos(theta) is too small 
00407 
00408     // quit if two triangles does not satifsy the applicability condition
00409     // i.e. two triangles do not face each other
00410     if(- eps_applicability < n1.dot(m1)) return 0;
00411     
00412     const double ea_length = (va1 - va2).norm();
00413     const double eb_length = (vb1 - vb2).norm();
00414     
00415     // return the normal vector of a triangle if an intersecting edge is too short
00416     if(ea_length < eps_length || eb_length < eps_length){
00417         // cout << "edge is too short" << endl;
00418         if(ea_length < eb_length) {
00419             n_vector = m1;
00420         } else {
00421             n_vector = -n1;
00422         }
00423         return 1;
00424     }
00425 
00426     const Vector3 sv1(v1 - ip);
00427     const double sv1_norm = sv1.norm();
00428     const Vector3 sv2(v2 - iq);
00429     const double sv2_norm = sv2.norm();
00430 
00431     if(eps_length < sv1_norm && eps_length < sv2_norm){
00432         // quit if two triangles do not satisfy the applicability conditions
00433         if(- eps_applicability < sv1.dot(sv2) / (sv1_norm * sv2_norm)){
00434             return 0;
00435         }
00436     }
00437 
00438     // now neither of two edges is not too short
00439     Vector3 ef(ef0.normalized());
00440 
00441     // Triangle p1p2p3
00442     const double theta1 = ef.dot(n1) / n1.norm();
00443     const double theta1_abs = fabs(theta1);
00444     
00445     double theta2;
00446     double theta2_abs;
00447     if(eps_length < sv1_norm){
00448         theta2 = ef.dot(sv1) / sv1_norm;
00449         theta2_abs = fabs(theta2);
00450     } else {
00451         theta2 = 0.0;
00452         theta2_abs = 0.0;
00453     }
00454     
00455     // triangle q1q2q3
00456     const double theta3 = ef.dot(m1) / m1.norm();
00457     const double theta3_abs = fabs(theta3);
00458     
00459     double theta4;
00460     double theta4_abs;
00461     if(eps_length < sv2_norm){
00462         theta4 = ef.dot(sv2) / sv2_norm;
00463         theta4_abs = fabs(theta4);
00464     } else {
00465         theta4 = 0.0;
00466         theta4_abs = 0.0;
00467     }
00468 
00469     if(sv1_norm < eps_length || sv2_norm < eps_length){
00470         // when sv1 or sv2 is too short
00471         // cout << "sv is too short" << endl;
00472         if(theta1_abs < theta3_abs){
00473             n_vector = m1;
00474         } else {
00475             n_vector = -n1;
00476         }
00477         return 1;    
00478     }
00479 
00480     if(theta2_abs < eps_theta && theta4_abs < eps_theta){
00481         // when two triangles are coplanar
00482         // proof.
00483         //  ef = (va2-va1)x(vb2-vb1) (1)
00484         //  sv1 * ef = 0             (2)
00485         //  sv2 * ef = 0             
00486         //  substituting (1) to (2),
00487         //    sv1 * (va2-va1) x (vb2-vb1) = 0
00488         //    (vb2 - vb1) * sv1 x (va2 - va1) = 0
00489         //  considering sv1 x (va2 - va1) = n,
00490         //    (vb2 - vb1) * n = 0
00491         //  in the same way
00492         //    (va2 - va1) * m = 0
00493         // q.e.d.
00494 
00495         if(theta1_abs < theta3_abs){
00496             n_vector = m1;
00497             return 1;
00498         } else{
00499             n_vector = -n1;
00500             return 1;
00501         }
00502     }
00503 
00504     // return 0 if the plane which passes through ip with normal vector ef
00505     // does not separate v1 and v2
00506     if(-eps_applicability < theta2 * theta4) return 0;
00507 
00508     //
00509     // regular case
00510     //
00511     double theta12;
00512     if(theta1_abs < theta2_abs){
00513         theta12 = theta2;
00514     } else {
00515         theta12 = -1.0 * theta1;
00516     }
00517 
00518     double theta34;
00519     if(theta3_abs < theta4_abs){
00520         theta34 = -1.0 * theta4;
00521     } else {
00522         theta34 = theta3;
00523     }
00524 
00525     double theta;
00526     if(fabs(theta12) < fabs(theta34)){
00527         theta = theta34;
00528     } else {
00529         theta = theta12;
00530     }
00531 
00532     if(0 < theta){
00533         n_vector = ef;
00534     } else {
00535         n_vector = -ef;
00536     }
00537 
00538     if(HIRUKAWA_DEBUG){
00539         cout << "va1=" << va1[0] << " " << va1[1] << " " << va1[2] << endl;
00540         cout << "va2=" << va2[0] << " " << va2[1] << " " << va2[2] << endl;
00541         cout << "va3=" << v1[0] << " " << v1[1] << " " << v1[2] << endl;
00542         cout << "vb1=" << vb1[0] << " " << vb1[1] << " " << vb1[2] << endl;
00543         cout << "vb2=" << vb2[0] << " " << vb2[1] << " " << vb2[2] << endl;
00544         cout << "vb3=" << v2[0] << " " << v2[1] << " " << v2[2] << endl;
00545         cout << "n1=" << n1[0] << " " << n1[1] << " " << n1[2] << endl;
00546         cout << "m1=" << m1[0] << " " << m1[1] << " " << m1[2] << endl;
00547         cout << "ef=" << ef[0] << " " << ef[1] << " " << ef[2] << endl;
00548         cout << "sv1=" << sv1[0] << " " << sv1[1] << " " << sv1[2] << endl;
00549         cout << "sv2=" << sv2[0] << " " << sv2[1] << " " << sv2[2] << endl;
00550         cout << endl;
00551     }
00552 
00553     if(n_vector.dot(sv1) < eps_applicability || - eps_applicability < n_vector.dot(sv2)){
00554         // when the separating plane separates the outsides of the triangles
00555         return 0;
00556     } else {
00557         return 1;
00558     }
00559 }
00560 
00561 
00562 //
00563 // find the collision info when a vertex penetrates a face
00564 //
00565 static int find_collision_info(
00566     const Vector3& p1,
00567     const Vector3& p2,
00568     const Vector3& p3,
00569     double mp0,
00570     double mp1,
00571     double mp2,
00572     const Vector3& q1,
00573     const Vector3& q2,
00574     const Vector3& q3,
00575     const Vector3& f1,
00576     const Vector3& f2,
00577     const Vector3& f3,
00578     const Vector3& n1,
00579     const Vector3& m1,
00580     Vector3& ip3,
00581     Vector3& ip4,
00582     Vector3& ip5, /* unused ? */
00583     Vector3& ip6, /* unused ? */
00584     collision_data* col_p, double pq)
00585 {
00586     Vector3 ip1;
00587     find_intersection_pt(ip1, p1, p2, mp0, mp1);
00588     Vector3 ip2;
00589     find_intersection_pt(ip2, p3, p1, mp2, mp0);
00590     
00591     if(get_normal_vector_test(ip1, p2, ip2, p3, m1, n1)){
00592 
00593         Vector3 vec;
00594         calcNormal(vec, p1, p2, p3, mp0);
00595         
00596         col_p->n_vector = m1 * pq;
00597 
00598         //
00599         // The depth is estimated in InsertCollisionPair.cpp
00600         // The following depth calculation is done only for debugging purpose
00601         //
00602         col_p->depth = calc_depth(ip1, ip2, p2, p3, p1, col_p->n_vector);
00603         const Vector3 nv(-n1 * pq);
00604         const double dp = calc_depth2(ip1, ip2, q1, q2, q3, nv);
00605         if(dp < col_p->depth){
00606             col_p->depth = dp;
00607         }
00608 
00609         ip3 = ip1; ip4 = ip2;
00610         col_p->num_of_i_points = 2;
00611 
00612         return 1;
00613     }
00614 
00615     return 0;
00616 }
00617 
00618 
00619 //
00620 // find the collision info when an edges penetrate a face each other 
00621 //
00622 static int find_collision_info(
00623     const Vector3& p1,
00624     const Vector3& p2,
00625     const Vector3& p3,
00626     double mp0,
00627     double mp1,
00628     const Vector3& q1,
00629     const Vector3& q2,
00630     const Vector3& q3,
00631     double nq0,
00632     double nq1,
00633     const Vector3& ef11,
00634     const Vector3& n1,
00635     const Vector3& m1,
00636     Vector3& ip3,
00637     Vector3& ip4,
00638     collision_data *col_p)
00639 {
00640     Vector3 ip1;
00641     find_intersection_pt(ip1, q1, q2, nq0, nq1);
00642     Vector3 ip2;
00643     find_intersection_pt(ip2, p1, p2, mp0, mp1);
00644 
00645     double dp;
00646     if(get_normal_vector_test(col_p->n_vector, ef11, ip2, ip1, p3, q3, n1, m1, p1, p2, q1, q2) &&
00647        find_common_perpendicular(p1, p2, q1, q2, ip1, ip2, n1, m1, col_p->n_vector, dp)){
00648 
00649         ip3 = ip1; ip4 = ip2;
00650         col_p->num_of_i_points = 2;
00651         col_p->depth = dp;
00652         return 1;
00653     }
00654 
00655     return 0;
00656 }
00657 
00658 
00659 // very robust triangle intersection test
00660 // uses no divisions
00661 // works on coplanar triangles
00662 
00663 int tri_tri_overlap(
00664     const Vector3& P1,
00665     const Vector3& P2,
00666     const Vector3& P3,
00667     const Vector3& Q1,
00668     const Vector3& Q2,
00669     const Vector3& Q3,
00670     collision_data* col_p,
00671     CollisionPairInserterBase* collisionPairInserter) 
00672 {
00673     /*
00674       One triangle is (p1,p2,p3).  Other is (q1,q2,q3).
00675       Edges are (e1,e2,e3) and (f1,f2,f3).
00676       Normals are n1 and m1
00677       Outwards are (g1,g2,g3) and (h1,h2,h3).
00678      
00679       We assume that the triangle vertices are in the same coordinate system.
00680 
00681       First thing we do is establish a new c.s. so that p1 is at (0,0,0).
00682 
00683     */
00684     Vector3 p1, p2, p3;
00685     Vector3 q1, q2, q3;
00686     Vector3 e1, e2, e3;
00687     Vector3 f1, f2, f3;
00688     // Vector3 g1, g2, g3;
00689     // Vector3 h1, h2, h3;
00690     Vector3 n1, m1;
00691     Vector3 z;
00692     Vector3 nq, mp;
00693 
00694     int triP,triQ;
00695     int edf1, edf2, edf3, ede1, ede2, ede3;
00696 
00697     Vector3 ef11, ef12, ef13;
00698     Vector3 ef21, ef22, ef23;
00699     Vector3 ef31, ef32, ef33;
00700 
00701     /* intersection point   R is a flag which tri P & Q correspond or not  */
00702     Vector3 ip,ip3,ip4,ip5,ip6;
00703     Vector3 i_pts_w[4];
00704   
00705     const int FV = 1; // face-vertex contact type
00706     const int VF = 2; // vertex-face contact type
00707     const int EE = 3; // edge-edge contact type
00708 
00709     z << 0.0,0.0,0.0;
00710   
00711     p1 =  P1 - P1;
00712     p2 =  P2 - P1;
00713     p3 =  P3 - P1;
00714   
00715     q1 =  Q1 - P1;
00716     q2 =  Q2 - P1;
00717     q3 =  Q3 - P1;
00718   
00719     e1 =  p2 - p1;
00720     e2 =  p3 - p2;
00721     e3 =  p1 - p3;
00722 
00723     f1 =  q2 - q1;
00724     f2 =  q3 - q2;
00725     f3 =  q1 - q3;
00726 
00727     n1 = e1.cross(e2);
00728     m1 = f1.cross(f2);
00729 
00730     // now begin the series of tests
00731 
00732     /*************************************
00733         separability test by face
00734     ************************************/
00735 
00736     nq[0] = n1.dot(q1);
00737     nq[1] = n1.dot(q2);
00738     nq[2] = n1.dot(q3);
00739     triQ = separability_test_by_face(nq);
00740 
00741     if(triQ == NOT_INTERSECT) return 0;
00742 
00743     double mq = m1.dot(q1);
00744     mp[0] = m1.dot(p1) - mq;
00745     mp[1] = m1.dot(p2) - mq;
00746     mp[2] = m1.dot(p3) - mq;
00747     triP = separability_test_by_face(mp);
00748     if(triP == NOT_INTERSECT) return 0;
00749 
00750     ef11 = e1.cross(f1);
00751     ef12 = e1.cross(f2);
00752     ef13 = e1.cross(f3);
00753     ef21 = e2.cross(f1);
00754     ef22 = e2.cross(f2);
00755     ef23 = e2.cross(f3);
00756     ef31 = e3.cross(f1);
00757     ef32 = e3.cross(f2);
00758     ef33 = e3.cross(f3);
00759 
00760     edf1 = 0; edf2 = 0; edf3 = 0; ede1 = 0; ede2 = 0; ede3 = 0;
00761 
00762     /********************************
00763          triangle inside test
00764     *********************************/  
00765     switch(triQ)
00766         {
00767         case NOT_INTERSECT:
00768             return 0;
00769 
00770         case EDGE1_NOT_INTERSECT:    
00771             edf2 = triangle_inside_test(ef12,ef22,ef32,p3,p1,p2,q2);
00772             edf3 = triangle_inside_test(ef13,ef23,ef33,p3,p1,p2,q3);
00773             break;
00774 
00775         case EDGE2_NOT_INTERSECT:         
00776             edf1 = triangle_inside_test(ef11,ef21,ef31,p3,p1,p2,q1);    
00777             edf3 = triangle_inside_test(ef13,ef23,ef33,p3,p1,p2,q3);
00778             break;
00779 
00780         case EDGE3_NOT_INTERSECT:       
00781             edf1 = triangle_inside_test(ef11,ef21,ef31,p3,p1,p2,q1);    
00782             edf2 = triangle_inside_test(ef12,ef22,ef32,p3,p1,p2,q2);
00783             break;
00784         }
00785 
00786     int num_of_edges = edf1 + edf2 + edf3;
00787     if(num_of_edges == 3){
00788         //exit(1);
00789         return 0;
00790     }
00791  
00792     if(num_of_edges < 2){
00793         switch(triP)
00794             {
00795             case EDGE1_NOT_INTERSECT:
00796                 ede2 = triangle_inside_test(ef21,ef22,ef23,q3,q1,q2,p2);
00797                 ede3 = triangle_inside_test(ef31,ef32,ef33,q3,q1,q2,p3);
00798                 if(ede2+ede3==2){
00799                     edf1= NOT_INTERSECT;
00800                     edf2= NOT_INTERSECT;
00801                     edf3= NOT_INTERSECT;
00802                 }
00803                 break;
00804         
00805             case EDGE2_NOT_INTERSECT:
00806                 ede1 = triangle_inside_test(ef11,ef12,ef13,q3,q1,q2,p1);
00807                 ede3 = triangle_inside_test(ef31,ef32,ef33,q3,q1,q2,p3);
00808                 if(ede1+ede3==2){
00809                     edf1= NOT_INTERSECT;
00810                     edf2= NOT_INTERSECT;
00811                     edf3= NOT_INTERSECT;
00812                 }
00813                 break;    
00814         
00815             case EDGE3_NOT_INTERSECT:
00816                 ede1 = triangle_inside_test(ef11,ef12,ef13,q3,q1,q2,p1);
00817                 ede2 = triangle_inside_test(ef21,ef22,ef23,q3,q1,q2,p2);
00818                 if(ede1+ede2 == 2){
00819                     edf1= NOT_INTERSECT;
00820                     edf2= NOT_INTERSECT;
00821                     edf3= NOT_INTERSECT;
00822                 }
00823                 break;
00824             }
00825         if(num_of_edges == 0 && ede1+ede2+ede3 == 3){
00826             //exit(1);
00827             return 0;
00828         }
00829     }
00830   
00831     int num = edf1+edf2+edf3+ede1+ede2+ede3;
00832     if(num == 0){
00833         // cout << "no edge intersect" << endl;
00834         return 0;
00835     }
00836     else if(num > 2){
00837         printf("err of edge detection....");
00838         //exit(1);
00839         return 0;
00840     }
00841 
00842     n1.normalize();
00843     m1.normalize();
00844 
00845     /*********************************
00846     find intersection points
00847     **********************************/
00848     if(num==1){
00849         if(edf1==INTERSECT){
00850             find_intersection_pt(ip,q1,q2,nq[0],nq[1]);
00851             ip3 = ip;
00852             col_p->n_vector = -n1;
00853             col_p->depth = 0.0;
00854             col_p->c_type = FV;
00855         }
00856         else if(edf2==INTERSECT){
00857             find_intersection_pt(ip,q2,q3,nq[1],nq[2]);
00858             ip3 = ip;
00859             col_p->n_vector = -n1;
00860             col_p->depth = 0.0;
00861             col_p->c_type = FV;
00862         }
00863         else if(edf3==INTERSECT){
00864             find_intersection_pt(ip,q3,q1,nq[2],nq[0]);
00865             ip3 = ip;
00866             col_p->n_vector = -n1;
00867             col_p->depth = 0.0;
00868             col_p->c_type = FV;
00869         }
00870         else if(ede1==INTERSECT){
00871             find_intersection_pt(ip,p1,p2,mp[0],mp[1]);
00872             ip3 =  ip;
00873             col_p->n_vector = m1;
00874             col_p->depth = 0.0;
00875             col_p->c_type = VF;
00876         }
00877         else if(ede2==INTERSECT){
00878             find_intersection_pt(ip,p2,p3,mp[1],mp[2]);
00879             ip3 =  ip;
00880             col_p->n_vector = m1;
00881             col_p->depth = 0.0;
00882             col_p->c_type = VF;
00883         }
00884         else if(ede3==INTERSECT){
00885             find_intersection_pt(ip,p3,p1,mp[2],mp[0]);
00886             ip3 =  ip;
00887             col_p->n_vector = m1;
00888             col_p->depth = 0.0;
00889             col_p->c_type = VF;
00890         }
00891         col_p->num_of_i_points = 1;
00892     }
00893     else if(num==2)
00894         {
00895             if(edf1==INTERSECT && edf2==INTERSECT){
00896                 if(HIRUKAWA_DEBUG) cout << "f1 f2" << endl;
00897                 col_p->c_type = FV;
00898                 if(!find_collision_info(q2,q1,q3,nq[1],nq[0],nq[2],p1,p2,p3,e1,e2,e3,
00899                                         m1,n1,ip3,ip4,ip5,ip6,col_p,-1.0))
00900                     return 0;
00901             }
00902             else if(edf1==INTERSECT && edf3==INTERSECT){
00903                 if(HIRUKAWA_DEBUG) cout << "f1 f3" << endl;
00904                 col_p->c_type = FV;
00905                 if(!find_collision_info(q1,q2,q3,nq[0],nq[1],nq[2],p1,p2,p3,e1,e2,e3,
00906                                         m1,n1,ip3,ip4,ip5,ip6,col_p,-1.0))
00907                     return 0;
00908             }
00909             else if(ede1==INTERSECT && edf1==INTERSECT){
00910                 if(HIRUKAWA_DEBUG) cout << "e1 f1" << endl;
00911                 col_p->c_type = EE;
00912                 if(!find_collision_info(p1,p2,p3,mp[0],mp[1],q1,q2,q3,nq[0],nq[1],ef11,
00913                                         n1,m1,ip3,ip4,col_p))
00914                     return 0;
00915             }
00916             else if(ede2==INTERSECT && edf1==INTERSECT){
00917                 if(HIRUKAWA_DEBUG) cout << "e2 f1" << endl;
00918                 col_p->c_type = EE;
00919                 if(!find_collision_info(p2,p3,p1,mp[1],mp[2],q1,q2,q3,nq[0],nq[1],ef21,
00920                                         n1,m1,ip3,ip4,col_p))
00921                     return 0;
00922             }
00923             else if(ede3==INTERSECT && edf1==INTERSECT){
00924                 if(HIRUKAWA_DEBUG) cout << "e3 f1" << endl;
00925                 col_p->c_type = EE;
00926                 if(!find_collision_info(p3,p1,p2,mp[2],mp[0],q1,q2,q3,nq[0],nq[1],ef31,
00927                                         n1,m1,ip3,ip4,col_p))
00928                     return 0;
00929             }
00930             else if(edf2==INTERSECT && edf3==INTERSECT){
00931                 if(HIRUKAWA_DEBUG) cout << "f2 f3" << endl;
00932                 col_p->c_type = FV;
00933                 if(!find_collision_info(q3,q2,q1,nq[2],nq[1],nq[0],p1,p2,p3,e1,e2,e3,
00934                                         m1,n1,ip3,ip4,ip5,ip6,col_p,-1.0))
00935                     return 0;
00936             }
00937             else if(ede1==INTERSECT && edf2==INTERSECT){
00938                 if(HIRUKAWA_DEBUG) cout << "e1 f2" << endl;
00939                 col_p->c_type = EE;
00940                 if(!find_collision_info(p1,p2,p3,mp[0],mp[1],q2,q3,q1,nq[1],nq[2],ef12,
00941                                         n1,m1,ip3,ip4,col_p))
00942                     return 0;
00943             }
00944             else if(ede2==INTERSECT && edf2==INTERSECT){
00945                 if(HIRUKAWA_DEBUG) cout << "e2 f2" << endl;
00946                 col_p->c_type = EE;
00947                 if(!find_collision_info(p2,p3,p1,mp[1],mp[2],q2,q3,q1,nq[1],nq[2],ef22,
00948                                         n1,m1,ip3,ip4,col_p))
00949                     return 0;
00950             }
00951             else if(ede3==INTERSECT && edf2==INTERSECT){
00952                 if(HIRUKAWA_DEBUG) cout << "e3 f2" << endl;
00953                 col_p->c_type = EE;
00954                 if(!find_collision_info(p3,p1,p2,mp[2],mp[0],q2,q3,q1,nq[1],nq[2],ef32,
00955                                         n1,m1,ip3,ip4,col_p))
00956                     return 0;
00957             }
00958             else if(ede1==INTERSECT && edf3==INTERSECT){
00959                 if(HIRUKAWA_DEBUG) cout << "e1 f3" << endl;
00960                 col_p->c_type = EE;
00961                 if(!find_collision_info(p1,p2,p3,mp[0],mp[1],q3,q1,q2,nq[2],nq[0],ef13,
00962                                         n1,m1,ip3,ip4,col_p))
00963                     return 0;
00964             }
00965             else if(ede2==INTERSECT && edf3==INTERSECT){
00966                 if(HIRUKAWA_DEBUG) cout << "e2 f3" << endl;
00967                 col_p->c_type = EE;
00968                 if(!find_collision_info(p2,p3,p1,mp[1],mp[2],q3,q1,q2,nq[2],nq[0],ef23,
00969                                         n1,m1,ip3,ip4,col_p))
00970                     return 0;
00971             }
00972             else if(ede3==INTERSECT && edf3==INTERSECT){
00973                 if(HIRUKAWA_DEBUG) cout << "e3 f3" << endl;
00974                 col_p->c_type = EE;
00975                 if(!find_collision_info(p3,p1,p2,mp[2],mp[0],q3,q1,q2,nq[2],nq[0],ef33,
00976                                         n1,m1,ip3,ip4,col_p))
00977                     return 0;
00978             }
00979             else if(ede1==INTERSECT && ede2==INTERSECT){
00980                 if(HIRUKAWA_DEBUG) cout << "e1 e2" << endl;
00981                 col_p->c_type = VF;
00982                 if(!find_collision_info(p2,p1,p3,mp[1],mp[0],mp[2],q1,q2,q3,f1,f2,f3,
00983                                         n1,m1,ip3,ip4,ip5,ip6,col_p,1.0))
00984                     return 0;
00985             }
00986             else if(ede1==INTERSECT && ede3==INTERSECT){
00987                 if(HIRUKAWA_DEBUG) cout << "e1 e3" << endl;
00988                 col_p->c_type = VF;
00989                 if(!find_collision_info(p1,p2,p3,mp[0],mp[1],mp[2],q1,q2,q3,f1,f2,f3,
00990                                         n1,m1,ip3,ip4,ip5,ip6,col_p,1.0))
00991                     return 0;
00992             }
00993             else if(ede2==INTERSECT && ede3==INTERSECT){
00994                 if(HIRUKAWA_DEBUG) cout << "e2 e3" << endl;
00995                 col_p->c_type = VF;
00996                 if(!find_collision_info(p3,p2,p1,mp[2],mp[1],mp[0],q1,q2,q3,f1,f2,f3,
00997                                         n1,m1,ip3,ip4,ip5,ip6,col_p,1.0))
00998                     return 0;
00999             }
01000         }    
01001 
01002     if(col_p->num_of_i_points == 1){
01003         col_p->i_points[0] = ip3 + P1;
01004     }
01005     else if(col_p->num_of_i_points == 2){
01006         col_p->i_points[0] = ip3 + P1;
01007         col_p->i_points[1] = ip4 + P1;
01008     }
01009     else if(col_p->num_of_i_points == 3){
01010         col_p->i_points[0] = ip3 + P1;
01011         col_p->i_points[1] = ip4 + P1;
01012         col_p->i_points[2] = ip5 + P1;
01013     }
01014     else if(col_p->num_of_i_points == 4){
01015         col_p->i_points[0] = ip3 + P1;
01016         col_p->i_points[1] = ip4 + P1;
01017         col_p->i_points[2] = ip5 + P1;
01018         col_p->i_points[3] = ip5 + P1;
01019     }
01020 
01021     col_p->n = n1;
01022     col_p->m = m1;
01023     
01024     if(HIRUKAWA_DEBUG){
01025 
01026         CollisionPairInserterBase& c = *collisionPairInserter;
01027     
01028         Vector3 p1w(c.CD_s2 * (c.CD_Rot2 * P1 + c.CD_Trans2));
01029         Vector3 p2w(c.CD_s2 * (c.CD_Rot2 * P2 + c.CD_Trans2));
01030         Vector3 p3w(c.CD_s2 * (c.CD_Rot2 * P3 + c.CD_Trans2));
01031         Vector3 q1w(c.CD_s2 * (c.CD_Rot2 * Q1 + c.CD_Trans2));
01032         Vector3 q2w(c.CD_s2 * (c.CD_Rot2 * Q2 + c.CD_Trans2));
01033         Vector3 q3w(c.CD_s2 * (c.CD_Rot2 * Q3 + c.CD_Trans2));
01034         cout << "P1 = " << p1w[0] << " " << p1w[1] << " " << p1w[2] << endl;
01035         cout << "P2 = " << p2w[0] << " " << p2w[1] << " " << p2w[2] << endl;
01036         cout << "P3 = " << p3w[0] << " " << p3w[1] << " " << p3w[2] << endl;
01037         cout << "Q1 = " << q1w[0] << " " << q1w[1] << " " << q1w[2] << endl;
01038         cout << "Q2 = " << q2w[0] << " " << q2w[1] << " " << q2w[2] << endl;
01039         cout << "Q3 = " << q3w[0] << " " << q3w[1] << " " << q3w[2] << endl;
01040 
01041         for(int i=0; i<col_p->num_of_i_points; i++){
01042             i_pts_w[i] = c.CD_s2 * ((c.CD_Rot2 * col_p->i_points[i]) + c.CD_Trans2);
01043             cout << i << "-th intersecting point = ";
01044             cout << i_pts_w[i][0] << " " << i_pts_w[i][1] << " " << i_pts_w[i][2] << endl;
01045         }
01046 
01047         cout << "n1 = " << n1[0] << " " << n1[1] << " " << n1[2] << endl;
01048         cout << "m1 = " << m1[0] << " " << m1[1] << " " << m1[2] << endl;
01049         cout << "mp[0] mp[1] mp[2] = " << mp[0] << " " << mp[1] << " " << mp[2] << endl;
01050         cout << "nq[0] nq[1] nq[2] = " << nq[0] << " " << nq[1] << " " << nq[2] << endl;
01051         cout << "n_vector = " << col_p->n_vector[0] << " " << col_p->n_vector[1]
01052              << " " << col_p->n_vector[2] << endl;
01053         cout << "depth = " << col_p->depth << endl << endl;;
01054 
01055     }
01056 
01057 #if TRACE1
01058     printf("intersect point...in tri_contact..\n");
01059     printf("    ip1x = %f ip1y = %f ip1z = %f\n    ip2x = %f ip2y = %f ip2z = %f\n",
01060            col_p->i_points[0][0],col_p->i_points[0][1],col_p->i_points[0][2],
01061            col_p->i_points[1][0],col_p->i_points[1][1],col_p->i_points[1][2]);
01062 
01063     printf("normal vector....it tri_conctact..\n");
01064     printf("N[0] = %f,N[1] = %f,N[2] = %f\n",col_p->n_vector[0],col_p->n_vector[1],col_p->n_vector[2]);
01065 #endif
01066 
01067     return 1;
01068 }


openhrp3
Author(s): AIST, General Robotix Inc., Nakamura Lab of Dept. of Mechano Informatics at University of Tokyo
autogenerated on Sun Apr 2 2017 03:43:57