All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends

gjk.cpp

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/gjk.h"
00038 
00039 namespace fcl
00040 {
00041 
00042 namespace details
00043 {
00044 
00045 Vec3f getSupport(const ShapeBase* shape, const Vec3f& dir)
00046 {
00047   switch(shape->getNodeType())
00048   {
00049   case GEOM_TRIANGLE:
00050     {
00051       const Triangle2* triangle = static_cast<const Triangle2*>(shape);
00052       FCL_REAL dota = dir.dot(triangle->a);
00053       FCL_REAL dotb = dir.dot(triangle->b);
00054       FCL_REAL dotc = dir.dot(triangle->c);
00055       if(dota > dotb)
00056       {
00057         if(dotc > dota)
00058           return triangle->c;
00059         else
00060           return triangle->a;
00061       }
00062       else
00063       {
00064         if(dotc > dotb)
00065           return triangle->c;
00066         else
00067           return triangle->b;
00068       }
00069     }
00070     break;
00071   case GEOM_BOX:
00072     {
00073       const Box* box = static_cast<const Box*>(shape);
00074       return Vec3f((dir[0]>0)?(box->side[0]/2):(-box->side[0]/2),
00075                    (dir[1]>0)?(box->side[1]/2):(-box->side[1]/2),
00076                    (dir[2]>0)?(box->side[2]/2):(-box->side[2]/2));
00077     }
00078     break;
00079   case GEOM_SPHERE:
00080     {
00081       const Sphere* sphere = static_cast<const Sphere*>(shape);
00082       return dir * sphere->radius;
00083     }
00084     break;
00085   case GEOM_CAPSULE:
00086     {
00087       const Capsule* capsule = static_cast<const Capsule*>(shape);
00088       FCL_REAL half_h = capsule->lz * 0.5;
00089       Vec3f pos1(0, 0, half_h);
00090       Vec3f pos2(0, 0, -half_h);
00091       Vec3f v = dir * capsule->radius;
00092       pos1 += v;
00093       pos2 += v;
00094       if(dir.dot(pos1) > dir.dot(pos2))
00095         return pos1;
00096       else return pos2;
00097     }
00098     break;
00099   case GEOM_CONE:
00100     {
00101       const Cone* cone = static_cast<const Cone*>(shape);
00102       FCL_REAL zdist = dir[0] * dir[0] + dir[1] * dir[1];
00103       FCL_REAL len = zdist + dir[2] * dir[2];
00104       zdist = std::sqrt(zdist);
00105       len = std::sqrt(len);
00106       FCL_REAL half_h = cone->lz * 0.5;
00107       FCL_REAL radius = cone->radius;
00108 
00109       FCL_REAL sin_a = radius / std::sqrt(radius * radius + 4 * half_h * half_h);
00110 
00111       if(dir[2] > len * sin_a)
00112         return Vec3f(0, 0, half_h);
00113       else if(zdist > 0)
00114       {
00115         FCL_REAL rad = radius / zdist;
00116         return Vec3f(rad * dir[0], rad * dir[1], -half_h);
00117       }
00118       else
00119         return Vec3f(0, 0, -half_h);
00120     }
00121     break;
00122   case GEOM_CYLINDER:
00123     {
00124       const Cylinder* cylinder = static_cast<const Cylinder*>(shape);
00125       FCL_REAL zdist = std::sqrt(dir[0] * dir[0] + dir[1] * dir[1]);
00126       FCL_REAL half_h = cylinder->lz * 0.5;
00127       if(zdist == 0.0)
00128       {
00129         return Vec3f(0, 0, (dir[2]>0)? half_h:-half_h);
00130       }
00131       else
00132       {
00133         FCL_REAL d = cylinder->radius / zdist;
00134         return Vec3f(d * dir[0], d * dir[1], (dir[2]>0)?half_h:-half_h);
00135       }
00136     }
00137     break;
00138   case GEOM_CONVEX:
00139     {
00140       const Convex* convex = static_cast<const Convex*>(shape);
00141       FCL_REAL maxdot = - std::numeric_limits<FCL_REAL>::max();
00142       Vec3f* curp = convex->points;
00143       Vec3f bestv;
00144       for(size_t i = 0; i < convex->num_points; ++i, curp+=1)
00145       {
00146         FCL_REAL dot = dir.dot(*curp);
00147         if(dot > maxdot)
00148         {
00149           bestv = *curp;
00150           maxdot = dot;
00151         }
00152       }
00153       return bestv;
00154     }
00155     break;
00156   case GEOM_PLANE:
00157     {
00158       return Vec3f(0, 0, 0);
00159     }
00160     break;
00161   }
00162 
00163   return Vec3f(0, 0, 0);
00164 }
00165 
00166 
00167 FCL_REAL projectOrigin(const Vec3f& a, const Vec3f& b, FCL_REAL* w, size_t& m)
00168 {
00169   const Vec3f d = b - a;
00170   const FCL_REAL l = d.sqrLength();
00171   if(l > 0)
00172   {
00173     const FCL_REAL t(l > 0 ? - a.dot(d) / l : 0);
00174     if(t >= 1) { w[0] = 0; w[1] = 1; m = 2; return b.sqrLength(); } // m = 0x10 
00175     else if(t <= 0) { w[0] = 1; w[1] = 0; m = 1; return a.sqrLength(); } // m = 0x01
00176     else { w[0] = 1 - (w[1] = t); m = 3; return (a + d * t).sqrLength(); } // m = 0x11
00177   }
00178 
00179   return -1;
00180 }
00181 
00182 FCL_REAL projectOrigin(const Vec3f& a, const Vec3f& b, const Vec3f& c, FCL_REAL* w, size_t& m)
00183 {
00184   static const size_t nexti[3] = {1, 2, 0};
00185   const Vec3f* vt[] = {&a, &b, &c};
00186   const Vec3f dl[] = {a - b, b - c, c - a};
00187   const Vec3f& n = dl[0].cross(dl[1]);
00188   const FCL_REAL l = n.sqrLength();
00189 
00190   if(l > 0)
00191   {
00192     FCL_REAL mindist = -1;
00193     FCL_REAL subw[2] = {0, 0};
00194     size_t subm = 0;
00195     for(size_t i = 0; i < 3; ++i)
00196     {
00197       if(vt[i]->dot(dl[i].cross(n)) > 0) // origin is to the outside part of the triangle edge, then the optimal can only be on the edge
00198       {
00199         size_t j = nexti[i];
00200         FCL_REAL subd = projectOrigin(*vt[i], *vt[j], subw, subm);
00201         if(mindist < 0 || subd < mindist)
00202         {
00203           mindist = subd;
00204           m = static_cast<size_t>(((subm&1)?1<<i:0) + ((subm&2)?1<<j:0));
00205           w[i] = subw[0];
00206           w[j] = subw[1];
00207           w[nexti[j]] = 0;
00208         }
00209       }
00210     }
00211     
00212     if(mindist < 0) // the origin project is within the triangle
00213     {
00214       FCL_REAL d = a.dot(n);
00215       FCL_REAL s = sqrt(l);
00216       Vec3f p = n * (d / l);
00217       mindist = p.sqrLength();
00218       m = 7; // m = 0x111
00219       w[0] = dl[1].cross(b-p).length() / s;
00220       w[1] = dl[2].cross(c-p).length() / s;
00221       w[2] = 1 - (w[0] + w[1]);
00222     }
00223 
00224     return mindist;
00225   }
00226   return -1;
00227 }
00228 
00229 FCL_REAL projectOrigin(const Vec3f& a, const Vec3f& b, const Vec3f& c, const Vec3f& d, FCL_REAL* w, size_t& m)
00230 {
00231   static const size_t nexti[] = {1, 2, 0};
00232   const Vec3f* vt[] = {&a, &b, &c, &d};
00233   const Vec3f dl[3] = {a-d, b-d, c-d};
00234   FCL_REAL vl = triple(dl[0], dl[1], dl[2]); 
00235   bool ng = (vl * a.dot((b-c).cross(a-b))) <= 0;
00236   if(ng && std::abs(vl) > 0) // abs(vl) == 0, the tetrahedron is degenerated; if ng is false, then the last vertex in the tetrahedron does not grow toward the origin (in fact origin is on the other side of the abc face)
00237   {
00238     FCL_REAL mindist = -1;
00239     FCL_REAL subw[3] = {0, 0, 0};
00240     size_t subm = 0;
00241     for(size_t i = 0; i < 3; ++i)
00242     {
00243       size_t j = nexti[i];
00244       FCL_REAL s = vl * d.dot(dl[i].cross(dl[j]));
00245       if(s > 0) // the origin is to the outside part of a triangle face, then the optimal can only be on the triangle face
00246       {
00247         FCL_REAL subd = projectOrigin(*vt[i], *vt[j], d, subw, subm);
00248         if(mindist < 0 || subd < mindist)
00249         {
00250           mindist = subd;
00251           m = static_cast<size_t>( (subm&1?1<<i:0) + (subm&2?1<<j:0) + (subm&4?8:0) );
00252           w[i] = subw[0];
00253           w[j] = subw[1];
00254           w[nexti[j]] = 0;
00255           w[3] = subw[2];
00256         }
00257       }
00258     }
00259 
00260     if(mindist < 0)
00261     {
00262       mindist = 0;
00263       m = 15;
00264       w[0] = triple(c, b, d) / vl;
00265       w[1] = triple(a, c, d) / vl;
00266       w[2] = triple(b, a, d) / vl;
00267       w[3] = 1 - (w[0] + w[1] + w[2]);
00268     }
00269     
00270     return mindist;
00271   }
00272   return -1;
00273 }
00274 
00275 
00276 void GJK::initialize()
00277 {
00278   ray = Vec3f();
00279   nfree = 0;
00280   status = Failed;
00281   current = 0;
00282   distance = 0.0;
00283 }
00284 
00285 GJK::Status GJK::evaluate(const MinkowskiDiff& shape_, const Vec3f& guess)
00286 {
00287   size_t iterations = 0;
00288   FCL_REAL sqdist = 0;
00289   FCL_REAL alpha = 0;
00290   Vec3f lastw[4];
00291   size_t clastw = 0;
00292     
00293   free_v[0] = &store_v[0];
00294   free_v[1] = &store_v[1];
00295   free_v[2] = &store_v[2];
00296   free_v[3] = &store_v[3];
00297     
00298   nfree = 4;
00299   current = 0;
00300   status = Valid;
00301   shape = shape_;
00302   distance = 0.0;
00303   simplices[0].rank = 0;
00304   ray = guess;
00305     
00306   FCL_REAL sqrl = ray.sqrLength();
00307   appendVertex(simplices[0], (sqrl>0) ? -ray : Vec3f(1, 0, 0));
00308   simplices[0].p[0] = 1;
00309   ray = simplices[0].c[0]->w;
00310   sqdist = sqrl;
00311   lastw[0] = lastw[1] = lastw[2] = lastw[3] = ray;
00312 
00313   do
00314   {
00315     size_t next = 1 - current;
00316     Simplex& curr_simplex = simplices[current];
00317     Simplex& next_simplex = simplices[next];
00318       
00319     FCL_REAL rl = ray.sqrLength();
00320     if(rl < tolerance) // means origin is near the face of original simplex, return touch
00321     {
00322       status = Inside;
00323       break;
00324     }
00325 
00326     appendVertex(curr_simplex, -ray); // see below, ray points away from origin
00327       
00328     Vec3f& w = curr_simplex.c[curr_simplex.rank - 1]->w;
00329     bool found = false;
00330     for(size_t i = 0; i < 4; ++i)
00331     {
00332       if((w - lastw[i]).sqrLength() < tolerance)
00333       {
00334         found = true; break;
00335       }
00336     }
00337 
00338     if(found)
00339     {
00340       removeVertex(simplices[current]);
00341       break; 
00342     }
00343     else
00344     {
00345       lastw[clastw = (clastw+1)&3] = w;
00346     }
00347 
00348     // check for termination, from bullet
00349     FCL_REAL omega = ray.dot(w) / rl;
00350     alpha = std::max(alpha, omega);
00351     if((rl - alpha) - tolerance * rl <= 0)
00352     {
00353       removeVertex(simplices[current]);
00354       break;
00355     }
00356 
00357     // reduce simplex and decide the extend direction
00358     FCL_REAL weights[4];
00359     size_t mask = 0; // decide the simplex vertices that compose the minimal distance
00360     switch(curr_simplex.rank)
00361     {
00362     case 2:
00363       sqdist = projectOrigin(curr_simplex.c[0]->w, curr_simplex.c[1]->w, weights, mask); break;
00364     case 3:
00365       sqdist = projectOrigin(curr_simplex.c[0]->w, curr_simplex.c[1]->w, curr_simplex.c[2]->w, weights, mask); break;
00366     case 4:
00367       sqdist = projectOrigin(curr_simplex.c[0]->w, curr_simplex.c[1]->w, curr_simplex.c[2]->w, curr_simplex.c[3]->w, weights, mask); break;
00368     }
00369       
00370     if(sqdist >= 0)
00371     {
00372       next_simplex.rank = 0;
00373       ray = Vec3f();
00374       current = next;
00375       for(size_t i = 0; i < curr_simplex.rank; ++i)
00376       {
00377         if(mask & (1 << i))
00378         {
00379           next_simplex.c[next_simplex.rank] = curr_simplex.c[i];
00380           next_simplex.p[next_simplex.rank++] = weights[i];
00381           ray += curr_simplex.c[i]->w * weights[i];
00382         }
00383         else
00384           free_v[nfree++] = curr_simplex.c[i];
00385       }
00386       if(mask == 15) status = Inside; // the origin is within the 4-simplex, collision
00387     }
00388     else
00389     {
00390       removeVertex(simplices[current]);
00391       break;
00392     }
00393 
00394     status = ((++iterations) < max_iterations) ? status : Failed;
00395       
00396   } while(status == Valid);
00397 
00398   simplex = &simplices[current];
00399   switch(status)
00400   {
00401   case Valid: distance = ray.length(); break;
00402   case Inside: distance = 0; break;
00403   }
00404   return status;
00405 }
00406 
00407 void GJK::getSupport(const Vec3f& d, SimplexV& sv) const
00408 {
00409   sv.d = normalize(d);
00410   sv.w = shape.support(sv.d);
00411 }
00412 
00413 void GJK::removeVertex(Simplex& simplex)
00414 {
00415   free_v[nfree++] = simplex.c[--simplex.rank];
00416 }
00417 
00418 void GJK::appendVertex(Simplex& simplex, const Vec3f& v)
00419 {
00420   simplex.p[simplex.rank] = 0; // initial weight 0
00421   simplex.c[simplex.rank] = free_v[--nfree]; // set the memory
00422   getSupport(v, *simplex.c[simplex.rank++]);
00423 }
00424 
00425 bool GJK::encloseOrigin()
00426 {
00427   switch(simplex->rank)
00428   {
00429   case 1:
00430     {
00431       for(size_t i = 0; i < 3; ++i)
00432       {
00433         Vec3f axis;
00434         axis[i] = 1;
00435         appendVertex(*simplex, axis);
00436         if(encloseOrigin()) return true;
00437         removeVertex(*simplex);
00438         appendVertex(*simplex, -axis);
00439         if(encloseOrigin()) return true;
00440         removeVertex(*simplex);
00441       }
00442     }
00443     break;
00444   case 2:
00445     {
00446       Vec3f d = simplex->c[1]->w - simplex->c[0]->w;
00447       for(size_t i = 0; i < 3; ++i)
00448       {
00449         Vec3f axis;
00450         axis[i] = 1;
00451         Vec3f p = d.cross(axis);
00452         if(p.sqrLength() > 0)
00453         {
00454           appendVertex(*simplex, p);
00455           if(encloseOrigin()) return true;
00456           removeVertex(*simplex);
00457           appendVertex(*simplex, -p);
00458           if(encloseOrigin()) return true;
00459           removeVertex(*simplex);
00460         }
00461       }
00462     }
00463     break;
00464   case 3:
00465     {
00466       Vec3f n = (simplex->c[1]->w - simplex->c[0]->w).cross(simplex->c[2]->w - simplex->c[0]->w);
00467       if(n.sqrLength() > 0)
00468       {
00469         appendVertex(*simplex, n);
00470         if(encloseOrigin()) return true;
00471         removeVertex(*simplex);
00472         appendVertex(*simplex, -n);
00473         if(encloseOrigin()) return true;
00474         removeVertex(*simplex);
00475       }
00476     }
00477     break;
00478   case 4:
00479     {
00480       if(std::abs(triple(simplex->c[0]->w - simplex->c[3]->w, simplex->c[1]->w - simplex->c[3]->w, simplex->c[2]->w - simplex->c[3]->w)) > 0)
00481         return true;
00482     }
00483     break;
00484   }
00485 
00486   return false;
00487 }
00488 
00489 
00490 void EPA::initialize()
00491 {
00492   sv_store = new SimplexV[max_vertex_num];
00493   fc_store = new SimplexF[max_face_num];
00494   status = Failed;
00495   normal = Vec3f(0, 0, 0);
00496   depth = 0;
00497   nextsv = 0;
00498   for(size_t i = 0; i < max_face_num; ++i)
00499     stock.append(&fc_store[max_face_num-i-1]);
00500 }
00501 
00502 bool EPA::getEdgeDist(SimplexF* face, SimplexV* a, SimplexV* b, FCL_REAL& dist)
00503 {
00504   Vec3f ba = b->w - a->w;
00505   Vec3f n_ab = ba.cross(face->n);
00506   FCL_REAL a_dot_nab = a->w.dot(n_ab);
00507 
00508   if(a_dot_nab < 0) // the origin is on the outside part of ab
00509   {
00510     FCL_REAL ba_l2 = ba.sqrLength();
00511 
00512     // following is similar to projectOrigin for two points
00513     // however, as we dont need to compute the parameterization, dont need to compute 0 or 1
00514     FCL_REAL a_dot_ba = a->w.dot(ba); 
00515     FCL_REAL b_dot_ba = b->w.dot(ba);
00516 
00517     if(a_dot_ba > 0) 
00518       dist = a->w.length();
00519     else if(b_dot_ba < 0)
00520       dist = b->w.length();
00521     else
00522     {
00523       FCL_REAL a_dot_b = a->w.dot(b->w);
00524       dist = std::sqrt(std::max(a->w.sqrLength() * b->w.sqrLength() - a_dot_b * a_dot_b, (FCL_REAL)0));
00525     }
00526 
00527     return true;
00528   }
00529 
00530   return false;
00531 }
00532 
00533 EPA::SimplexF* EPA::newFace(SimplexV* a, SimplexV* b, SimplexV* c, bool forced)
00534 {
00535   if(stock.root)
00536   {
00537     SimplexF* face = stock.root;
00538     stock.remove(face);
00539     hull.append(face);
00540     face->pass = 0;
00541     face->c[0] = a;
00542     face->c[1] = b;
00543     face->c[2] = c;
00544     face->n = (b->w - a->w).cross(c->w - a->w);
00545     FCL_REAL l = face->n.length();
00546       
00547     if(l > tolerance)
00548     {
00549       if(!(getEdgeDist(face, a, b, face->d) ||
00550            getEdgeDist(face, b, c, face->d) ||
00551            getEdgeDist(face, c, a, face->d)))
00552       {
00553         face->d = a->w.dot(face->n) / l;
00554       }
00555 
00556       face->n /= l;
00557       if(forced || face->d >= -tolerance)
00558         return face;
00559       else
00560         status = NonConvex;
00561     }
00562     else
00563       status = Degenerated;
00564 
00565     hull.remove(face);
00566     stock.append(face);
00567     return NULL;
00568   }
00569     
00570   status = stock.root ? OutOfVertices : OutOfFaces;
00571   return NULL;
00572 }
00573 
00575 EPA::SimplexF* EPA::findBest()
00576 {
00577   SimplexF* minf = hull.root;
00578   FCL_REAL mind = minf->d * minf->d;
00579   for(SimplexF* f = minf->l[1]; f; f = f->l[1])
00580   {
00581     FCL_REAL sqd = f->d * f->d;
00582     if(sqd < mind)
00583     {
00584       minf = f;
00585       mind = sqd;
00586     }
00587   }
00588   return minf;
00589 }
00590 
00591 EPA::Status EPA::evaluate(GJK& gjk, const Vec3f& guess)
00592 {
00593   GJK::Simplex& simplex = *gjk.getSimplex();
00594   if((simplex.rank > 1) && gjk.encloseOrigin())
00595   {
00596     while(hull.root)
00597     {
00598       SimplexF* f = hull.root;
00599       hull.remove(f);
00600       stock.append(f);
00601     }
00602 
00603     status = Valid;
00604     nextsv = 0;
00605 
00606     if((simplex.c[0]->w - simplex.c[3]->w).dot((simplex.c[1]->w - simplex.c[3]->w).cross(simplex.c[2]->w - simplex.c[3]->w)) < 0)
00607     {
00608       SimplexV* tmp = simplex.c[0];
00609       simplex.c[0] = simplex.c[1];
00610       simplex.c[1] = tmp;
00611 
00612       FCL_REAL tmpv = simplex.p[0];
00613       simplex.p[0] = simplex.p[1];
00614       simplex.p[1] = tmpv;
00615     }
00616 
00617     SimplexF* tetrahedron[] = {newFace(simplex.c[0], simplex.c[1], simplex.c[2], true),
00618                                newFace(simplex.c[1], simplex.c[0], simplex.c[3], true),
00619                                newFace(simplex.c[2], simplex.c[1], simplex.c[3], true),
00620                                newFace(simplex.c[0], simplex.c[2], simplex.c[3], true) };
00621 
00622     if(hull.count == 4)
00623     {
00624       SimplexF* best = findBest(); // find the best face (the face with the minimum distance to origin) to split
00625       SimplexF outer = *best;
00626       size_t pass = 0;
00627       size_t iterations = 0;
00628         
00629       // set the face connectivity
00630       bind(tetrahedron[0], 0, tetrahedron[1], 0);
00631       bind(tetrahedron[0], 1, tetrahedron[2], 0);
00632       bind(tetrahedron[0], 2, tetrahedron[3], 0);
00633       bind(tetrahedron[1], 1, tetrahedron[3], 2);
00634       bind(tetrahedron[1], 2, tetrahedron[2], 1);
00635       bind(tetrahedron[2], 2, tetrahedron[3], 1);
00636 
00637       status = Valid;
00638       for(; iterations < max_iterations; ++iterations)
00639       {
00640         if(nextsv < max_vertex_num)
00641         {
00642           SimplexHorizon horizon;
00643           SimplexV* w = &sv_store[nextsv++];
00644           bool valid = true;
00645           best->pass = ++pass;
00646           gjk.getSupport(best->n, *w);
00647           FCL_REAL wdist = best->n.dot(w->w) - best->d;
00648           if(wdist > tolerance)
00649           {
00650             for(size_t j = 0; (j < 3) && valid; ++j)
00651             {
00652               valid &= expand(pass, w, best->f[j], best->e[j], horizon);
00653             }
00654 
00655               
00656             if(valid && horizon.nf >= 3)
00657             {
00658               // need to add the edge connectivity between first and last faces
00659               bind(horizon.ff, 2, horizon.cf, 1);
00660               hull.remove(best);
00661               stock.append(best);
00662               best = findBest();
00663               outer = *best;
00664             }
00665             else
00666             {
00667               status = InvalidHull; break;
00668             }
00669           }
00670           else
00671           {
00672             status = AccuracyReached; break;
00673           }
00674         }
00675         else
00676         {
00677           status = OutOfVertices; break;
00678         }
00679       }
00680 
00681       Vec3f projection = outer.n * outer.d;
00682       normal = outer.n;
00683       depth = outer.d;
00684       result.rank = 3;
00685       result.c[0] = outer.c[0];
00686       result.c[1] = outer.c[1];
00687       result.c[2] = outer.c[2];
00688       result.p[0] = ((outer.c[1]->w - projection).cross(outer.c[2]->w - projection)).length();
00689       result.p[1] = ((outer.c[2]->w - projection).cross(outer.c[0]->w - projection)).length();
00690       result.p[2] = ((outer.c[0]->w - projection).cross(outer.c[1]->w - projection)).length();
00691 
00692       FCL_REAL sum = result.p[0] + result.p[1] + result.p[2];
00693       result.p[0] /= sum;
00694       result.p[1] /= sum;
00695       result.p[2] /= sum;
00696       return status;
00697     }
00698   }
00699 
00700   status = FallBack;
00701   normal = -guess;
00702   FCL_REAL nl = normal.length();
00703   if(nl > 0) normal /= nl;
00704   else normal = Vec3f(1, 0, 0);
00705   depth = 0;
00706   result.rank = 1;
00707   result.c[0] = simplex.c[0];
00708   result.p[0] = 1;
00709   return status;
00710 }
00711 
00712 
00714 bool EPA::expand(size_t pass, SimplexV* w, SimplexF* f, size_t e, SimplexHorizon& horizon)
00715 {
00716   static const size_t nexti[] = {1, 2, 0};
00717   static const size_t previ[] = {2, 0, 1};
00718 
00719   if(f->pass != pass)
00720   {
00721     const size_t e1 = nexti[e];
00722       
00723     // case 1: the new face is not degenerated, i.e., the new face is not coplanar with the old face f.
00724     if(f->n.dot(w->w) - f->d < -tolerance)
00725     {
00726       SimplexF* nf = newFace(f->c[e1], f->c[e], w, false);
00727       if(nf)
00728       {
00729         // add face-face connectivity
00730         bind(nf, 0, f, e);
00731           
00732         // if there is last face in the horizon, then need to add another connectivity, i.e. the edge connecting the current new add edge and the last new add edge. 
00733         // This does not finish all the connectivities because the final face need to connect with the first face, this will be handled in the evaluate function.
00734         // Notice the face is anti-clockwise, so the edges are 0 (bottom), 1 (right), 2 (left)
00735         if(horizon.cf)  
00736           bind(nf, 2, horizon.cf, 1);
00737         else
00738           horizon.ff = nf; 
00739           
00740         horizon.cf = nf;
00741         ++horizon.nf;
00742         return true;
00743       }
00744     }
00745     else // case 2: the new face is coplanar with the old face f. We need to add two faces and delete the old face
00746     {
00747       const size_t e2 = previ[e];
00748       f->pass = pass;
00749       if(expand(pass, w, f->f[e1], f->e[e1], horizon) && expand(pass, w, f->f[e2], f->e[e2], horizon))
00750       {
00751         hull.remove(f);
00752         stock.append(f);
00753         return true;
00754       }
00755     }
00756   }
00757 
00758   return false;
00759 }
00760 
00761 } // details
00762 
00763 } // fcl