narrowphase.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2011, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 
00037 #include "fcl/narrowphase/narrowphase.h"
00038 #include "fcl/shape/geometric_shapes_utility.h"
00039 #include <boost/math/constants/constants.hpp>
00040 #include <vector>
00041 
00042 namespace fcl
00043 {
00044 
00045 namespace details
00046 {
00047 
00048 bool sphereSphereIntersect(const Sphere& s1, const Transform3f& tf1, 
00049                            const Sphere& s2, const Transform3f& tf2,
00050                            Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal)
00051 {
00052   Vec3f diff = tf1.transform(Vec3f()) - tf2.transform(Vec3f());
00053   FCL_REAL len = diff.length();
00054   if(len > s1.radius + s2.radius)
00055     return false;
00056 
00057   if(penetration_depth) 
00058     *penetration_depth = s1.radius + s2.radius - len;
00059   if(normal) 
00060   {
00061     if(len > 0)
00062       *normal = diff / len;
00063     else
00064       *normal = diff;
00065   }
00066 
00067   if(contact_points)
00068     *contact_points = tf1.transform(Vec3f()) + diff * 0.5;
00069   
00070   return true;
00071 }
00072 
00073 
00074 bool sphereSphereDistance(const Sphere& s1, const Transform3f& tf1,
00075                           const Sphere& s2, const Transform3f& tf2,
00076                           FCL_REAL* dist)
00077 {
00078   Vec3f diff = tf1.transform(Vec3f()) - tf2.transform(Vec3f());
00079   FCL_REAL len = diff.length();
00080   if(len > s1.radius + s2.radius)
00081   {
00082     *dist = len - (s1.radius + s2.radius);
00083     return true;
00084   }
00085 
00086   *dist = -1;
00087   return false;
00088 }
00089 
00091 FCL_REAL segmentSqrDistance(const Vec3f& from, const Vec3f& to,const Vec3f& p, Vec3f& nearest) 
00092 {
00093   Vec3f diff = p - from;
00094   Vec3f v = to - from;
00095   FCL_REAL t = v.dot(diff);
00096         
00097   if(t > 0) 
00098   {
00099     FCL_REAL dotVV = v.dot(v);
00100     if(t < dotVV) 
00101     {
00102       t /= dotVV;
00103       diff -= v * t;
00104     } 
00105     else 
00106     {
00107       t = 1;
00108       diff -= v;
00109     }
00110   } 
00111   else
00112     t = 0;
00113 
00114   nearest = from + v * t;
00115   return diff.dot(diff);        
00116 }
00117 
00119 bool projectInTriangle(const Vec3f& p1, const Vec3f& p2, const Vec3f& p3, const Vec3f& normal, const Vec3f& p)
00120 {
00121   Vec3f edge1(p2 - p1);
00122   Vec3f edge2(p3 - p2);
00123   Vec3f edge3(p1 - p3);
00124 
00125   Vec3f p1_to_p(p - p1);
00126   Vec3f p2_to_p(p - p2);
00127   Vec3f p3_to_p(p - p3);
00128 
00129   Vec3f edge1_normal(edge1.cross(normal));
00130   Vec3f edge2_normal(edge2.cross(normal));
00131   Vec3f edge3_normal(edge3.cross(normal));
00132         
00133   FCL_REAL r1, r2, r3;
00134   r1 = edge1_normal.dot(p1_to_p);
00135   r2 = edge2_normal.dot(p2_to_p);
00136   r3 = edge3_normal.dot(p3_to_p);
00137   if ( ( r1 > 0 && r2 > 0 && r3 > 0 ) ||
00138        ( r1 <= 0 && r2 <= 0 && r3 <= 0 ) )
00139     return true;
00140   return false;
00141 }
00142 
00143 
00144 bool sphereTriangleIntersect(const Sphere& s, const Transform3f& tf,
00145                              const Vec3f& P1, const Vec3f& P2, const Vec3f& P3, Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal_)
00146 {
00147   Vec3f normal = (P2 - P1).cross(P3 - P1);
00148   normal.normalize();
00149   const Vec3f& center = tf.getTranslation();
00150   const FCL_REAL& radius = s.radius;
00151   FCL_REAL radius_with_threshold = radius + std::numeric_limits<FCL_REAL>::epsilon();
00152   Vec3f p1_to_center = center - P1;
00153   FCL_REAL distance_from_plane = p1_to_center.dot(normal);
00154 
00155   if(distance_from_plane < 0)
00156   {
00157     distance_from_plane *= -1;
00158     normal *= -1;
00159   }
00160 
00161   bool is_inside_contact_plane = (distance_from_plane < radius_with_threshold);
00162   
00163   bool has_contact = false;
00164   Vec3f contact_point;
00165   if(is_inside_contact_plane)
00166   {
00167     if(projectInTriangle(P1, P2, P3, center, normal))
00168     {
00169       has_contact = true;
00170       contact_point = center - normal * distance_from_plane;
00171     }
00172     else
00173     {
00174       FCL_REAL contact_capsule_radius_sqr = radius_with_threshold * radius_with_threshold;
00175       Vec3f nearest_on_edge;
00176       FCL_REAL distance_sqr;
00177       distance_sqr = segmentSqrDistance(P1, P2, center, nearest_on_edge);
00178       if(distance_sqr < contact_capsule_radius_sqr)
00179       {
00180         has_contact = true;
00181         contact_point = nearest_on_edge;
00182       }
00183 
00184       distance_sqr = segmentSqrDistance(P2, P3, center, nearest_on_edge);
00185       if(distance_sqr < contact_capsule_radius_sqr)
00186       {
00187         has_contact = true;
00188         contact_point = nearest_on_edge;
00189       }
00190 
00191       distance_sqr = segmentSqrDistance(P3, P1, center, nearest_on_edge);
00192       if(distance_sqr < contact_capsule_radius_sqr)
00193       {
00194         has_contact = true;
00195         contact_point = nearest_on_edge;
00196       }
00197     }
00198   }
00199 
00200   if(has_contact)
00201   {
00202     Vec3f contact_to_center = center - contact_point;
00203     FCL_REAL distance_sqr = contact_to_center.sqrLength();
00204 
00205     if(distance_sqr < radius_with_threshold * radius_with_threshold)
00206     {
00207       if(distance_sqr > 0)
00208       {
00209         FCL_REAL distance = std::sqrt(distance_sqr);
00210         if(normal_) *normal_ = normalize(contact_to_center);
00211         if(contact_points) *contact_points = contact_point;
00212         if(penetration_depth) *penetration_depth = -(radius - distance);
00213       }
00214       else
00215       {
00216         FCL_REAL distance = 0;
00217         if(normal_) *normal_ = normal;
00218         if(contact_points) *contact_points = contact_point;
00219         if(penetration_depth) *penetration_depth = -radius;
00220       }
00221 
00222       return true;
00223     }
00224   }
00225 
00226   return false;
00227 }
00228 
00229 bool sphereTriangleDistance(const Sphere& sp, const Transform3f& tf,
00230                             const Vec3f& P1, const Vec3f& P2, const Vec3f& P3,
00231                             FCL_REAL* dist)
00232 {
00233   // from geometric tools, very different from the collision code.
00234 
00235   const Vec3f& center = tf.getTranslation();
00236   FCL_REAL radius = sp.radius;
00237   Vec3f diff = P1 - center;
00238   Vec3f edge0 = P2 - P1;
00239   Vec3f edge1 = P3 - P1;
00240   FCL_REAL a00 = edge0.sqrLength();
00241   FCL_REAL a01 = edge0.dot(edge1);
00242   FCL_REAL a11 = edge1.sqrLength();
00243   FCL_REAL b0 = diff.dot(edge0);
00244   FCL_REAL b1 = diff.dot(edge1);
00245   FCL_REAL c = diff.sqrLength();
00246   FCL_REAL det = fabs(a00*a11 - a01*a01);
00247   FCL_REAL s = a01*b1 - a11*b0;
00248   FCL_REAL t = a01*b0 - a00*b1;
00249 
00250   FCL_REAL sqr_dist;
00251 
00252   if(s + t <= det)
00253   {
00254     if(s < 0)
00255     {
00256       if(t < 0)  // region 4
00257       {
00258         if(b0 < 0)
00259         {
00260           t = 0;
00261           if(-b0 >= a00)
00262           {
00263             s = 1;
00264             sqr_dist = a00 + 2*b0 + c;
00265           }
00266           else
00267           {
00268             s = -b0/a00;
00269             sqr_dist = b0*s + c;
00270           }
00271         }
00272         else
00273         {
00274           s = 0;
00275           if(b1 >= 0)
00276           {
00277             t = 0;
00278             sqr_dist = c;
00279           }
00280           else if(-b1 >= a11)
00281           {
00282             t = 1;
00283             sqr_dist = a11 + 2*b1 + c;
00284           }
00285           else
00286           {
00287             t = -b1/a11;
00288             sqr_dist = b1*t + c;
00289           }
00290         }
00291       }
00292       else  // region 3
00293       {
00294         s = 0;
00295         if(b1 >= 0)
00296         {
00297           t = 0;
00298           sqr_dist = c;
00299         }
00300         else if(-b1 >= a11)
00301         {
00302           t = 1;
00303           sqr_dist = a11 + 2*b1 + c;
00304         }
00305         else
00306         {
00307           t = -b1/a11;
00308           sqr_dist = b1*t + c;
00309         }
00310       }
00311     }
00312     else if(t < 0)  // region 5
00313     {
00314       t = 0;
00315       if(b0 >= 0)
00316       {
00317         s = 0;
00318         sqr_dist = c;
00319       }
00320       else if(-b0 >= a00)
00321       {
00322         s = 1;
00323         sqr_dist = a00 + 2*b0 + c;
00324       }
00325       else
00326       {
00327         s = -b0/a00;
00328         sqr_dist = b0*s + c;
00329       }
00330     }
00331     else  // region 0
00332     {
00333       // minimum at interior point
00334       FCL_REAL inv_det = (1)/det;
00335       s *= inv_det;
00336       t *= inv_det;
00337       sqr_dist = s*(a00*s + a01*t + 2*b0) + t*(a01*s + a11*t + 2*b1) + c;
00338     }
00339   }
00340   else
00341   {
00342     FCL_REAL tmp0, tmp1, numer, denom;
00343 
00344     if(s < 0)  // region 2
00345     {
00346       tmp0 = a01 + b0;
00347       tmp1 = a11 + b1;
00348       if(tmp1 > tmp0)
00349       {
00350         numer = tmp1 - tmp0;
00351         denom = a00 - 2*a01 + a11;
00352         if(numer >= denom)
00353         {
00354           s = 1;
00355           t = 0;
00356           sqr_dist = a00 + 2*b0 + c;
00357         }
00358         else
00359         {
00360           s = numer/denom;
00361           t = 1 - s;
00362           sqr_dist = s*(a00*s + a01*t + 2*b0) + t*(a01*s + a11*t + 2*b1) + c;
00363         }
00364       }
00365       else
00366       {
00367         s = 0;
00368         if(tmp1 <= 0)
00369         {
00370           t = 1;
00371           sqr_dist = a11 + 2*b1 + c;
00372         }
00373         else if(b1 >= 0)
00374         {
00375           t = 0;
00376           sqr_dist = c;
00377         }
00378         else
00379         {
00380           t = -b1/a11;
00381           sqr_dist = b1*t + c;
00382         }
00383       }
00384     }
00385     else if(t < 0)  // region 6
00386     {
00387       tmp0 = a01 + b1;
00388       tmp1 = a00 + b0;
00389       if(tmp1 > tmp0)
00390       {
00391         numer = tmp1 - tmp0;
00392         denom = a00 - 2*a01 + a11;
00393         if(numer >= denom)
00394         {
00395           t = 1;
00396           s = 0;
00397           sqr_dist = a11 + 2*b1 + c;
00398         }
00399         else
00400         {
00401           t = numer/denom;
00402           s = 1 - t;
00403           sqr_dist = s*(a00*s + a01*t + 2*b0) + t*(a01*s + a11*t + 2*b1) + c;
00404         }
00405       }
00406       else
00407       {
00408         t = 0;
00409         if(tmp1 <= 0)
00410         {
00411           s = 1;
00412           sqr_dist = a00 + 2*b0 + c;
00413         }
00414         else if(b0 >= 0)
00415         {
00416           s = 0;
00417           sqr_dist = c;
00418         }
00419         else
00420         {
00421           s = -b0/a00;
00422           sqr_dist = b0*s + c;
00423         }
00424       }
00425     }
00426     else  // region 1
00427     {
00428       numer = a11 + b1 - a01 - b0;
00429       if(numer <= 0)
00430       {
00431         s = 0;
00432         t = 1;
00433         sqr_dist = a11 + 2*b1 + c;
00434       }
00435       else
00436       {
00437         denom = a00 - 2*a01 + a11;
00438         if(numer >= denom)
00439         {
00440           s = 1;
00441           t = 0;
00442           sqr_dist = a00 + 2*b0 + c;
00443         }
00444         else
00445         {
00446           s = numer/denom;
00447           t = 1 - s;
00448           sqr_dist = s*(a00*s + a01*t + 2*b0) + t*(a01*s + a11*t + 2*b1) + c;
00449         }
00450       }
00451     }
00452   }
00453 
00454   // Account for numerical round-off error.
00455   if(sqr_dist < 0)
00456     sqr_dist = 0;
00457 
00458   if(sqr_dist > radius * radius)
00459   {
00460     *dist = std::sqrt(sqr_dist) - radius;
00461     return true;
00462   }
00463   else
00464   {
00465     *dist = -1;
00466     return false;
00467   }
00468 }
00469 
00470 
00471 
00472 struct ContactPoint
00473 {
00474   Vec3f normal;
00475   Vec3f point;
00476   FCL_REAL depth;
00477   ContactPoint(const Vec3f& n, const Vec3f& p, FCL_REAL d) : normal(n), point(p), depth(d) {}
00478 };
00479 
00480 
00481 static inline void lineClosestApproach(const Vec3f& pa, const Vec3f& ua,
00482                                        const Vec3f& pb, const Vec3f& ub,
00483                                        FCL_REAL* alpha, FCL_REAL* beta)
00484 {
00485   Vec3f p = pb - pa;
00486   FCL_REAL uaub = ua.dot(ub);
00487   FCL_REAL q1 = ua.dot(p);
00488   FCL_REAL q2 = -ub.dot(p);
00489   FCL_REAL d = 1 - uaub * uaub;
00490   if(d <= (FCL_REAL)(0.0001f))
00491   {
00492     *alpha = 0;
00493     *beta = 0;
00494   }
00495   else
00496   {
00497     d = 1 / d;
00498     *alpha = (q1 + uaub * q2) * d;
00499     *beta = (uaub * q1 + q2) * d;
00500   }
00501 }
00502 
00503 // find all the intersection points between the 2D rectangle with vertices
00504 // at (+/-h[0],+/-h[1]) and the 2D quadrilateral with vertices (p[0],p[1]),
00505 // (p[2],p[3]),(p[4],p[5]),(p[6],p[7]).
00506 //
00507 // the intersection points are returned as x,y pairs in the 'ret' array.
00508 // the number of intersection points is returned by the function (this will
00509 // be in the range 0 to 8).
00510 static int intersectRectQuad2(FCL_REAL h[2], FCL_REAL p[8], FCL_REAL ret[16])
00511 {
00512   // q (and r) contain nq (and nr) coordinate points for the current (and
00513   // chopped) polygons
00514   int nq = 4, nr = 0;
00515   FCL_REAL buffer[16];
00516   FCL_REAL* q = p;
00517   FCL_REAL* r = ret;
00518   for(int dir = 0; dir <= 1; ++dir) 
00519   {
00520     // direction notation: xy[0] = x axis, xy[1] = y axis
00521     for(int sign = -1; sign <= 1; sign += 2) 
00522     {
00523       // chop q along the line xy[dir] = sign*h[dir]
00524       FCL_REAL* pq = q;
00525       FCL_REAL* pr = r;
00526       nr = 0;
00527       for(int i = nq; i > 0; --i) 
00528       {
00529         // go through all points in q and all lines between adjacent points
00530         if(sign * pq[dir] < h[dir]) 
00531         {
00532           // this point is inside the chopping line
00533           pr[0] = pq[0];
00534           pr[1] = pq[1];
00535           pr += 2;
00536           nr++;
00537           if(nr & 8) 
00538           {
00539             q = r;
00540             goto done;
00541           }
00542         }
00543         FCL_REAL* nextq = (i > 1) ? pq+2 : q;
00544         if((sign*pq[dir] < h[dir]) ^ (sign*nextq[dir] < h[dir])) 
00545         {
00546           // this line crosses the chopping line
00547           pr[1-dir] = pq[1-dir] + (nextq[1-dir]-pq[1-dir]) /
00548             (nextq[dir]-pq[dir]) * (sign*h[dir]-pq[dir]);
00549           pr[dir] = sign*h[dir];
00550           pr += 2;
00551           nr++;
00552           if(nr & 8) 
00553           {
00554             q = r;
00555             goto done;
00556           }
00557         }
00558         pq += 2;
00559       }
00560       q = r;
00561       r = (q == ret) ? buffer : ret;
00562       nq = nr;
00563     }
00564   }
00565  
00566  done:
00567   if(q != ret) memcpy(ret, q, nr*2*sizeof(FCL_REAL));
00568   return nr;  
00569 }
00570 
00571 // given n points in the plane (array p, of size 2*n), generate m points that
00572 // best represent the whole set. the definition of 'best' here is not
00573 // predetermined - the idea is to select points that give good box-box
00574 // collision detection behavior. the chosen point indexes are returned in the
00575 // array iret (of size m). 'i0' is always the first entry in the array.
00576 // n must be in the range [1..8]. m must be in the range [1..n]. i0 must be
00577 // in the range [0..n-1].
00578 static inline void cullPoints2(int n, FCL_REAL p[], int m, int i0, int iret[])
00579 {
00580   // compute the centroid of the polygon in cx,cy
00581   FCL_REAL a, cx, cy, q;
00582   switch(n)
00583   {
00584   case 1:
00585     cx = p[0];
00586     cy = p[1];
00587     break;
00588   case 2:
00589     cx = 0.5 * (p[0] + p[2]);
00590     cy = 0.5 * (p[1] + p[3]);
00591     break;
00592   default:
00593     a = 0;
00594     cx = 0;
00595     cy = 0;
00596     for(int i = 0; i < n-1; ++i) 
00597     {
00598       q = p[i*2]*p[i*2+3] - p[i*2+2]*p[i*2+1];
00599       a += q;
00600       cx += q*(p[i*2]+p[i*2+2]);
00601       cy += q*(p[i*2+1]+p[i*2+3]);
00602     }
00603     q = p[n*2-2]*p[1] - p[0]*p[n*2-1];
00604     if(std::abs(a+q) > std::numeric_limits<FCL_REAL>::epsilon())
00605       a = 1/(3*(a+q));
00606     else
00607       a= 1e18f;
00608     
00609     cx = a*(cx + q*(p[n*2-2]+p[0]));
00610     cy = a*(cy + q*(p[n*2-1]+p[1]));
00611   }
00612 
00613 
00614   // compute the angle of each point w.r.t. the centroid
00615   FCL_REAL A[8];
00616   for(int i = 0; i < n; ++i) 
00617     A[i] = atan2(p[i*2+1]-cy,p[i*2]-cx);
00618 
00619   // search for points that have angles closest to A[i0] + i*(2*pi/m).
00620   int avail[8];
00621   for(int i = 0; i < n; ++i) avail[i] = 1;
00622   avail[i0] = 0;
00623   iret[0] = i0;
00624   iret++;
00625   const double pi = boost::math::constants::pi<FCL_REAL>();
00626   for(int j = 1; j < m; ++j) 
00627   {
00628     a = j*(2*pi/m) + A[i0];
00629     if (a > pi) a -= 2*pi;
00630     FCL_REAL maxdiff= 1e9, diff;
00631 
00632     *iret = i0; // iret is not allowed to keep this value, but it sometimes does, when diff=#QNAN0
00633     for(int i = 0; i < n; ++i) 
00634     {
00635       if(avail[i]) 
00636       {
00637         diff = std::abs(A[i]-a);
00638         if(diff > pi) diff = 2*pi - diff;
00639         if(diff < maxdiff) 
00640         {
00641           maxdiff = diff;
00642           *iret = i;
00643         }
00644       }
00645     }
00646     avail[*iret] = 0;
00647     iret++;
00648   }
00649 }
00650 
00651 
00652 
00653 int boxBox2(const Vec3f& side1, const Matrix3f& R1, const Vec3f& T1,
00654             const Vec3f& side2, const Matrix3f& R2, const Vec3f& T2,
00655             Vec3f& normal, FCL_REAL* depth, int* return_code,
00656             int maxc, std::vector<ContactPoint>& contacts)
00657 {
00658   const FCL_REAL fudge_factor = FCL_REAL(1.05);
00659   Vec3f normalC;
00660   FCL_REAL s, s2, l;
00661   int invert_normal, code;
00662 
00663   Vec3f p = T2 - T1; // get vector from centers of box 1 to box 2, relative to box 1
00664   Vec3f pp = R1.transposeTimes(p); // get pp = p relative to body 1
00665 
00666   // get side lengths / 2
00667   Vec3f A = side1 * 0.5;
00668   Vec3f B = side2 * 0.5;
00669 
00670   // Rij is R1'*R2, i.e. the relative rotation between R1 and R2
00671   Matrix3f R = R1.transposeTimes(R2);
00672   Matrix3f Q = abs(R);
00673 
00674 
00675   // for all 15 possible separating axes:
00676   //   * see if the axis separates the boxes. if so, return 0.
00677   //   * find the depth of the penetration along the separating axis (s2)
00678   //   * if this is the largest depth so far, record it.
00679   // the normal vector will be set to the separating axis with the smallest
00680   // depth. note: normalR is set to point to a column of R1 or R2 if that is
00681   // the smallest depth normal so far. otherwise normalR is 0 and normalC is
00682   // set to a vector relative to body 1. invert_normal is 1 if the sign of
00683   // the normal should be flipped.
00684 
00685   int best_col_id = -1;
00686   FCL_REAL tmp = 0;
00687 
00688   s = - std::numeric_limits<FCL_REAL>::max();
00689   invert_normal = 0;
00690   code = 0;
00691 
00692   // separating axis = u1, u2, u3
00693   tmp = pp[0];
00694   s2 = std::abs(tmp) - (Q.dotX(B) + A[0]);
00695   if(s2 > 0) { *return_code = 0; return 0; }
00696   if(s2 > s) 
00697   {
00698     s = s2; 
00699     best_col_id = 0;
00700     invert_normal = (tmp < 0);
00701     code = 1;
00702   }
00703 
00704   tmp = pp[1]; 
00705   s2 = std::abs(tmp) - (Q.dotY(B) + A[1]);
00706   if(s2 > 0) { *return_code = 0; return 0; }
00707   if(s2 > s) 
00708   {
00709     s = s2; 
00710     best_col_id = 1;
00711     invert_normal = (tmp < 0);
00712     code = 2;
00713   }
00714 
00715   tmp = pp[2];
00716   s2 = std::abs(tmp) - (Q.dotZ(B) + A[2]);
00717   if(s2 > 0) { *return_code = 0; return 0; }
00718   if(s2 > s)
00719   {
00720     s = s2;
00721     best_col_id = 2;
00722     invert_normal = (tmp < 0);
00723     code = 3;
00724   }
00725 
00726   // separating axis = v1, v2, v3
00727   tmp = R2.transposeDotX(p);
00728   s2 = std::abs(tmp) - (Q.transposeDotX(A) + B[0]);
00729   if(s2 > 0) { *return_code = 0; return 0; }
00730   if(s2 > s)
00731   {
00732     s = s2;
00733     best_col_id = 0;
00734     code = 4;
00735   }
00736 
00737   tmp = R2.transposeDotY(p);
00738   s2 = std::abs(tmp) - (Q.transposeDotY(A) + B[1]);
00739   if(s2 > 0) { *return_code = 0; return 0; }
00740   if(s2 > s)
00741   {
00742     s = s2;
00743     best_col_id = 1;
00744     code = 5;
00745   }
00746 
00747   tmp = R2.transposeDotZ(p);
00748   s2 =  std::abs(tmp) - (Q.transposeDotZ(A) + B[2]);
00749   if(s2 > 0) { *return_code = 0; return 0; }
00750   if(s2 > s)
00751   {
00752     s = s2;
00753     best_col_id = 2;
00754     code = 6;
00755   }
00756   
00757 
00758   FCL_REAL fudge2(1.0e-6);
00759   Q += fudge2;
00760 
00761   Vec3f n;
00762   FCL_REAL eps = std::numeric_limits<FCL_REAL>::epsilon();
00763 
00764   // separating axis = u1 x (v1,v2,v3)
00765   tmp = pp[2] * R(1, 0) - pp[1] * R(2, 0);
00766   s2 = std::abs(tmp) - (A[1] * Q(2, 0) + A[2] * Q(1, 0) + B[1] * Q(0, 2) + B[2] * Q(0, 1));
00767   if(s2 > eps) { *return_code = 0; return 0; }
00768   n = Vec3f(0, -R(2, 0), R(1, 0));
00769   l = n.length();
00770   if(l > eps) 
00771   {
00772     s2 /= l;
00773     if(s2 * fudge_factor > s)
00774     {
00775       s = s2;
00776       best_col_id = 0;
00777       normalC = n / l;
00778       invert_normal = (tmp < 0);
00779       code = 7;
00780     }
00781   }
00782 
00783   tmp = pp[2] * R(1, 1) - pp[1] * R(2, 1);
00784   s2 = std::abs(tmp) - (A[1] * Q(2, 1) + A[2] * Q(1, 1) + B[0] * Q(0, 2) + B[2] * Q(0, 0));
00785   if(s2 > eps) { *return_code = 0; return 0; }
00786   n = Vec3f(0, -R(2, 1), R(1, 1));
00787   l = n.length();
00788   if(l > eps) 
00789   {
00790     s2 /= l;
00791     if(s2 * fudge_factor > s)
00792     {
00793       s = s2;
00794       best_col_id = 0;
00795       normalC = n / l;
00796       invert_normal = (tmp < 0);
00797       code = 8;
00798     }
00799   }
00800   
00801   tmp = pp[2] * R(1, 2) - pp[1] * R(2, 2);
00802   s2 = std::abs(tmp) - (A[1] * Q(2, 2) + A[2] * Q(1, 2) + B[0] * Q(0, 1) + B[1] * Q(0, 0));
00803   if(s2 > eps) { *return_code = 0; return 0; }
00804   n = Vec3f(0, -R(2, 2), R(1, 2));
00805   l = n.length();
00806   if(l > eps) 
00807   {
00808     s2 /= l;
00809     if(s2 * fudge_factor > s)
00810     {
00811       s = s2;
00812       best_col_id = 0;
00813       normalC = n / l;
00814       invert_normal = (tmp < 0);
00815       code = 9;
00816     }
00817   }
00818 
00819   // separating axis = u2 x (v1,v2,v3)
00820   tmp = pp[0] * R(2, 0) - pp[2] * R(0, 0);
00821   s2 = std::abs(tmp) - (A[0] * Q(2, 0) + A[2] * Q(0, 0) + B[1] * Q(1, 2) + B[2] * Q(1, 1));
00822   if(s2 > eps) { *return_code = 0; return 0; }
00823   n = Vec3f(R(2, 0), 0, -R(0, 0));
00824   l = n.length();
00825   if(l > eps) 
00826   {
00827     s2 /= l;
00828     if(s2 * fudge_factor > s)
00829     {
00830       s = s2;
00831       best_col_id = 0;
00832       normalC = n / l;
00833       invert_normal = (tmp < 0);
00834       code = 10;
00835     }
00836   }
00837 
00838   tmp = pp[0] * R(2, 1) - pp[2] * R(0, 1);
00839   s2 = std::abs(tmp) - (A[0] * Q(2, 1) + A[2] * Q(0, 1) + B[0] * Q(1, 2) + B[2] * Q(1, 0));
00840   if(s2 > eps) { *return_code = 0; return 0; }
00841   n = Vec3f(R(2, 1), 0, -R(0, 1));
00842   l = n.length();
00843   if(l > eps) 
00844   {
00845     s2 /= l;
00846     if(s2 * fudge_factor > s)
00847     {
00848       s = s2;
00849       best_col_id = 0;
00850       normalC = n / l;
00851       invert_normal = (tmp < 0);
00852       code = 11;
00853     }
00854   }
00855   
00856   tmp = pp[0] * R(2, 2) - pp[2] * R(0, 2);
00857   s2 = std::abs(tmp) - (A[0] * Q(2, 2) + A[2] * Q(0, 2) + B[0] * Q(1, 1) + B[1] * Q(1, 0));
00858   if(s2 > eps) { *return_code = 0; return 0; }
00859   n = Vec3f(R(2, 2), 0, -R(0, 2));
00860   l = n.length();
00861   if(l > eps) 
00862   {
00863     s2 /= l;
00864     if(s2 * fudge_factor > s)
00865     {
00866       s = s2;
00867       best_col_id = 0;
00868       normalC = n / l;
00869       invert_normal = (tmp < 0);
00870       code = 12;
00871     }
00872   }
00873 
00874   // separating axis = u3 x (v1,v2,v3)
00875   tmp = pp[1] * R(0, 0) - pp[0] * R(1, 0);
00876   s2 = std::abs(tmp) - (A[0] * Q(1, 0) + A[1] * Q(0, 0) + B[1] * Q(2, 2) + B[2] * Q(2, 1));
00877   if(s2 > eps) { *return_code = 0; return 0; }
00878   n = Vec3f(-R(1, 0), R(0, 0), 0);
00879   l = n.length();
00880   if(l > eps) 
00881   {
00882     s2 /= l;
00883     if(s2 * fudge_factor > s)
00884     {
00885       s = s2;
00886       best_col_id = 0;
00887       normalC = n / l;
00888       invert_normal = (tmp < 0);
00889       code = 13;
00890     }
00891   }
00892 
00893   tmp = pp[1] * R(0, 1) - pp[0] * R(1, 1);
00894   s2 = std::abs(tmp) - (A[0] * Q(1, 1) + A[1] * Q(0, 1) + B[0] * Q(2, 2) + B[2] * Q(2, 0));
00895   if(s2 > eps) { *return_code = 0; return 0; }
00896   n = Vec3f(-R(1, 1), R(0, 1), 0);
00897   l = n.length();
00898   if(l > eps) 
00899   {
00900     s2 /= l;
00901     if(s2 * fudge_factor > s)
00902     {
00903       s = s2;
00904       best_col_id = 0;
00905       normalC = n / l;
00906       invert_normal = (tmp < 0);
00907       code = 14;
00908     }
00909   }
00910   
00911   tmp = pp[1] * R(0, 2) - pp[0] * R(1, 2);
00912   s2 = std::abs(tmp) - (A[0] * Q(1, 2) + A[1] * Q(0, 2) + B[0] * Q(2, 1) + B[1] * Q(2, 0));
00913   if(s2 > eps) { *return_code = 0; return 0; }
00914   n = Vec3f(-R(1, 2), R(0, 2), 0);
00915   l = n.length();
00916   if(l > eps) 
00917   {
00918     s2 /= l;
00919     if(s2 * fudge_factor > s)
00920     {
00921       s = s2;
00922       best_col_id = 0;
00923       normalC = n / l;
00924       invert_normal = (tmp < 0);
00925       code = 15;
00926     }
00927   }
00928 
00929 
00930   
00931   if (!code) { *return_code = code; return 0; }
00932 
00933   // if we get to this point, the boxes interpenetrate. compute the normal
00934   // in global coordinates.
00935   if(best_col_id != -1) 
00936     normal = R.getColumn(best_col_id);
00937   else 
00938     normal = R1 * normalC;
00939   
00940   if(invert_normal) 
00941     normal.negate();
00942 
00943   *depth = -s;
00944 
00945   // compute contact point(s)
00946 
00947   if(code > 6) 
00948   {
00949     // an edge from box 1 touches an edge from box 2.
00950     // find a point pa on the intersecting edge of box 1
00951     Vec3f pa(T1);
00952     FCL_REAL sign;
00953   
00954     for(int j = 0; j < 3; ++j)
00955     {
00956       sign = (R1.transposeDot(j, normal) > 0) ? 1 : -1;
00957       pa += R1.getColumn(j) * (A[j] * sign);
00958     }
00959   
00960     // find a point pb on the intersecting edge of box 2
00961     Vec3f pb;
00962     pb = T2;
00963     for(int j = 0; j < 3; ++j)
00964     {
00965       sign = (R2.transposeDot(j, normal) > 0) ? 1 : -1;
00966       pb += R2.getColumn(j) * (B[j] * sign);
00967     }
00968 
00969     FCL_REAL alpha, beta;
00970     Vec3f ua(R1.getColumn((code-7)/3));
00971     Vec3f ub(R2.getColumn((code-7)%3));
00972     
00973     lineClosestApproach(pa, ua, pb, ub, &alpha, &beta);
00974     pa += ua * alpha;
00975     pb += ub * beta;
00976     
00977     
00978     Vec3f pointInWorld((pa + pb) * 0.5);
00979     contacts.push_back(ContactPoint(-normal, pointInWorld, -*depth));
00980     *return_code = code;
00981     
00982     return 1;
00983   }
00984 
00985   // okay, we have a face-something intersection (because the separating
00986   // axis is perpendicular to a face). define face 'a' to be the reference
00987   // face (i.e. the normal vector is perpendicular to this) and face 'b' to be
00988   // the incident face (the closest face of the other box).
00989   
00990   const Matrix3f *Ra, *Rb;
00991   const Vec3f *pa, *pb, *Sa, *Sb;
00992 
00993   if(code <= 3)
00994   {
00995     Ra = &R1;
00996     Rb = &R2;
00997     pa = &T1;
00998     pb = &T2;
00999     Sa = &A;
01000     Sb = &B;
01001   }
01002   else
01003   {
01004     Ra = &R2;
01005     Rb = &R1;
01006     pa = &T2;
01007     pb = &T1;
01008     Sa = &B;
01009     Sb = &A;
01010   }
01011 
01012   // nr = normal vector of reference face dotted with axes of incident box.
01013   // anr = absolute values of nr.
01014   Vec3f normal2, nr, anr;
01015   if(code <= 3) 
01016     normal2 = normal;
01017   else 
01018     normal2 = -normal;
01019 
01020   nr = Rb->transposeTimes(normal2);
01021   anr = abs(anr);
01022 
01023   // find the largest compontent of anr: this corresponds to the normal
01024   // for the indident face. the other axis numbers of the indicent face
01025   // are stored in a1,a2.
01026   int lanr, a1, a2;
01027   if(anr[1] > anr[0]) 
01028   {
01029     if(anr[1] > anr[2]) 
01030     {
01031       a1 = 0;
01032       lanr = 1;
01033       a2 = 2;
01034     }
01035     else 
01036     {
01037       a1 = 0;
01038       a2 = 1;
01039       lanr = 2;
01040     }
01041   }
01042   else 
01043   {
01044     if(anr[0] > anr[2]) 
01045     {
01046       lanr = 0;
01047       a1 = 1;
01048       a2 = 2;
01049     }
01050     else 
01051     {
01052       a1 = 0;
01053       a2 = 1;
01054       lanr = 2;
01055     }
01056   }
01057 
01058   // compute center point of incident face, in reference-face coordinates
01059   Vec3f center;
01060   if(nr[lanr] < 0) 
01061     center = (*pb) - (*pa) + Rb->getColumn(lanr) * ((*Sb)[lanr]);
01062   else
01063     center = (*pb) - (*pa) - Rb->getColumn(lanr) * ((*Sb)[lanr]);
01064 
01065   // find the normal and non-normal axis numbers of the reference box
01066   int codeN, code1, code2;
01067   if(code <= 3) 
01068     codeN = code-1; 
01069   else codeN = code-4;
01070   
01071   if(codeN == 0) 
01072   {
01073     code1 = 1;
01074     code2 = 2;
01075   }
01076   else if(codeN == 1) 
01077   {
01078     code1 = 0;
01079     code2 = 2;
01080   }
01081   else 
01082   {
01083     code1 = 0;
01084     code2 = 1;
01085   }
01086 
01087   // find the four corners of the incident face, in reference-face coordinates
01088   FCL_REAL quad[8]; // 2D coordinate of incident face (x,y pairs)
01089   FCL_REAL c1, c2, m11, m12, m21, m22;
01090   c1 = Ra->transposeDot(code1, center);
01091   c2 = Ra->transposeDot(code2, center);
01092   // optimize this? - we have already computed this data above, but it is not
01093   // stored in an easy-to-index format. for now it's quicker just to recompute
01094   // the four dot products.
01095   Vec3f tempRac = Ra->getColumn(code1);
01096   m11 = Rb->transposeDot(a1, tempRac);
01097   m12 = Rb->transposeDot(a2, tempRac);
01098   tempRac = Ra->getColumn(code2);
01099   m21 = Rb->transposeDot(a1, tempRac);
01100   m22 = Rb->transposeDot(a2, tempRac);
01101  
01102   FCL_REAL k1 = m11 * (*Sb)[a1];
01103   FCL_REAL k2 = m21 * (*Sb)[a1];
01104   FCL_REAL k3 = m12 * (*Sb)[a2];
01105   FCL_REAL k4 = m22 * (*Sb)[a2];
01106   quad[0] = c1 - k1 - k3;
01107   quad[1] = c2 - k2 - k4;
01108   quad[2] = c1 - k1 + k3;
01109   quad[3] = c2 - k2 + k4;
01110   quad[4] = c1 + k1 + k3;
01111   quad[5] = c2 + k2 + k4;
01112   quad[6] = c1 + k1 - k3;
01113   quad[7] = c2 + k2 - k4;
01114 
01115   // find the size of the reference face
01116   FCL_REAL rect[2];
01117   rect[0] = (*Sa)[code1];
01118   rect[1] = (*Sa)[code2];
01119 
01120   // intersect the incident and reference faces
01121   FCL_REAL ret[16];
01122   int n_intersect = intersectRectQuad2(rect, quad, ret);
01123   if(n_intersect < 1) { *return_code = code; return 0; } // this should never happen
01124 
01125   // convert the intersection points into reference-face coordinates,
01126   // and compute the contact position and depth for each point. only keep
01127   // those points that have a positive (penetrating) depth. delete points in
01128   // the 'ret' array as necessary so that 'point' and 'ret' correspond.
01129   Vec3f points[8]; // penetrating contact points
01130   FCL_REAL dep[8]; // depths for those points
01131   FCL_REAL det1 = 1.f/(m11*m22 - m12*m21);
01132   m11 *= det1;
01133   m12 *= det1;
01134   m21 *= det1;
01135   m22 *= det1;
01136   int cnum = 0; // number of penetrating contact points found
01137   for(int j = 0; j < n_intersect; ++j) 
01138   {
01139     FCL_REAL k1 =  m22*(ret[j*2]-c1) - m12*(ret[j*2+1]-c2);
01140     FCL_REAL k2 = -m21*(ret[j*2]-c1) + m11*(ret[j*2+1]-c2);
01141     points[cnum] = center + Rb->getColumn(a1) * k1 + Rb->getColumn(a2) * k2;
01142     dep[cnum] = (*Sa)[codeN] - normal2.dot(points[cnum]);
01143     if(dep[cnum] >= 0) 
01144     {
01145       ret[cnum*2] = ret[j*2];
01146       ret[cnum*2+1] = ret[j*2+1];
01147       cnum++;
01148     }
01149   }
01150   if(cnum < 1) { *return_code = code; return 0; } // this should never happen
01151 
01152   // we can't generate more contacts than we actually have
01153   if(maxc > cnum) maxc = cnum;
01154   if(maxc < 1) maxc = 1;
01155 
01156   if(cnum <= maxc) 
01157   {
01158     if(code<4) 
01159     {
01160       // we have less contacts than we need, so we use them all
01161       for(int j = 0; j < cnum; ++j) 
01162       {
01163         Vec3f pointInWorld = points[j] + (*pa);
01164         contacts.push_back(ContactPoint(-normal, pointInWorld, -dep[j]));
01165       }
01166     } 
01167     else
01168     {
01169       // we have less contacts than we need, so we use them all
01170       for(int j = 0; j < cnum; ++j) 
01171       {
01172         Vec3f pointInWorld = points[j] + (*pa) - normal * dep[j];
01173         contacts.push_back(ContactPoint(-normal, pointInWorld, -dep[j]));
01174       }
01175     }
01176   }
01177   else 
01178   {
01179     // we have more contacts than are wanted, some of them must be culled.
01180     // find the deepest point, it is always the first contact.
01181     int i1 = 0;
01182     FCL_REAL maxdepth = dep[0];
01183     for(int i = 1; i < cnum; ++i) 
01184     {
01185       if(dep[i] > maxdepth) 
01186       {
01187         maxdepth = dep[i];
01188         i1 = i;
01189       }
01190     }
01191 
01192     int iret[8];
01193     cullPoints2(cnum, ret, maxc, i1, iret);
01194 
01195     for(int j = 0; j < maxc; ++j) 
01196     {
01197       Vec3f posInWorld = points[iret[j] * 3] + (*pa);
01198       if(code < 4)
01199         contacts.push_back(ContactPoint(-normal, posInWorld, -dep[iret[j]]));
01200       else
01201         contacts.push_back(ContactPoint(-normal, posInWorld - normal * dep[iret[j]], -dep[iret[j]]));
01202     }
01203     cnum = maxc;
01204   }
01205 
01206   *return_code = code;
01207   return cnum;
01208 }
01209 
01210 
01211 
01212 bool boxBoxIntersect(const Box& s1, const Transform3f& tf1,
01213                      const Box& s2, const Transform3f& tf2,
01214                      Vec3f* contact_points, FCL_REAL* penetration_depth_, Vec3f* normal_)
01215 {
01216   std::vector<ContactPoint> contacts;
01217   int return_code; 
01218   Vec3f normal;
01219   FCL_REAL depth;
01220   int cnum = boxBox2(s1.side, tf1.getRotation(), tf1.getTranslation(),
01221                      s2.side, tf2.getRotation(), tf2.getTranslation(),
01222                      normal, &depth, &return_code,
01223                      4, contacts);
01224 
01225   if(normal_) *normal_ = normal;
01226   if(penetration_depth_) *penetration_depth_ = depth;
01227 
01228   if(contact_points)
01229   {
01230     Vec3f contact_point;
01231     for(size_t i = 0; i < contacts.size(); ++i)
01232     {
01233       contact_point += contacts[i].point;
01234     }
01235 
01236     contact_point = contact_point / (FCL_REAL)contacts.size();
01237 
01238     *contact_points = contact_point;
01239   }
01240 
01241   return return_code != 0;
01242 }
01243 
01244 template<typename T>
01245 T halfspaceIntersectTolerance()
01246 {
01247   return 0;
01248 }
01249 
01250 template<>
01251 float halfspaceIntersectTolerance()
01252 {
01253   return 0.0001f;
01254 }
01255 
01256 template<>
01257 double halfspaceIntersectTolerance()
01258 {
01259   return 0.0000001;
01260 }
01261 
01262 bool sphereHalfspaceIntersect(const Sphere& s1, const Transform3f& tf1,
01263                               const Halfspace& s2, const Transform3f& tf2,
01264                               Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal)
01265 {
01266   Halfspace new_s2 = transform(s2, tf2);
01267   const Vec3f& center = tf1.getTranslation();
01268   FCL_REAL depth = s1.radius - new_s2.signedDistance(center);
01269   if(depth >= 0)
01270   {
01271     if(normal) *normal = -new_s2.n; // pointing from s1 to s2
01272     if(penetration_depth) *penetration_depth = depth;
01273     if(contact_points) *contact_points = center - new_s2.n * s1.radius + new_s2.n * (depth * 0.5);
01274     return true;
01275   }
01276   else
01277     return false;
01278 }
01279 
01285 bool boxHalfspaceIntersect(const Box& s1, const Transform3f& tf1, 
01286                            const Halfspace& s2, const Transform3f& tf2)
01287 {
01288   Halfspace new_s2 = transform(s2, tf2);
01289   
01290   const Matrix3f& R = tf1.getRotation();
01291   const Vec3f& T = tf1.getTranslation();
01292   
01293   Vec3f Q = R.transposeTimes(new_s2.n);
01294   Vec3f A(Q[0] * s1.side[0], Q[1] * s1.side[1], Q[2] * s1.side[2]);
01295   Vec3f B = abs(A);
01296 
01297   FCL_REAL depth = 0.5 * (B[0] + B[1] + B[2]) - new_s2.signedDistance(T);
01298   return (depth >= 0);
01299 }
01300 
01301 
01302 bool boxHalfspaceIntersect(const Box& s1, const Transform3f& tf1,
01303                            const Halfspace& s2, const Transform3f& tf2,
01304                            Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal)
01305 {
01306   if(!contact_points && !penetration_depth && !normal)
01307     return boxHalfspaceIntersect(s1, tf1, s2, tf2);
01308   else
01309   {
01310     Halfspace new_s2 = transform(s2, tf2);
01311   
01312     const Matrix3f& R = tf1.getRotation();
01313     const Vec3f& T = tf1.getTranslation();
01314   
01315     Vec3f Q = R.transposeTimes(new_s2.n);
01316     Vec3f A(Q[0] * s1.side[0], Q[1] * s1.side[1], Q[2] * s1.side[2]);
01317     Vec3f B = abs(A);
01318 
01319     FCL_REAL depth = 0.5 * (B[0] + B[1] + B[2]) - new_s2.signedDistance(T);
01320     if(depth < 0) return false;
01321     
01322     Vec3f axis[3];
01323     axis[0] = R.getColumn(0);
01324     axis[1] = R.getColumn(1);
01325     axis[2] = R.getColumn(2);
01326 
01328     Vec3f p(T);
01329     int sign = 0;
01330 
01331     if(std::abs(Q[0] - 1) < halfspaceIntersectTolerance<FCL_REAL>() || std::abs(Q[0] + 1) < halfspaceIntersectTolerance<FCL_REAL>())
01332     {
01333       sign = (A[0] > 0) ? -1 : 1;
01334       p += axis[0] * (0.5 * s1.side[0] * sign);
01335     }    
01336     else if(std::abs(Q[1] - 1) < halfspaceIntersectTolerance<FCL_REAL>() || std::abs(Q[1] + 1) < halfspaceIntersectTolerance<FCL_REAL>())
01337     {
01338       sign = (A[1] > 0) ? -1 : 1;
01339       p += axis[1] * (0.5 * s1.side[1] * sign);
01340     }
01341     else if(std::abs(Q[2] - 1) < halfspaceIntersectTolerance<FCL_REAL>() || std::abs(Q[2] + 1) < halfspaceIntersectTolerance<FCL_REAL>())
01342     {
01343       sign = (A[2] > 0) ? -1 : 1;
01344       p += axis[2] * (0.5 * s1.side[2] * sign);
01345     }
01346     else
01347     {
01348       for(std::size_t i = 0; i < 3; ++i)
01349       {
01350         sign = (A[i] > 0) ? -1 : 1;
01351         p += axis[i] * (0.5 * s1.side[i] * sign);
01352       }
01353     }
01354 
01356     if(penetration_depth) *penetration_depth = depth;
01357     if(normal) *normal = -new_s2.n;
01358     if(contact_points) *contact_points = p + new_s2.n * (depth * 0.5);
01359     
01360     return true;
01361   }
01362 }
01363 
01364 bool capsuleHalfspaceIntersect(const Capsule& s1, const Transform3f& tf1,
01365                                const Halfspace& s2, const Transform3f& tf2,
01366                                Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal)
01367 {
01368   Halfspace new_s2 = transform(s2, tf2);
01369 
01370   const Matrix3f& R = tf1.getRotation();
01371   const Vec3f& T = tf1.getTranslation();
01372 
01373   Vec3f dir_z = R.getColumn(2);
01374 
01375   FCL_REAL cosa = dir_z.dot(new_s2.n);
01376   if(cosa < halfspaceIntersectTolerance<FCL_REAL>())
01377   {
01378     FCL_REAL signed_dist = new_s2.signedDistance(T);
01379     FCL_REAL depth = s1.radius - signed_dist;
01380     if(depth < 0) return false;
01381 
01382     if(penetration_depth) *penetration_depth = depth;
01383     if(normal) *normal = -new_s2.n;
01384     if(contact_points) *contact_points = T + new_s2.n * (0.5 * depth - s1.radius);
01385 
01386     return true;
01387   }
01388   else
01389   {
01390     int sign = (cosa > 0) ? -1 : 1;
01391     Vec3f p = T + dir_z * (s1.lz * 0.5 * sign);
01392 
01393     FCL_REAL signed_dist = new_s2.signedDistance(p);
01394     FCL_REAL depth = s1.radius - signed_dist;
01395     if(depth < 0) return false;
01396   
01397     if(penetration_depth) *penetration_depth = depth;
01398     if(normal) *normal = -new_s2.n;
01399     if(contact_points) 
01400     {
01401       // deepest point
01402       Vec3f c = p - new_s2.n * s1.radius;
01403       *contact_points = c + new_s2.n * (0.5 * depth);
01404     }
01405 
01406     return true;
01407   }
01408 }
01409 
01410 
01411 bool cylinderHalfspaceIntersect(const Cylinder& s1, const Transform3f& tf1,
01412                                 const Halfspace& s2, const Transform3f& tf2,
01413                                 Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal)
01414 {
01415   Halfspace new_s2 = transform(s2, tf2);
01416 
01417   const Matrix3f& R = tf1.getRotation();
01418   const Vec3f& T = tf1.getTranslation();
01419 
01420   Vec3f dir_z = R.getColumn(2);
01421   FCL_REAL cosa = dir_z.dot(new_s2.n);
01422 
01423   if(cosa < halfspaceIntersectTolerance<FCL_REAL>())
01424   {
01425     FCL_REAL signed_dist = new_s2.signedDistance(T);
01426     FCL_REAL depth = s1.radius - signed_dist;
01427     if(depth < 0) return false;
01428 
01429     if(penetration_depth) *penetration_depth = depth;
01430     if(normal) *normal = -new_s2.n;
01431     if(contact_points) *contact_points = T + new_s2.n * (0.5 * depth - s1.radius);
01432 
01433     return true;
01434   }
01435   else
01436   {
01437     Vec3f C = dir_z * cosa - new_s2.n;
01438     if(std::abs(cosa + 1) < halfspaceIntersectTolerance<FCL_REAL>() || std::abs(cosa - 1) < halfspaceIntersectTolerance<FCL_REAL>())
01439       C = Vec3f(0, 0, 0);
01440     else
01441     {
01442       FCL_REAL s = C.length();
01443       s = s1.radius / s;
01444       C *= s;
01445     }
01446 
01447     int sign = (cosa > 0) ? -1 : 1;
01448     // deepest point
01449     Vec3f p = T + dir_z * (s1.lz * 0.5 * sign) + C;
01450     FCL_REAL depth = -new_s2.signedDistance(p);
01451     if(depth < 0) return false;
01452     else
01453     {
01454       if(penetration_depth) *penetration_depth = depth;
01455       if(normal) *normal = -new_s2.n;
01456       if(contact_points) *contact_points = p + new_s2.n * (0.5 * depth);
01457       return true;
01458     }
01459   }
01460 }
01461 
01462 
01463 bool coneHalfspaceIntersect(const Cone& s1, const Transform3f& tf1,
01464                             const Halfspace& s2, const Transform3f& tf2,
01465                             Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal)
01466 {
01467   Halfspace new_s2 = transform(s2, tf2);
01468 
01469   const Matrix3f& R = tf1.getRotation();
01470   const Vec3f& T = tf1.getTranslation();
01471 
01472   Vec3f dir_z = R.getColumn(2);
01473   FCL_REAL cosa = dir_z.dot(new_s2.n);
01474 
01475   if(cosa < halfspaceIntersectTolerance<FCL_REAL>())
01476   {
01477     FCL_REAL signed_dist = new_s2.signedDistance(T);
01478     FCL_REAL depth = s1.radius - signed_dist;
01479     if(depth < 0) return false;
01480     else
01481     {
01482       if(penetration_depth) *penetration_depth = depth;
01483       if(normal) *normal = -new_s2.n;
01484       if(contact_points) *contact_points = T - dir_z * (s1.lz * 0.5) + new_s2.n * (0.5 * depth - s1.radius);
01485       return true;
01486     }
01487   }
01488   else
01489   {
01490     Vec3f C = dir_z * cosa - new_s2.n;
01491     if(std::abs(cosa + 1) < halfspaceIntersectTolerance<FCL_REAL>() || std::abs(cosa - 1) < halfspaceIntersectTolerance<FCL_REAL>())
01492       C = Vec3f(0, 0, 0);
01493     else
01494     {
01495       FCL_REAL s = C.length();
01496       s = s1.radius / s;
01497       C *= s;
01498     }
01499 
01500     Vec3f p1 = T + dir_z * (0.5 * s1.lz);
01501     Vec3f p2 = T - dir_z * (0.5 * s1.lz) + C;
01502     
01503     FCL_REAL d1 = new_s2.signedDistance(p1);
01504     FCL_REAL d2 = new_s2.signedDistance(p2);
01505 
01506     if(d1 > 0 && d2 > 0) return false;
01507     else
01508     {
01509       FCL_REAL depth = -std::min(d1, d2);
01510       if(penetration_depth) *penetration_depth = depth;
01511       if(normal) *normal = -new_s2.n;
01512       if(contact_points) *contact_points = ((d1 < d2) ? p1 : p2) + new_s2.n * (0.5 * depth);
01513       return true;
01514     }                                           
01515   }
01516 }
01517 
01518 bool convexHalfspaceIntersect(const Convex& s1, const Transform3f& tf1,
01519                               const Halfspace& s2, const Transform3f& tf2,
01520                               Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal)
01521 {
01522   Halfspace new_s2 = transform(s2, tf2);
01523 
01524   Vec3f v;
01525   FCL_REAL depth = std::numeric_limits<FCL_REAL>::max();
01526 
01527   for(std::size_t i = 0; i < s1.num_points; ++i)
01528   {
01529     Vec3f p = tf1.transform(s1.points[i]);
01530     
01531     FCL_REAL d = new_s2.signedDistance(p);
01532     if(d < depth)
01533     {
01534       depth = d;
01535       v = p;
01536     }
01537   }
01538 
01539   if(depth <= 0)
01540   {
01541     if(contact_points) *contact_points = v - new_s2.n * (0.5 * depth);
01542     if(penetration_depth) *penetration_depth = depth;
01543     if(normal) *normal = -new_s2.n;
01544     return true;
01545   }
01546   else
01547     return false;
01548 }
01549 
01550 bool halfspaceTriangleIntersect(const Halfspace& s1, const Transform3f& tf1,
01551                                 const Vec3f& P1, const Vec3f& P2, const Vec3f& P3, const Transform3f& tf2,
01552                                 Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal)
01553 {
01554   Halfspace new_s1 = transform(s1, tf1);
01555 
01556   Vec3f v = tf2.transform(P1);
01557   FCL_REAL depth = new_s1.signedDistance(v);
01558 
01559   Vec3f p = tf2.transform(P2);
01560   FCL_REAL d = new_s1.signedDistance(p);
01561   if(d < depth)
01562   {
01563     depth = d;
01564     v = p;
01565   }
01566 
01567   p = tf2.transform(P3);
01568   d = new_s1.signedDistance(p);
01569   if(d < depth)
01570   {
01571     depth = d;
01572     v = p;
01573   }
01574 
01575   if(depth <= 0)
01576   {
01577     if(penetration_depth) *penetration_depth = -depth;
01578     if(normal) *normal = new_s1.n;
01579     if(contact_points) *contact_points = v - new_s1.n * (0.5 * depth);
01580     return true;
01581   }
01582   else
01583     return false;
01584 }
01585 
01586 
01594 bool planeHalfspaceIntersect(const Plane& s1, const Transform3f& tf1,
01595                              const Halfspace& s2, const Transform3f& tf2,
01596                              Plane& pl, 
01597                              Vec3f& p, Vec3f& d,
01598                              FCL_REAL& penetration_depth,
01599                              int& ret)
01600 {
01601   Plane new_s1 = transform(s1, tf1);
01602   Halfspace new_s2 = transform(s2, tf2);
01603 
01604   ret = 0;
01605 
01606   Vec3f dir = (new_s1.n).cross(new_s2.n);
01607   FCL_REAL dir_norm = dir.sqrLength();
01608   if(dir_norm < std::numeric_limits<FCL_REAL>::epsilon()) // parallel
01609   {
01610     if((new_s1.n).dot(new_s2.n) > 0)
01611     {
01612       if(new_s1.d < new_s2.d)
01613       {
01614         penetration_depth = new_s2.d - new_s1.d;
01615         ret = 1;
01616         pl = new_s1;
01617         return true;
01618       }
01619       else
01620         return false;
01621     }
01622     else
01623     {
01624       if(new_s1.d + new_s2.d > 0)
01625         return false;
01626       else
01627       {
01628         penetration_depth = -(new_s1.d + new_s2.d);
01629         ret = 2;
01630         pl = new_s1;
01631         return true;
01632       }
01633     }
01634   }
01635   
01636   Vec3f n = new_s2.n * new_s1.d - new_s1.n * new_s2.d;
01637   Vec3f origin = n.cross(dir);
01638   origin *= (1.0 / dir_norm);
01639 
01640   p = origin;
01641   d = dir;
01642   ret = 3;
01643   penetration_depth = std::numeric_limits<FCL_REAL>::max();
01644 
01645   return true;
01646 }
01647 
01656 bool halfspaceIntersect(const Halfspace& s1, const Transform3f& tf1,
01657                         const Halfspace& s2, const Transform3f& tf2,
01658                         Vec3f& p, Vec3f& d, 
01659                         Halfspace& s,
01660                         FCL_REAL& penetration_depth,
01661                         int& ret)
01662 {
01663   Halfspace new_s1 = transform(s1, tf1);
01664   Halfspace new_s2 = transform(s2, tf2);
01665 
01666   ret = 0;
01667   
01668   Vec3f dir = (new_s1.n).cross(new_s2.n);
01669   FCL_REAL dir_norm = dir.sqrLength();
01670   if(dir_norm < std::numeric_limits<FCL_REAL>::epsilon()) // parallel 
01671   {
01672     if((new_s1.n).dot(new_s2.n) > 0)
01673     {
01674       if(new_s1.d < new_s2.d) // s1 is inside s2
01675       {
01676         ret = 1;
01677         penetration_depth = std::numeric_limits<FCL_REAL>::max();
01678         s = new_s1;
01679       }
01680       else // s2 is inside s1
01681       {
01682         ret = 2;
01683         penetration_depth = std::numeric_limits<FCL_REAL>::max();
01684         s = new_s2;
01685       }
01686       return true;
01687     }
01688     else
01689     {
01690       if(new_s1.d + new_s2.d > 0) // not collision
01691         return false;
01692       else // in each other
01693       {
01694         ret = 3;
01695         penetration_depth = -(new_s1.d + new_s2.d);
01696         return true;
01697       }    
01698     }
01699   }
01700 
01701   Vec3f n = new_s2.n * new_s1.d - new_s1.n * new_s2.d;
01702   Vec3f origin = n.cross(dir);
01703   origin *= (1.0 / dir_norm);
01704 
01705   p = origin;
01706   d = dir;
01707   ret = 4;
01708   penetration_depth = std::numeric_limits<FCL_REAL>::max();
01709 
01710   return true;
01711 }
01712 
01713 template<typename T>
01714 T planeIntersectTolerance()
01715 {
01716   return 0;
01717 }
01718 
01719 template<>
01720 double planeIntersectTolerance<double>()
01721 {
01722   return 0.0000001;
01723 }
01724 
01725 template<>
01726 float planeIntersectTolerance<float>()
01727 {
01728   return 0.0001;
01729 }
01730 
01731 bool spherePlaneIntersect(const Sphere& s1, const Transform3f& tf1,
01732                           const Plane& s2, const Transform3f& tf2,
01733                           Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal)
01734 {
01735   Plane new_s2 = transform(s2, tf2);
01736  
01737   const Vec3f& center = tf1.getTranslation();
01738   FCL_REAL signed_dist = new_s2.signedDistance(center);
01739   FCL_REAL depth = - std::abs(signed_dist) + s1.radius;
01740   if(depth >= 0)
01741   {
01742     if(normal) *normal = (signed_dist > 0) ? -new_s2.n : new_s2.n;
01743     if(penetration_depth) *penetration_depth = depth;
01744     if(contact_points) *contact_points = center - new_s2.n * signed_dist;
01745 
01746     return true;
01747   }
01748   else
01749     return false;
01750 }
01751 
01759 bool boxPlaneIntersect(const Box& s1, const Transform3f& tf1,
01760                        const Plane& s2, const Transform3f& tf2,
01761                        Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal)
01762 {
01763   Plane new_s2 = transform(s2, tf2);
01764 
01765   const Matrix3f& R = tf1.getRotation();
01766   const Vec3f& T = tf1.getTranslation();
01767 
01768   Vec3f Q = R.transposeTimes(new_s2.n);
01769   Vec3f A(Q[0] * s1.side[0], Q[1] * s1.side[1], Q[2] * s1.side[2]);
01770   Vec3f B = abs(A);
01771 
01772   FCL_REAL signed_dist = new_s2.signedDistance(T);
01773   FCL_REAL depth = 0.5 * (B[0] + B[1] + B[2]) - std::abs(signed_dist);
01774   if(depth < 0) return false;
01775 
01776   Vec3f axis[3];
01777   axis[0] = R.getColumn(0);
01778   axis[1] = R.getColumn(1);
01779   axis[2] = R.getColumn(2);
01780 
01781   // find the deepest point
01782   Vec3f p = T;
01783 
01784   // when center is on the positive side of the plane, use a, b, c make (R^T n) (a v1 + b v2 + c v3) the minimum
01785   // otherwise, use a, b, c make (R^T n) (a v1 + b v2 + c v3) the maximum
01786   int sign = (signed_dist > 0) ? 1 : -1;
01787 
01788   if(std::abs(Q[0] - 1) < planeIntersectTolerance<FCL_REAL>() || std::abs(Q[0] + 1) < planeIntersectTolerance<FCL_REAL>())
01789   {
01790     int sign2 = (A[0] > 0) ? -1 : 1;
01791     sign2 *= sign;
01792     p += axis[0] * (0.5 * s1.side[0] * sign2);
01793   }
01794   else if(std::abs(Q[1] - 1) < planeIntersectTolerance<FCL_REAL>() || std::abs(Q[1] + 1) < planeIntersectTolerance<FCL_REAL>())
01795   {
01796     int sign2 = (A[1] > 0) ? -1 : 1;
01797     sign2 *= sign;
01798     p += axis[1] * (0.5 * s1.side[1] * sign2);
01799   }
01800   else if(std::abs(Q[2] - 1) < planeIntersectTolerance<FCL_REAL>() || std::abs(Q[2] + 1) < planeIntersectTolerance<FCL_REAL>())
01801   {
01802     int sign2 = (A[2] > 0) ? -1 : 1;
01803     sign2 *= sign;
01804     p += axis[2] * (0.5 * s1.side[2] * sign2);
01805   }
01806   else
01807   {
01808     for(std::size_t i = 0; i < 3; ++i)
01809     {
01810       int sign2 = (A[i] > 0) ? -1 : 1;
01811       sign2 *= sign;
01812       p += axis[i] * (0.5 * s1.side[i] * sign2);
01813     }
01814   }
01815 
01816   // compute the contact point by project the deepest point onto the plane
01817   if(penetration_depth) *penetration_depth = depth;
01818   if(normal) *normal = (signed_dist > 0) ? -new_s2.n : new_s2.n;
01819   if(contact_points) *contact_points = p - new_s2.n * new_s2.signedDistance(p);
01820 
01821   return true;
01822 }
01823 
01824 
01825 bool capsulePlaneIntersect(const Capsule& s1, const Transform3f& tf1,
01826                            const Plane& s2, const Transform3f& tf2)
01827 {
01828   Plane new_s2 = transform(s2, tf2);
01829 
01830   const Matrix3f& R = tf1.getRotation();
01831   const Vec3f& T = tf1.getTranslation();
01832 
01833   Vec3f dir_z = R.getColumn(2);
01834   Vec3f p1 = T + dir_z * (0.5 * s1.lz);
01835   Vec3f p2 = T - dir_z * (0.5 * s1.lz);
01836   
01837   FCL_REAL d1 = new_s2.signedDistance(p1);
01838   FCL_REAL d2 = new_s2.signedDistance(p2);
01839 
01840   // two end points on different side of the plane
01841   if(d1 * d2 <= 0)
01842     return true;
01843 
01844   // two end points on the same side of the plane, but the end point spheres might intersect the plane
01845   return (std::abs(d1) <= s1.radius) || (std::abs(d2) <= s1.radius);
01846 }
01847 
01848 bool capsulePlaneIntersect(const Capsule& s1, const Transform3f& tf1,
01849                            const Plane& s2, const Transform3f& tf2,
01850                            Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal)
01851 {
01852   Plane new_s2 = transform(s2, tf2);
01853 
01854   if(!contact_points && !penetration_depth && !normal)
01855     return capsulePlaneIntersect(s1, tf1, s2, tf2);
01856   else
01857   {
01858     Plane new_s2 = transform(s2, tf2);
01859     
01860     const Matrix3f& R = tf1.getRotation();
01861     const Vec3f& T = tf1.getTranslation();
01862 
01863     Vec3f dir_z = R.getColumn(2);
01864 
01865 
01866     Vec3f p1 = T + dir_z * (0.5 * s1.lz);
01867     Vec3f p2 = T - dir_z * (0.5 * s1.lz);
01868     
01869     FCL_REAL d1 = new_s2.signedDistance(p1);
01870     FCL_REAL d2 = new_s2.signedDistance(p2);
01871 
01872     FCL_REAL abs_d1 = std::abs(d1);
01873     FCL_REAL abs_d2 = std::abs(d2);
01874 
01875     // two end points on different side of the plane
01876     // the contact point is the intersect of axis with the plane
01877     // the normal is the direction to avoid intersection
01878     // the depth is the minimum distance to resolve the collision
01879     if(d1 * d2 < -planeIntersectTolerance<FCL_REAL>())
01880     {
01881       if(abs_d1 < abs_d2)
01882       {
01883         if(penetration_depth) *penetration_depth = abs_d1 + s1.radius;
01884         if(contact_points) *contact_points = p1 * (abs_d2 / (abs_d1 + abs_d2)) + p2 * (abs_d1 / (abs_d1 + abs_d2));
01885         if(normal) *normal = (d1 < 0) ? -new_s2.n : new_s2.n;
01886       }
01887       else
01888       {
01889         if(penetration_depth) *penetration_depth = abs_d2 + s1.radius;
01890         if(contact_points) *contact_points = p1 * (abs_d2 / (abs_d1 + abs_d2)) + p2 * (abs_d1 / (abs_d1 + abs_d2));
01891         if(normal) *normal = (d2 < 0) ? -new_s2.n : new_s2.n;
01892       }
01893       return true;
01894     }
01895 
01896     if(abs_d1 > s1.radius && abs_d2 > s1.radius)
01897       return false;
01898     else
01899     {
01900       if(penetration_depth) *penetration_depth = s1.radius - std::min(abs_d1, abs_d2);
01901         
01902       if(contact_points)
01903       {
01904         if(abs_d1 <= s1.radius && abs_d2 <= s1.radius)
01905         {
01906           Vec3f c1 = p1 - new_s2.n * d2;
01907           Vec3f c2 = p2 - new_s2.n * d1;
01908           *contact_points = (c1 + c2) * 0.5;
01909         }
01910         else if(abs_d1 <= s1.radius)
01911         {
01912           Vec3f c = p1 - new_s2.n * d1;
01913           *contact_points = c;
01914         }
01915         else if(abs_d2 <= s1.radius)
01916         {
01917           Vec3f c = p2 - new_s2.n * d2;
01918           *contact_points = c;
01919         }
01920       }
01921         
01922       if(normal) *normal = (d1 < 0) ? new_s2.n : -new_s2.n;
01923       return true;
01924     }
01925   }
01926 }
01927 
01933 bool cylinderPlaneIntersect(const Cylinder& s1, const Transform3f& tf1,
01934                             const Plane& s2, const Transform3f& tf2)
01935 {
01936   Plane new_s2 = transform(s2, tf2);
01937 
01938   const Matrix3f& R = tf1.getRotation();
01939   const Vec3f& T = tf1.getTranslation();
01940 
01941   Vec3f Q = R.transposeTimes(new_s2.n);
01942 
01943   FCL_REAL term = std::abs(Q[2]) * s1.lz + s1.radius * std::sqrt(Q[0] * Q[0] + Q[1] * Q[1]);
01944   FCL_REAL dist = new_s2.distance(T);
01945   FCL_REAL depth = term - dist;
01946 
01947   if(depth < 0)
01948     return false;
01949   else
01950     return true;
01951 }
01952 
01953 bool cylinderPlaneIntersect(const Cylinder& s1, const Transform3f& tf1,
01954                             const Plane& s2, const Transform3f& tf2,
01955                             Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal)
01956 {
01957   if(!contact_points && !penetration_depth && !normal)
01958     return cylinderPlaneIntersect(s1, tf1, s2, tf2);
01959   else
01960   {
01961     Plane new_s2 = transform(s2, tf2);
01962   
01963     const Matrix3f& R = tf1.getRotation();
01964     const Vec3f& T = tf1.getTranslation();
01965   
01966     Vec3f dir_z = R.getColumn(2);
01967     FCL_REAL cosa = dir_z.dot(new_s2.n);
01968 
01969     if(std::abs(cosa) < planeIntersectTolerance<FCL_REAL>())
01970     {
01971       FCL_REAL d = new_s2.signedDistance(T);
01972       FCL_REAL depth = s1.radius - std::abs(d);
01973       if(depth < 0) return false;
01974       else
01975       {
01976         if(penetration_depth) *penetration_depth = depth;
01977         if(normal) *normal = (d < 0) ? new_s2.n : -new_s2.n;
01978         if(contact_points) *contact_points = T - new_s2.n * d;
01979         return true;
01980       }
01981     }
01982     else
01983     {
01984       Vec3f C = dir_z * cosa - new_s2.n;
01985       if(std::abs(cosa + 1) < planeIntersectTolerance<FCL_REAL>() || std::abs(cosa - 1) < planeIntersectTolerance<FCL_REAL>())
01986         C = Vec3f(0, 0, 0);
01987       else
01988       {
01989         FCL_REAL s = C.length();
01990         s = s1.radius / s;
01991         C *= s;
01992       }
01993 
01994       Vec3f p1 = T + dir_z * (0.5 * s1.lz);
01995       Vec3f p2 = T - dir_z * (0.5 * s1.lz);
01996 
01997       Vec3f c1, c2;
01998       if(cosa > 0)
01999       {
02000         c1 = p1 - C;
02001         c2 = p2 + C;
02002       }
02003       else
02004       {
02005         c1 = p1 + C;
02006         c2 = p2 - C;
02007       }
02008 
02009       FCL_REAL d1 = new_s2.signedDistance(c1);
02010       FCL_REAL d2 = new_s2.signedDistance(c2);
02011 
02012       if(d1 * d2 <= 0)
02013       {
02014         FCL_REAL abs_d1 = std::abs(d1);
02015         FCL_REAL abs_d2 = std::abs(d2);
02016 
02017         if(abs_d1 > abs_d2)
02018         {
02019           if(penetration_depth) *penetration_depth = abs_d2;
02020           if(contact_points) *contact_points = c2 - new_s2.n * d2;
02021           if(normal) *normal = (d2 < 0) ? -new_s2.n : new_s2.n;
02022         }
02023         else
02024         {
02025           if(penetration_depth) *penetration_depth = abs_d1;
02026           if(contact_points) *contact_points = c1 - new_s2.n * d1;
02027           if(normal) *normal = (d1 < 0) ? -new_s2.n : new_s2.n;
02028         }
02029         return true;
02030       }
02031       else
02032         return false;
02033     }
02034   }
02035 }
02036 
02037 bool conePlaneIntersect(const Cone& s1, const Transform3f& tf1,
02038                         const Plane& s2, const Transform3f& tf2,
02039                         Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal)
02040 {
02041   Plane new_s2 = transform(s2, tf2);
02042   
02043   const Matrix3f& R = tf1.getRotation();
02044   const Vec3f& T = tf1.getTranslation();
02045   
02046   Vec3f dir_z = R.getColumn(2);
02047   FCL_REAL cosa = dir_z.dot(new_s2.n);
02048 
02049   if(std::abs(cosa) < planeIntersectTolerance<FCL_REAL>())
02050   {
02051     FCL_REAL d = new_s2.signedDistance(T);
02052     FCL_REAL depth = s1.radius - std::abs(d);
02053     if(depth < 0) return false;
02054     else
02055     {
02056       if(penetration_depth) *penetration_depth = depth;
02057       if(normal) *normal = (d < 0) ? new_s2.n : -new_s2.n;
02058       if(contact_points) *contact_points = T - dir_z * (0.5 * s1.lz) + dir_z * (0.5 * depth / s1.radius * s1.lz) - new_s2.n * d;
02059       return true;
02060     }
02061   }
02062   else
02063   {
02064     Vec3f C = dir_z * cosa - new_s2.n;
02065     if(std::abs(cosa + 1) < planeIntersectTolerance<FCL_REAL>() || std::abs(cosa - 1) < planeIntersectTolerance<FCL_REAL>())
02066       C = Vec3f(0, 0, 0);
02067     else
02068     {
02069       FCL_REAL s = C.length();
02070       s = s1.radius / s;
02071       C *= s;
02072     }
02073 
02074     Vec3f c[3];
02075     c[0] = T + dir_z * (0.5 * s1.lz);
02076     c[1] = T - dir_z * (0.5 * s1.lz) + C;
02077     c[2] = T - dir_z * (0.5 * s1.lz) - C;
02078 
02079     FCL_REAL d[3];
02080     d[0] = new_s2.signedDistance(c[0]);
02081     d[1] = new_s2.signedDistance(c[1]);
02082     d[2] = new_s2.signedDistance(c[2]);
02083 
02084     if((d[0] >= 0 && d[1] >= 0 && d[2] >= 0) || (d[0] <= 0 && d[1] <= 0 && d[2] <= 0))
02085       return false;
02086     else
02087     {
02088       bool positive[3];
02089       for(std::size_t i = 0; i < 3; ++i)
02090         positive[i] = (d[i] >= 0);
02091 
02092       int n_positive = 0;
02093       FCL_REAL d_positive = 0, d_negative = 0;
02094       for(std::size_t i = 0; i < 3; ++i)
02095       {
02096         if(positive[i]) 
02097         {
02098           n_positive++;
02099           if(d_positive <= d[i]) d_positive = d[i];
02100         }
02101         else
02102         {
02103           if(d_negative <= -d[i]) d_negative = -d[i];
02104         }
02105       }
02106 
02107       if(penetration_depth) *penetration_depth = std::min(d_positive, d_negative);
02108       if(normal) *normal = (d_positive > d_negative) ? -new_s2.n : new_s2.n;
02109       if(contact_points)
02110       {
02111         Vec3f p[2];
02112         Vec3f q;
02113             
02114         FCL_REAL p_d[2];
02115         FCL_REAL q_d;
02116 
02117         if(n_positive == 2)
02118         {            
02119           for(std::size_t i = 0, j = 0; i < 3; ++i)
02120           {
02121             if(positive[i]) { p[j] = c[i]; p_d[j] = d[i]; j++; }
02122             else { q = c[i]; q_d = d[i]; }
02123           }
02124 
02125           Vec3f t1 = (-p[0] * q_d + q * p_d[0]) / (-q_d + p_d[0]);
02126           Vec3f t2 = (-p[1] * q_d + q * p_d[1]) / (-q_d + p_d[1]);
02127           *contact_points = (t1 + t2) * 0.5;
02128         }
02129         else
02130         {            
02131           for(std::size_t i = 0, j = 0; i < 3; ++i)
02132           {
02133             if(!positive[i]) { p[j] = c[i]; p_d[j] = d[i]; j++; }
02134             else { q = c[i]; q_d = d[i]; }
02135           }
02136 
02137           Vec3f t1 = (p[0] * q_d - q * p_d[0]) / (q_d - p_d[0]);
02138           Vec3f t2 = (p[1] * q_d - q * p_d[1]) / (q_d - p_d[1]);
02139           *contact_points = (t1 + t2) * 0.5;            
02140         }
02141       }
02142       return true;
02143     }
02144   }
02145 }
02146 
02147 bool convexPlaneIntersect(const Convex& s1, const Transform3f& tf1,
02148                           const Plane& s2, const Transform3f& tf2,
02149                           Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal)
02150 {
02151   Plane new_s2 = transform(s2, tf2);
02152 
02153   Vec3f v_min, v_max;
02154   FCL_REAL d_min = std::numeric_limits<FCL_REAL>::max(), d_max = -std::numeric_limits<FCL_REAL>::max();
02155 
02156   for(std::size_t i = 0; i < s1.num_points; ++i)
02157   {
02158     Vec3f p = tf1.transform(s1.points[i]);
02159     
02160     FCL_REAL d = new_s2.signedDistance(p);
02161     
02162     if(d < d_min) { d_min = d; v_min = p; }
02163     if(d > d_max) { d_max = d; v_max = p; }
02164   }
02165   
02166   if(d_min * d_max > 0) return false;
02167   else
02168   {
02169     if(d_min + d_max > 0)
02170     {
02171       if(penetration_depth) *penetration_depth = -d_min;
02172       if(normal) *normal = -new_s2.n;
02173       if(contact_points) *contact_points = v_min - new_s2.n * d_min;
02174     }
02175     else
02176     {
02177       if(penetration_depth) *penetration_depth = d_max;
02178       if(normal) *normal = new_s2.n;
02179       if(contact_points) *contact_points = v_max - new_s2.n * d_max;
02180     }
02181     return true;
02182   }
02183 }
02184 
02185 
02186 
02187 bool planeTriangleIntersect(const Plane& s1, const Transform3f& tf1,
02188                             const Vec3f& P1, const Vec3f& P2, const Vec3f& P3, const Transform3f& tf2,
02189                             Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal)
02190 {
02191   Plane new_s1 = transform(s1, tf1);
02192 
02193   Vec3f c[3];
02194   c[0] = tf2.transform(P1);
02195   c[1] = tf2.transform(P2);
02196   c[2] = tf2.transform(P3);
02197 
02198   FCL_REAL d[3];
02199   d[0] = new_s1.signedDistance(c[0]);
02200   d[1] = new_s1.signedDistance(c[1]);
02201   d[2] = new_s1.signedDistance(c[2]);
02202 
02203   if((d[0] >= 0 && d[1] >= 0 && d[2] >= 0) || (d[0] <= 0 && d[1] <= 0 && d[2] <= 0))
02204     return false;
02205   else
02206   {
02207     bool positive[3];
02208     for(std::size_t i = 0; i < 3; ++i)
02209       positive[i] = (d[i] > 0);
02210 
02211     int n_positive = 0;
02212     FCL_REAL d_positive = 0, d_negative = 0;
02213     for(std::size_t i = 0; i < 3; ++i)
02214     {
02215       if(positive[i])
02216       {
02217         n_positive++;
02218         if(d_positive <= d[i]) d_positive = d[i];
02219       }
02220       else
02221       {
02222         if(d_negative <= -d[i]) d_negative = -d[i];
02223       }
02224     }
02225 
02226     if(penetration_depth) *penetration_depth = std::min(d_positive, d_negative);
02227     if(normal) *normal = (d_positive > d_negative) ? new_s1.n : -new_s1.n;
02228     if(contact_points)
02229     {
02230       Vec3f p[2];
02231       Vec3f q;
02232       
02233       FCL_REAL p_d[2];
02234       FCL_REAL q_d;
02235       
02236       if(n_positive == 2)
02237       {
02238         for(std::size_t i = 0, j = 0; i < 3; ++i)
02239         {
02240           if(positive[i]) { p[j] = c[i]; p_d[j] = d[i]; j++; }
02241           else { q = c[i]; q_d = d[i]; }
02242         }
02243 
02244         Vec3f t1 = (-p[0] * q_d + q * p_d[0]) / (-q_d + p_d[0]);
02245         Vec3f t2 = (-p[1] * q_d + q * p_d[1]) / (-q_d + p_d[1]);
02246         *contact_points = (t1 + t2) * 0.5;
02247       }
02248       else
02249       {
02250         for(std::size_t i = 0, j = 0; i < 3; ++i)
02251         {
02252           if(!positive[i]) { p[j] = c[i]; p_d[j] = d[i]; j++; }
02253           else { q = c[i]; q_d = d[i]; }
02254         }
02255 
02256         Vec3f t1 = (p[0] * q_d - q * p_d[0]) / (q_d - p_d[0]);
02257         Vec3f t2 = (p[1] * q_d - q * p_d[1]) / (q_d - p_d[1]);
02258         *contact_points = (t1 + t2) * 0.5;            
02259       }
02260     }
02261     return true;
02262   }
02263 }
02264 
02265 bool halfspacePlaneIntersect(const Halfspace& s1, const Transform3f& tf1,
02266                              const Plane& s2, const Transform3f& tf2,
02267                              Plane& pl, Vec3f& p, Vec3f& d,
02268                              FCL_REAL& penetration_depth,
02269                              int& ret)
02270 {
02271   return planeHalfspaceIntersect(s2, tf2, s1, tf1, pl, p, d, penetration_depth, ret);
02272 }
02273 
02274 bool planeIntersect(const Plane& s1, const Transform3f& tf1,
02275                     const Plane& s2, const Transform3f& tf2,
02276                     Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal)
02277 {
02278   Plane new_s1 = transform(s1, tf1);
02279   Plane new_s2 = transform(s2, tf2);
02280 
02281   FCL_REAL a = (new_s1.n).dot(new_s2.n);
02282   if(a == 1 && new_s1.d != new_s2.d)
02283     return false;
02284   if(a == -1 && new_s1.d != -new_s2.d)
02285     return false;
02286  
02287   return true;
02288 }
02289 
02290 
02291 
02292 } // details
02293 
02294 
02295 template<>
02296 bool GJKSolver_libccd::shapeIntersect<Sphere, Sphere>(const Sphere& s1, const Transform3f& tf1,
02297                                                       const Sphere& s2, const Transform3f& tf2,
02298                                                       Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02299 {
02300   return details::sphereSphereIntersect(s1, tf1, s2, tf2, contact_points, penetration_depth, normal);
02301 }
02302 
02303 template<>
02304 bool GJKSolver_libccd::shapeIntersect<Box, Box>(const Box& s1, const Transform3f& tf1,
02305                                                 const Box& s2, const Transform3f& tf2,
02306                                                 Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02307 {
02308   return details::boxBoxIntersect(s1, tf1, s2, tf2, contact_points, penetration_depth, normal);
02309 }
02310 
02311 template<>
02312 bool GJKSolver_libccd::shapeIntersect<Sphere, Halfspace>(const Sphere& s1, const Transform3f& tf1,
02313                                                          const Halfspace& s2, const Transform3f& tf2,
02314                                                          Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02315 {
02316   return details::sphereHalfspaceIntersect(s1, tf1, s2, tf2, contact_points, penetration_depth, normal);
02317 }
02318 
02319 template<>
02320 bool GJKSolver_libccd::shapeIntersect<Box, Halfspace>(const Box& s1, const Transform3f& tf1,
02321                                                       const Halfspace& s2, const Transform3f& tf2,
02322                                                       Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02323 {
02324   return details::boxHalfspaceIntersect(s1, tf1, s2, tf2, contact_points, penetration_depth, normal);
02325 }
02326 
02327 template<>
02328 bool GJKSolver_libccd::shapeIntersect<Capsule, Halfspace>(const Capsule& s1, const Transform3f& tf1,
02329                                                           const Halfspace& s2, const Transform3f& tf2,
02330                                                           Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02331 {
02332   return details::capsuleHalfspaceIntersect(s1, tf1, s2, tf2, contact_points, penetration_depth, normal);
02333 }
02334 
02335 template<>
02336 bool GJKSolver_libccd::shapeIntersect<Cylinder, Halfspace>(const Cylinder& s1, const Transform3f& tf1,
02337                                                            const Halfspace& s2, const Transform3f& tf2,
02338                                                            Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02339 {
02340   return details::cylinderHalfspaceIntersect(s1, tf1, s2, tf2, contact_points, penetration_depth, normal);
02341 }
02342 
02343 template<>
02344 bool GJKSolver_libccd::shapeIntersect<Cone, Halfspace>(const Cone& s1, const Transform3f& tf1,
02345                                                        const Halfspace& s2, const Transform3f& tf2,
02346                                                        Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02347 {
02348   return details::coneHalfspaceIntersect(s1, tf1, s2, tf2, contact_points, penetration_depth, normal);
02349 }
02350 
02351 template<>
02352 bool GJKSolver_libccd::shapeIntersect<Halfspace, Halfspace>(const Halfspace& s1, const Transform3f& tf1,
02353                                                             const Halfspace& s2, const Transform3f& tf2,
02354                                                             Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02355 {
02356   Halfspace s;
02357   Vec3f p, d;
02358   FCL_REAL depth;
02359   int ret;
02360   return details::halfspaceIntersect(s1, tf1, s2, tf2, p, d, s, depth, ret);
02361 }
02362 
02363 template<>
02364 bool GJKSolver_libccd::shapeIntersect<Plane, Halfspace>(const Plane& s1, const Transform3f& tf1,
02365                                                         const Halfspace& s2, const Transform3f& tf2,
02366                                                         Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02367 {
02368   Plane pl;
02369   Vec3f p, d;
02370   FCL_REAL depth;
02371   int ret;
02372   return details::planeHalfspaceIntersect(s1, tf1, s2, tf2, pl, p, d, depth, ret);
02373 }
02374 
02375 template<>
02376 bool GJKSolver_libccd::shapeIntersect<Sphere, Plane>(const Sphere& s1, const Transform3f& tf1,
02377                                                      const Plane& s2, const Transform3f& tf2,
02378                                                      Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02379 {
02380   return details::spherePlaneIntersect(s1, tf1, s2, tf2, contact_points, penetration_depth, normal);
02381 }
02382 
02383 template<>
02384 bool GJKSolver_libccd::shapeIntersect<Box, Plane>(const Box& s1, const Transform3f& tf1,
02385                                                   const Plane& s2, const Transform3f& tf2,
02386                                                   Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02387 {
02388   return details::boxPlaneIntersect(s1, tf1, s2, tf2, contact_points, penetration_depth, normal);
02389 }
02390 
02391 template<>
02392 bool GJKSolver_libccd::shapeIntersect<Capsule, Plane>(const Capsule& s1, const Transform3f& tf1,
02393                                                       const Plane& s2, const Transform3f& tf2,
02394                                                       Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02395 {
02396   return details::capsulePlaneIntersect(s1, tf1, s2, tf2, contact_points, penetration_depth, normal);
02397 }
02398 
02399 template<>
02400 bool GJKSolver_libccd::shapeIntersect<Cylinder, Plane>(const Cylinder& s1, const Transform3f& tf1,
02401                                                        const Plane& s2, const Transform3f& tf2,
02402                                                        Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02403 {
02404   return details::cylinderPlaneIntersect(s1, tf1, s2, tf2, contact_points, penetration_depth, normal);
02405 }
02406 
02407 template<>
02408 bool GJKSolver_libccd::shapeIntersect<Cone, Plane>(const Cone& s1, const Transform3f& tf1,
02409                                                    const Plane& s2, const Transform3f& tf2,
02410                                                    Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02411 {
02412   return details::conePlaneIntersect(s1, tf1, s2, tf2, contact_points, penetration_depth, normal);
02413 }
02414 
02415 template<>
02416 bool GJKSolver_libccd::shapeIntersect<Halfspace, Plane>(const Halfspace& s1, const Transform3f& tf1,
02417                                                         const Plane& s2, const Transform3f& tf2,
02418                                                         Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02419 {
02420   Plane pl;
02421   Vec3f p, d;
02422   FCL_REAL depth;
02423   int ret;
02424   return details::halfspacePlaneIntersect(s1, tf1, s2, tf2, pl, p, d, depth, ret);
02425 }
02426 
02427 template<>
02428 bool GJKSolver_libccd::shapeIntersect<Plane, Plane>(const Plane& s1, const Transform3f& tf1,
02429                                                     const Plane& s2, const Transform3f& tf2,
02430                                                     Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02431 {
02432   return details::planeIntersect(s1, tf1, s2, tf2, contact_points, penetration_depth, normal);
02433 }
02434 
02435 
02436 template<> 
02437 bool GJKSolver_libccd::shapeTriangleIntersect(const Sphere& s, const Transform3f& tf,
02438                                               const Vec3f& P1, const Vec3f& P2, const Vec3f& P3, Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02439 {
02440   return details::sphereTriangleIntersect(s, tf, P1, P2, P3, contact_points, penetration_depth, normal);
02441 }
02442 
02443 template<> 
02444 bool GJKSolver_libccd::shapeTriangleIntersect(const Sphere& s, const Transform3f& tf1,
02445                                               const Vec3f& P1, const Vec3f& P2, const Vec3f& P3, const Transform3f& tf2, Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02446 {
02447   return details::sphereTriangleIntersect(s, tf1, tf2.transform(P1), tf2.transform(P2), tf2.transform(P3), contact_points, penetration_depth, normal);
02448 }
02449 
02450 
02451 template<>
02452 bool GJKSolver_libccd::shapeTriangleIntersect(const Halfspace& s, const Transform3f& tf1,
02453                                               const Vec3f& P1, const Vec3f& P2, const Vec3f& P3, const Transform3f& tf2, Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02454 {
02455   return details::halfspaceTriangleIntersect(s, tf1, P1, P2, P3, tf2, contact_points, penetration_depth, normal);
02456 }
02457 
02458 template<>
02459 bool GJKSolver_libccd::shapeTriangleIntersect(const Plane& s, const Transform3f& tf1,
02460                                               const Vec3f& P1, const Vec3f& P2, const Vec3f& P3, const Transform3f& tf2, Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02461 {
02462   return details::planeTriangleIntersect(s, tf1, P1, P2, P3, tf2, contact_points, penetration_depth, normal);
02463 }
02464 
02465 
02466 
02467 
02468 template<>
02469 bool GJKSolver_libccd::shapeDistance<Sphere, Sphere>(const Sphere& s1, const Transform3f& tf1,
02470                                                      const Sphere& s2, const Transform3f& tf2,
02471                                                      FCL_REAL* dist) const
02472 {
02473   return details::sphereSphereDistance(s1, tf1, s2, tf2, dist);
02474 }
02475 
02476 template<>
02477 bool GJKSolver_libccd::shapeTriangleDistance<Sphere>(const Sphere& s, const Transform3f& tf,
02478                                                      const Vec3f& P1, const Vec3f& P2, const Vec3f& P3, 
02479                                                      FCL_REAL* dist) const
02480 {
02481   return details::sphereTriangleDistance(s, tf, P1, P2, P3, dist);
02482 }
02483 
02484 template<> 
02485 bool GJKSolver_libccd::shapeTriangleDistance<Sphere>(const Sphere& s, const Transform3f& tf1, 
02486                                                      const Vec3f& P1, const Vec3f& P2, const Vec3f& P3, const Transform3f& tf2,
02487                                                      FCL_REAL* dist) const
02488 {
02489   return details::sphereTriangleDistance(s, tf1, tf2.transform(P1), tf2.transform(P2), tf2.transform(P3), dist);
02490 }
02491 
02492 
02493 
02494 
02495 
02496 
02497 
02498 template<>
02499 bool GJKSolver_indep::shapeIntersect<Sphere, Sphere>(const Sphere& s1, const Transform3f& tf1,
02500                                                      const Sphere& s2, const Transform3f& tf2,
02501                                                      Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02502 {
02503   return details::sphereSphereIntersect(s1, tf1, s2, tf2, contact_points, penetration_depth, normal);
02504 }
02505 
02506 template<>
02507 bool GJKSolver_indep::shapeIntersect<Box, Box>(const Box& s1, const Transform3f& tf1,
02508                                                const Box& s2, const Transform3f& tf2,
02509                                                Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02510 {
02511   return details::boxBoxIntersect(s1, tf1, s2, tf2, contact_points, penetration_depth, normal);
02512 }
02513 
02514 template<>
02515 bool GJKSolver_indep::shapeIntersect<Sphere, Halfspace>(const Sphere& s1, const Transform3f& tf1,
02516                                                         const Halfspace& s2, const Transform3f& tf2,
02517                                                         Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02518 {
02519   return details::sphereHalfspaceIntersect(s1, tf1, s2, tf2, contact_points, penetration_depth, normal);
02520 }
02521 
02522 template<>
02523 bool GJKSolver_indep::shapeIntersect<Box, Halfspace>(const Box& s1, const Transform3f& tf1,
02524                                                      const Halfspace& s2, const Transform3f& tf2,
02525                                                      Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02526 {
02527   return details::boxHalfspaceIntersect(s1, tf1, s2, tf2, contact_points, penetration_depth, normal);
02528 }
02529 
02530 template<>
02531 bool GJKSolver_indep::shapeIntersect<Capsule, Halfspace>(const Capsule& s1, const Transform3f& tf1,
02532                                                          const Halfspace& s2, const Transform3f& tf2,
02533                                                          Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02534 {
02535   return details::capsuleHalfspaceIntersect(s1, tf1, s2, tf2, contact_points, penetration_depth, normal);
02536 }
02537 
02538 template<>
02539 bool GJKSolver_indep::shapeIntersect<Cylinder, Halfspace>(const Cylinder& s1, const Transform3f& tf1,
02540                                                           const Halfspace& s2, const Transform3f& tf2,
02541                                                           Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02542 {
02543   return details::cylinderHalfspaceIntersect(s1, tf1, s2, tf2, contact_points, penetration_depth, normal);
02544 }
02545 
02546 template<>
02547 bool GJKSolver_indep::shapeIntersect<Cone, Halfspace>(const Cone& s1, const Transform3f& tf1,
02548                                                       const Halfspace& s2, const Transform3f& tf2,
02549                                                       Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02550 {
02551   return details::coneHalfspaceIntersect(s1, tf1, s2, tf2, contact_points, penetration_depth, normal);
02552 }
02553 
02554 template<>
02555 bool GJKSolver_indep::shapeIntersect<Halfspace, Halfspace>(const Halfspace& s1, const Transform3f& tf1,
02556                                                            const Halfspace& s2, const Transform3f& tf2,
02557                                                            Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02558 {
02559   Halfspace s;
02560   Vec3f p, d;
02561   FCL_REAL depth;
02562   int ret;
02563   
02564   return details::halfspaceIntersect(s1, tf1, s2, tf2, p, d, s, depth, ret);
02565 }
02566 
02567 template<>
02568 bool GJKSolver_indep::shapeIntersect<Plane, Halfspace>(const Plane& s1, const Transform3f& tf1,
02569                                                        const Halfspace& s2, const Transform3f& tf2,
02570                                                        Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02571 {
02572   Plane pl;
02573   Vec3f p, d;
02574   FCL_REAL depth;
02575   int ret;
02576   return details::planeHalfspaceIntersect(s1, tf1, s2, tf2, pl, p, d, depth, ret);
02577 }
02578 
02579 template<>
02580 bool GJKSolver_indep::shapeIntersect<Sphere, Plane>(const Sphere& s1, const Transform3f& tf1,
02581                                                     const Plane& s2, const Transform3f& tf2,
02582                                                     Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02583 {
02584   return details::spherePlaneIntersect(s1, tf1, s2, tf2, contact_points, penetration_depth, normal);
02585 }
02586 
02587 template<>
02588 bool GJKSolver_indep::shapeIntersect<Box, Plane>(const Box& s1, const Transform3f& tf1,
02589                                                  const Plane& s2, const Transform3f& tf2,
02590                                                  Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02591 {
02592   return details::boxPlaneIntersect(s1, tf1, s2, tf2, contact_points, penetration_depth, normal);
02593 }
02594 
02595 template<>
02596 bool GJKSolver_indep::shapeIntersect<Capsule, Plane>(const Capsule& s1, const Transform3f& tf1,
02597                                                      const Plane& s2, const Transform3f& tf2,
02598                                                      Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02599 {
02600   return details::capsulePlaneIntersect(s1, tf1, s2, tf2, contact_points, penetration_depth, normal);
02601 }
02602 
02603 template<>
02604 bool GJKSolver_indep::shapeIntersect<Cylinder, Plane>(const Cylinder& s1, const Transform3f& tf1,
02605                                                       const Plane& s2, const Transform3f& tf2,
02606                                                       Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02607 {
02608   return details::cylinderPlaneIntersect(s1, tf1, s2, tf2, contact_points, penetration_depth, normal);
02609 }
02610 
02611 template<>
02612 bool GJKSolver_indep::shapeIntersect<Cone, Plane>(const Cone& s1, const Transform3f& tf1,
02613                                                   const Plane& s2, const Transform3f& tf2,
02614                                                   Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02615 {
02616   return details::conePlaneIntersect(s1, tf1, s2, tf2, contact_points, penetration_depth, normal);
02617 }
02618 
02619 template<>
02620 bool GJKSolver_indep::shapeIntersect<Halfspace, Plane>(const Halfspace& s1, const Transform3f& tf1,
02621                                                        const Plane& s2, const Transform3f& tf2,
02622                                                        Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02623 {
02624   Plane pl;
02625   Vec3f p, d;
02626   FCL_REAL depth;
02627   int ret;
02628   return details::halfspacePlaneIntersect(s1, tf1, s2, tf2, pl, p, d, depth, ret);
02629 }
02630 
02631 template<>
02632 bool GJKSolver_indep::shapeIntersect<Plane, Plane>(const Plane& s1, const Transform3f& tf1,
02633                                                    const Plane& s2, const Transform3f& tf2,
02634                                                    Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02635 {
02636   return details::planeIntersect(s1, tf1, s2, tf2, contact_points, penetration_depth, normal);
02637 }
02638 
02639 
02640 template<> 
02641 bool GJKSolver_indep::shapeTriangleIntersect(const Sphere& s, const Transform3f& tf,
02642                                              const Vec3f& P1, const Vec3f& P2, const Vec3f& P3, Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02643 {
02644   return details::sphereTriangleIntersect(s, tf, P1, P2, P3, contact_points, penetration_depth, normal);
02645 }
02646 
02647 template<> 
02648 bool GJKSolver_indep::shapeTriangleIntersect(const Sphere& s, const Transform3f& tf1,
02649                                              const Vec3f& P1, const Vec3f& P2, const Vec3f& P3, const Transform3f& tf2, Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02650 {
02651   return details::sphereTriangleIntersect(s, tf1, tf2.transform(P1), tf2.transform(P2), tf2.transform(P3), contact_points, penetration_depth, normal);
02652 }
02653 
02654 template<>
02655 bool GJKSolver_indep::shapeTriangleIntersect(const Halfspace& s, const Transform3f& tf1,
02656                                              const Vec3f& P1, const Vec3f& P2, const Vec3f& P3, const Transform3f& tf2, Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02657 {
02658   return details::halfspaceTriangleIntersect(s, tf1, P1, P2, P3, tf2, contact_points, penetration_depth, normal);
02659 }
02660 
02661 template<>
02662 bool GJKSolver_indep::shapeTriangleIntersect(const Plane& s, const Transform3f& tf1,
02663                                              const Vec3f& P1, const Vec3f& P2, const Vec3f& P3, const Transform3f& tf2, Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal) const
02664 {
02665   return details::planeTriangleIntersect(s, tf1, P1, P2, P3, tf2, contact_points, penetration_depth, normal);
02666 }
02667 
02668 
02669 template<>
02670 bool GJKSolver_indep::shapeDistance<Sphere, Sphere>(const Sphere& s1, const Transform3f& tf1,
02671                                                     const Sphere& s2, const Transform3f& tf2,
02672                                                     FCL_REAL* dist) const
02673 {
02674   return details::sphereSphereDistance(s1, tf1, s2, tf2, dist);
02675 }
02676 
02677 template<>
02678 bool GJKSolver_indep::shapeTriangleDistance<Sphere>(const Sphere& s, const Transform3f& tf,
02679                                                     const Vec3f& P1, const Vec3f& P2, const Vec3f& P3, 
02680                                                     FCL_REAL* dist) const
02681 {
02682   return details::sphereTriangleDistance(s, tf, P1, P2, P3, dist);
02683 }
02684 
02685 template<> 
02686 bool GJKSolver_indep::shapeTriangleDistance<Sphere>(const Sphere& s, const Transform3f& tf1, 
02687                                                     const Vec3f& P1, const Vec3f& P2, const Vec3f& P3, const Transform3f& tf2,
02688                                                     FCL_REAL* dist) const
02689 {
02690   return details::sphereTriangleDistance(s, tf1, tf2.transform(P1), tf2.transform(P2), tf2.transform(P3), dist);
02691 }
02692 
02693 
02694 
02695 
02696 
02697 
02698 } // fcl
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


fcl
Author(s): Jia Pan
autogenerated on Tue Jan 15 2013 16:05:30