pivot.h
Go to the documentation of this file.
00001 #ifndef VCG_PIVOT_H
00002 #define VCG_PIVOT_H
00003 
00004 #include <vector>
00005 #include <list>
00006 
00007 
00008 #include "vcg/space/index/grid_static_ptr.h"
00009 #include "vcg/complex/algorithms/closest.h"
00010 
00011 namespace vcg {
00012 namespace tri {
00013 
00014 
00015 struct Hinge { 
00016       int v0, v1, v2;   //v0, v1 represent the Hinge, v2 the other vertex in the face
00017                         //this Hinge belongs to
00018       int face;        //corresponding face
00019       Point3f center;  //center of the sphere touching the face
00020       int count;   //test delay touch Hinges.  
00021       
00022       //the loops in the front are mantained as a double linked list
00023       std::list<Hinge>::iterator next;            
00024       std::list<Hinge>::iterator previous;
00025     
00026       Hinge() {}
00027       Hinge(int _v0, int _v1, int _v2, int _face, Point3f &_center): 
00028                v0(_v0), v1(_v1), v2(_v2), 
00029                face(_face), center(_center), count(0) {
00030                  assert(v0 != v1 && v1 != v2 && v0 != v2);
00031                }
00032     };
00033     
00034 template <class MESH>
00035 class Pivot {
00036   public:
00037 //    typedef CMesh MESH;
00038     typedef GridStaticPtr<typename MESH::VertexType, typename MESH::ScalarType > StaticGrid;
00039     
00040     
00041 
00042     float radius;  //default 1 (not meaningful
00043     float mindist; //minimum distance between points in the mesh (% of radius)   
00044     float crease;  // -0.5 
00045     Box3f box;
00046     
00047     MESH &mesh;    
00048     StaticGrid grid;
00049     
00050     /* front Hinges of the mesh: 
00051        to expand the front we get the first Hinge
00052        if an Hinge cannot create a new triangle it is marked dead and moved
00053        to the end of the list
00054        the new Hinges are inserted to the back (before dead_begin) */
00055        
00056     std::list<Hinge> front;   
00057     std::list<Hinge> deads;
00058     std::vector<int> nb; //number of fronts a vertex is into,
00059                          //this is used for the Visited and Border flags
00060                          //but adding topology may not be needed anymode
00061 
00062       
00063     Pivot(MESH &_mesh, float _radius, float _mindist = 0.05, float _crease = -0.5): 
00064        mesh(_mesh), radius(_radius), mindist(_mindist), crease(_crease) {
00065     
00066       //Compute bounding box. (this may be passed as a parameter?
00067       for(int i = 0; i < mesh.vert.size(); i++)
00068         box.Add(mesh.vert[i].P());
00069      
00070       /* we need to enlarge the grid to allow queries from little outside of the box 
00071          Someone is a bit lazy... */        
00072       box.Offset(4*radius);
00073       grid.Set(mesh.vert.begin(), mesh.vert.end(), box);
00074       nb.clear();
00075       nb.resize(mesh.vert.size(), 0);
00076       for(int i = 0; i < mesh.vert.size(); i++) 
00077          mesh.vert[i].ClearFlags();
00078       
00079     }
00080     
00081     
00082     /* select a vertex at random, a small group of nearby vertices and looks
00083        for a sphere that touches 3 and contains none.
00084        Use the center of the box to get a sphere inside (or outside) the model 
00085        You may be unlucky... */
00086        
00087     bool seed(bool outside = true, int start = -1) {         
00088       //pick a random point (well...)
00089       if(start == -1) start = rand()%mesh.vert.size();
00090       
00091       //get a sphere of neighbours
00092       std::vector<int> targets;
00093       std::vector<float> dists;
00094       int n = getInSphere(mesh.vert[start].P(), 2*radius, targets, dists);
00095       if(n < 3) { 
00096         //bad luck. we should call seed again (assuming random pick) up to
00097         //some maximum tries. im lazy.
00098         return false;
00099       }
00100       int v0, v1, v2;
00101       bool found = false;
00102       //find a triplet that does not contains any other point
00103       Point3f center;
00104       for(int i = 0; i < n; i++) {
00105         v0 = targets[i];
00106         CVertex &vv0 = mesh.vert[v0];
00107         if(vv0.IsD() || vv0.IsB() || vv0.IsV()) continue;
00108         Point3f &p0 = mesh.vert[v0].P();
00109         Point3f out = (p0 - box.Center());
00110         if(!outside) out = -out;
00111     
00112         for(int k = i+1; k < n; k++) {
00113           v1 = targets[k];            
00114           CVertex &vv1 = mesh.vert[v1];
00115           if(vv1.IsD() || vv1.IsB() || vv1.IsV()) continue;
00116           Point3f &p1 = mesh.vert[v1].P();            
00117           if((p1 - p0).Norm() < mindist*radius) continue;
00118     
00119           for(int j = k+1; j < n; j++) {
00120             v2 = targets[j];
00121             CVertex &vv2 = mesh.vert[v2];
00122             if(vv2.IsD() || vv2.IsB() || vv2.IsV()) continue;
00123             Point3f &p2 = mesh.vert[v2].P();
00124             if((p2 - p0).Norm() < mindist*radius) continue;
00125             if((p2 - p1).Norm() < mindist*radius) continue;
00126             Point3f normal = (p1 - p0)^(p2 - p0);
00127             //check normal pointing inside
00128             if(normal * out < 0) continue;
00129             if(!findSphere(p0, p1, p2, center)) continue;
00130             
00131             bool failed = false;
00132             //check no other point inside
00133             for(int t = 0; t < n; t++) {
00134               Point3f &p = mesh.vert[targets[t]].P();
00135               if((center - p).Norm() <= radius) {
00136                 failed = true;
00137                 break;
00138               }
00139             }
00140             if(failed) continue;  
00141             found = true;
00142             i = k = j = n;
00143           }
00144         }
00145       }
00146       
00147       if(!found)  //see bad luck above
00148         return false;
00149       
00150       assert(!front.size());
00151       //TODO: should i check the Hinges too?
00152       addFace(v0, v1, v2);
00153       
00154       //create the border of the first face  
00155       std::list<Hinge>::iterator e = front.end();
00156       std::list<Hinge>::iterator last;
00157       for(int i = 0; i < 3; i++) {
00158         int v0 = (int)(mesh.face.back().V0(i));
00159         int v1 = (int)(mesh.face.back().V1(i));    
00160         int v2 = (int)(mesh.face.back().V2(i));    
00161         nb[v0] = 1;
00162         assert(!mesh.vert[v0].IsB());
00163         mesh.vert[v0].SetB();
00164         Hinge Hinge(v0, v1, v2, 0, center);
00165         Hinge.previous = e;
00166         e = front.insert(front.begin(), Hinge);
00167         if(i == 0) last = e;
00168         (*Hinge.previous).next = e;
00169         
00170         cluster(v0);
00171       } 
00172     
00173       //connect last and first
00174       (*e).next = last;
00175       (*last).previous = e;
00176       return true;
00177     }
00178       
00179          
00180     /* expand the front adding 1 face. Return false on failure (id when
00181        all Hinges are dead  returns:
00182        1: added a face
00183        0: added nothing
00184        -1: finished */
00185     int addFace() {
00186       //We try to seed again
00187       if(!mesh.face.size()) {
00188         for(int i = 0; i < 100; i++) 
00189           if(seed()) return 1;
00190         return -1;
00191       }
00192       
00193       if(!front.size()) {
00194         //maybe there are unconnected parts of the mesh:
00195         //find a non D, V, B point and try to seed if failed D it.
00196         for(int i = 0; i < mesh.vert.size();i ++) {
00197           CVertex &v = mesh.vert[i];
00198           if(v.IsD() || v.IsV() || v.IsB()) continue;
00199           if(seed(true, i)) return 1;
00200           v.SetD();
00201         }
00202         return -1;
00203       }
00204     
00205       std::list<Hinge>::iterator ei = front.begin();
00206       Hinge &e = *ei;
00207       Hinge &previous = *e.previous;           
00208       Hinge &next = *e.next;  
00209       int v0 = e.v0, v1 = e.v1;
00210     
00211       //last triangle missing. or it is the first?
00212       if(0 &&next.next == e.previous) {  
00213     
00214         int v[3] = { previous.v0, next.v0, e.v0 };
00215         int c[3] = { 0, 0, 0 };
00216             
00217         for(int k = 0; k < 3; k++) {
00218           int vert = v[k];
00219           nb[vert]--;
00220           if(nb[vert] == 0) {       
00221             mesh.vert[vert].SetV();
00222             mesh.vert[vert].ClearB();
00223           }              
00224         }        
00225         assert(previous.previous == e.next); 
00226         addFace(previous.v0, next.v0, e.v0);                       
00227     
00228         front.erase(e.previous);
00229         front.erase(e.next);        
00230         front.erase(ei);    
00231         
00232         return 1;
00233       }
00234     
00235       int v2;
00236       Point3f center;
00237     
00238       std::vector<int> targets;
00239       bool success = pivot(e, v2, center, targets);
00240     
00241       //if no pivoting move this thing to the end and try again
00242       //or we are trying to connect to the inside of the mesh. BAD.
00243       if(!success || mesh.vert[v2].IsV()) {
00244         killHinge(ei);
00245         return 0;
00246       } 
00247     
00248       //does v2 belongs to a front? (and which?)
00249       std::list<Hinge>::iterator touch = touches(v2, ei);
00250     
00251       assert(v2 != v0 && v2 != v1);  
00252     
00253       int fn = mesh.face.size();
00254       if(touch != front.end()) {       
00255     
00256         if(!checkHinge(v0, v2) || !checkHinge(v2, v1)) {                      
00257           killHinge(ei);
00258           return 0;
00259         }
00260         
00261         if(v2 == previous.v0) {    
00262           /*touching previous Hinge  (we reuse previous)        
00263                                     next
00264              ------->v2 -----> v1------>
00265                       \       /
00266                        \     /
00267                previous \   / e
00268                          \ /
00269                           v0           */
00270           
00271           detach(v0);
00272         
00273           previous.v1 = v1;       
00274           previous.v2 = v0;
00275           previous.face = fn;
00276           previous.center = center;
00277           
00278           previous.next = e.next;
00279           next.previous = e.previous;
00280           moveBack(e.previous);            
00281           
00282           //this checks if we can glue something to e.previous
00283           trovamiunnome(e.previous);      
00284           front.erase(ei);    
00285           
00286            
00287         } else if(v2 == next.v1) {
00288         /*touching previous Hinge  (we reuse next)        
00289           previous
00290              ------->v0 -----> v2------>
00291                       \       /
00292                        \     /
00293                         \   / next
00294                          \ /
00295                           v1           */      
00296     
00297           detach(v1);
00298           
00299           next.v0 = v0;
00300           next.v2 = v1;
00301           next.face = fn;
00302           next.center = center;
00303           next.previous = e.previous;
00304           previous.next = e.next;
00305     //      moveBack(e.next);
00306           
00307           //this checks if we can glue something to e.previous
00308           trovamiunnome(e.next);         
00309           front.erase(ei);
00310               
00311         } else {
00312     
00313     /*   this code would delay the joining Hinge to avoid bad situations not used but..
00314          if(e.count < 2) {
00315             e.count++;
00316             moveBack(ei);
00317             return true;         
00318           }*/
00319     
00320         //touching some loop: split (or merge it is local does not matter.
00321         //like this 
00322         /*                 
00323                     left        right
00324                   <--------v2-<------
00325                           /|\
00326                          /   \
00327                      up /     \ down
00328                        /       \
00329                       /         V
00330                  ----v0 - - - > v1---------
00331                           e                         */           
00332           std::list<Hinge>::iterator left = touch;
00333           std::list<Hinge>::iterator right = (*touch).previous;      
00334           std::list<Hinge>::iterator up = ei;
00335           
00336           if(v1 == (*right).v0 || v0 == (*left).v1) {
00337 //            cout << "Bad join.\n";
00338             killHinge(ei);
00339             return 0;
00340           }
00341           
00342           nb[v2]++;    
00343                       
00344           std::list<Hinge>::iterator down = newHinge(Hinge(v2, v1, v0, fn, center));      
00345     
00346           (*right).next = down;
00347           (*down).previous = right;
00348     
00349           (*down).next = e.next;
00350           next.previous = down;      
00351     
00352           (*left).previous = up;
00353           (*up).next = left;
00354           
00355           (*up).v2 = v1;      
00356           (*up).v1 = v2;
00357           (*up).face = fn;
00358           (*up).center = center;
00359           moveBack(ei);
00360         }                         
00361     
00362               
00363       
00364       } else {
00365         assert(!mesh.vert[v2].IsB()); //fatal error! a new point is already a border?
00366     
00367         /*  adding a new vertex
00368                  
00369                            v2
00370                           /|\
00371                          /   \
00372                      up /     \ down
00373                        /       \
00374                       /         V
00375                  ----v0 - - - > v1--------- */
00376         cluster(v2);        
00377         nb[v2]++;                 
00378         mesh.vert[v2].SetB();
00379         std::list<Hinge>::iterator down = newHinge(Hinge(v2, v1, v0, fn, center));
00380         (*down).previous = ei;
00381         (*down).next = e.next;
00382         next.previous = down;
00383         
00384         e.v2 = v1;    
00385         e.v1 = v2;
00386         e.face = fn;
00387         e.center = center;
00388         e.next = down; 
00389         moveBack(ei);
00390       }
00391       addFace(v0, v2, v1);
00392       return 1;
00393     }        
00394     
00395 
00396     
00397     /* return new vertex and the center of the new sphere pivoting from Hinge
00398        if the vertex belongs to another Hinge, touch points to it. */
00399     bool pivot(Hinge &Hinge, int &candidate, Point3f &end_pivot, std::vector<int> &targets) {
00400         Point3f v0 = mesh.vert[Hinge.v0].P();
00401         Point3f v1 = mesh.vert[Hinge.v1].P();  
00402         Point3f v2 = mesh.vert[Hinge.v2].P();  
00403         /* TODO why using the face normals everything goes wrong? should be
00404            exactly the same................................................
00405            Check if the e.face is correct.
00406            Point3f &normal = mesh.face[Hinge.face].N();
00407         */
00408     
00409         Point3f normal = ((v1 - v0)^(v2 - v0)).Normalize();
00410         
00411         Point3f middle = (v0 + v1)/2;    
00412         Point3f start_pivot = Hinge.center - middle;          
00413         Point3f axis = (v1 - v0);
00414         
00415         float axis_len = axis.SquaredNorm();
00416         if(axis_len > 4*radius*radius) return false;
00417         axis.Normalize();
00418         
00419         // r is the radius of the thorus of all possible spheres passing throug v0 and v1
00420         float r = sqrt(radius*radius - axis_len/4);
00421         
00422     
00423         std::vector<float> dists;    
00424         getInSphere(middle, r + radius, targets, dists);
00425     
00426         if(targets.size() == 0) return false; //this really would be strange but one never knows.
00427     
00428         candidate = -1;
00429         float minangle = 0;
00430         Point3f center;  //to be computed for each sample
00431         for(int i = 0; i < targets.size(); i++) {      
00432           int id = targets[i];
00433           
00434           if(id == Hinge.v0 || id == Hinge.v1 || id == Hinge.v2) continue;
00435     
00436           if(mesh.vert[id].IsD()) {
00437             continue;      
00438           }
00439     
00440     
00441           Point3f p = mesh.vert[id].P();
00442     
00443           /* Prevent 360 Hinges, also often reject ~ 50% points */      
00444           Point3f n = ((p - v0)^(v1 - v0)).Normalize();
00445           if(n * normal < -0.5) {
00446             continue;               
00447           }
00448           
00449     
00450           /* Find the sphere through v0, p, v1 (store center on end_pivot */
00451           if(!findSphere(v0, p, v1, center)) {
00452             continue;      
00453           }
00454           
00455           /* Angle between old center and new center */
00456           float alpha = angle(start_pivot, center - middle, axis);
00457     
00458           /* adding a small bias to already chosen vertices.
00459              doesn't solve numerical problems, but helps. */
00460           if(mesh.vert[id].IsB()) alpha -= 0.001;
00461           
00462           /* Sometimes alpha might be little less then M_PI while it should be 0,
00463              by numerical errors: happens for example pivoting 
00464              on the diagonal of a square. */
00465           
00466           if(alpha > 2*M_PI - 0.8) {               
00467             // Angle between old center and new *point* 
00468             //TODO is this really overshooting? shouldbe enough to alpha -= 2*M_PI
00469             Point3f proj = p - axis * (axis * p - axis * middle);
00470             float beta = angle(start_pivot, proj - middle, axis);
00471           
00472             if(alpha > beta) alpha -= 2*M_PI; 
00473           }
00474           if(candidate == -1 || alpha < minangle) {        
00475             candidate = id; 
00476             minangle = alpha;
00477             end_pivot = center;
00478           }
00479         }
00480         //found no point suitable.
00481         if(candidate == -1) {
00482           return false;
00483         }
00484            
00485         assert(candidate != Hinge.v0 && candidate != Hinge.v1);
00486         return true;
00487     }         
00488     
00489   private:
00490      //front management:
00491      //Add a new Hinge to the back of the queue
00492      std::list<Hinge>::iterator newHinge(Hinge e) {                  
00493        return front.insert(front.end(), e);
00494      }     
00495      //move an Hinge among the dead ones
00496      void killHinge(std::list<Hinge>::iterator e) {
00497        deads.splice(deads.end(), front, e);
00498      }
00499 
00500      //move an Hinge to the back of the queue
00501      void moveBack(std::list<Hinge>::iterator e) {
00502        front.splice(front.end(), front, e);          
00503      }
00504      
00505      void moveFront(std::list<Hinge>::iterator e) {
00506        front.splice(front.begin(), front, e);
00507      }
00508     bool checkHinge(int v0, int v1) {
00509       int tot = 0;
00510       //HACK to speed up things until i can use a seach structure
00511       int i = mesh.face.size() - 2*(front.size());
00512     //  i = 0;
00513       if(i < 0) i = 0;
00514       for(; i < mesh.face.size(); i++) { 
00515         CFace &f = mesh.face[i];
00516         for(int k = 0; k < 3; k++) {
00517           if(v1== (int)f.V(k) && v0 == (int)f.V((k+1)%3)) ++tot;
00518           else if(v0 == (int)f.V(k) && v1 == (int)f.V((k+1)%3)) { //orientation non constistent
00519              return false;
00520           }
00521         }
00522         if(tot >= 2) { //non manifold
00523           return false;
00524         }
00525       }
00526       return true;
00527     }        
00528     
00529                
00530     void Pivot::cluster(int v) {
00531       /* clean up too close points */
00532         std::vector<int> targets;
00533         std::vector<float> dists;    
00534         getInSphere(mesh.vert[v].P(), mindist*radius, targets, dists);
00535         
00536         for(int i = 0; i < targets.size(); i++) {
00537           int id = targets[i];
00538           if(id == v) continue;
00539     
00540           CVertex &v = mesh.vert[id];
00541           if(v.IsD() || v.IsV() || v.IsB()) continue;
00542           v.SetD();
00543         }
00544             
00545     }
00546     
00547     void Pivot::trovamiunnome(std::list<Hinge>::iterator e) {
00548       if(glue((*e).previous, e)) return;
00549       glue(e, (*e).next);
00550     }
00551     
00552     //glue toghether a and b (where a.next = b
00553     bool Pivot::glue(std::list<Hinge>::iterator a, std::list<Hinge>::iterator b) {
00554       if((*a).v0 != (*b).v1) return false; 
00555       
00556       std::list<Hinge>::iterator previous = (*a).previous;
00557       std::list<Hinge>::iterator next = (*b).next;
00558       (*previous).next = next;
00559       (*next).previous = previous;
00560       detach((*a).v1);
00561       detach((*a).v0); 
00562       front.erase(a);
00563       front.erase(b);  
00564       return true;
00565     }
00566     
00567     void Pivot::detach(int v) {
00568       assert(nb[v] > 0);
00569       if(--nb[v] == 0) {
00570         mesh.vert[v].SetV();
00571         mesh.vert[v].ClearB();      
00572       }
00573     }
00574 
00575           
00576     /* compute angle from p to q, using axis for orientation */
00577     float angle(Point3f p, Point3f q, Point3f &axis) {
00578       p.Normalize();
00579       q.Normalize();
00580       Point3f vec = p^q;
00581       float angle = acos(p*q);
00582       if(vec*axis < 0) angle = -angle;
00583       if(angle < 0) angle += 2*M_PI;
00584       return angle;
00585     }          
00586     /* add a new face. compute normals. */
00587     void addFace(int a, int b, int c) {
00588       CFace face;
00589       face.V(0) = (CVertex *)a;
00590       face.V(1) = (CVertex *)b;
00591       face.V(2) = (CVertex *)c;
00592       Point3f &p0 = mesh.vert[a].P();
00593       Point3f &p1 = mesh.vert[b].P();
00594       Point3f &p2 = mesh.vert[c].P();
00595       face.N() = ((p1 - p0)^(p2 - p0)).Normalize();
00596       
00597       mesh.face.push_back(face);
00598       mesh.fn++;
00599     }         
00600               
00601                              
00602     /* intersects segment [v0, v1] with the sphere of radius radius. */
00603     bool intersect(int v0, int v1, Point3f &center) {
00604       Point3f m =  mesh.vert[v1].P() -  mesh.vert[v0].P();
00605       float t = m*(center - mesh.vert[v0].P());
00606       if(t < 0) return false;
00607       if(t > m*m) return false;
00608       return true;
00609     }         
00610 
00611 
00612     float distance(int v0, int v1, Point3f &center) {
00613       Point3f m =  mesh.vert[v1].P() -  mesh.vert[v0].P();
00614       float t = m*(center - mesh.vert[v0].P())/(m*m);
00615       Point3f p = mesh.vert[v0].P() + m*t;
00616       return (p - center).Norm();
00617     }             
00618 
00619 
00620     /* return all point in a given ball, notice as i want the index
00621        of the vertices not the pointers... this may change in future */
00622     unsigned int getInSphere(vcg::Point3f &p, float distance, 
00623                              std::vector<int> &results,
00624                              std::vector<float> &dists) {
00625       std::vector<CVertex *> ptr;
00626       std::vector<Point3f> points;
00627       int n = vcg::tri::GetInSphereVertex(mesh, grid, p, distance, ptr, dists, points);
00628       for(int i = 0; i < ptr.size(); i++) 
00629         results.push_back(ptr[i] - &(mesh.vert[0]));
00630       return n;
00631     }                                                
00632 
00633 
00634     
00635     /* returns the sphere touching p0, p1, p2 of radius r such that
00636        the normal of the face points toward the center of the sphere */
00637     bool findSphere(Point3f &p0, Point3f &p1, Point3f &p2, Point3f &center) {
00638       Point3f q1 = p1 - p0;
00639       Point3f q2 = p2 - p0;  
00640     
00641       Point3f up = q1^q2;
00642       float uplen = up.Norm();
00643     
00644       //the three points are aligned
00645       if(uplen < 0.001*q1.Norm()*q2.Norm()) return false;
00646       up /= uplen;
00647       
00648     
00649       float a11 = q1*q1;
00650       float a12 = q1*q2;
00651       float a22 = q2*q2;
00652     
00653       float m = 4*(a11*a22 - a12*a12);
00654       float l1 = 2*(a11*a22 - a22*a12)/m;
00655       float l2 = 2*(a11*a22 - a12*a11)/m;
00656     
00657       center = q1*l1 + q2*l2;
00658       float circle_r = center.Norm();
00659       if(circle_r > radius) return false; //need too big a sphere
00660     
00661       float height = sqrt(radius*radius - circle_r*circle_r);
00662       center += p0 + up*height;
00663     
00664       return true;
00665     }         
00666     std::list<Hinge>::iterator touches(int v, std::list<Hinge>::iterator e) {
00667       //TODO what happens when it touches more than one front?
00668       //might still work.
00669     
00670       std::list<Hinge>::iterator touch = front.end();
00671       if(mesh.vert[v].IsB()) {
00672         //test nearby Hinges: it is faster
00673         std::list<Hinge>::iterator p = e;
00674         p = (*e).previous;
00675         if(v == (*p).v0) return p;
00676         e = (*e).next;
00677         if(v == (*e).v0) return e;
00678     
00679         p = (*p).previous;
00680         if(v == (*p).v0) return p;
00681         e = (*e).next;
00682         if(v == (*e).v0) return e;
00683     
00684         //test all. sigh.
00685     
00686         for(std::list<Hinge>::iterator k = front.begin(); k != front.end(); k++) {
00687           if(v == (*k).v0) { 
00688             touch = k;
00689             break;
00690           }
00691         }
00692         for(std::list<Hinge>::iterator k = deads.begin(); k != deads.end(); k++) {
00693           if(v == (*k).v0) { 
00694             touch = k;
00695             break;
00696           }
00697         }
00698         assert(touch != front.end());
00699       }
00700     
00701       return touch;
00702     }                              
00703     
00704     
00705  public:
00706         
00707  };
00708         
00709 
00710 }//namespace
00711 }//namespace
00712 /*  CODE FOR PIVOTING IN  A TOUCH SITUATION not used now.
00713 
00714     //if touch we want to check the ball could really pivot around that point
00715     if(touch != front.end() && touch != (*Hinge.next).next && touch != Hinge.previous) {
00716       Point3f &hinge = mesh.vert[min].P();      
00717       Point3f target = (*touch).center - hinge;
00718       float d = (target * start_pivot)/(target.Norm()*start_pivot.Norm());
00719       if(d < -0.8) {
00720         return false;
00721       }
00722       
00723       
00724 
00725       if(d < 0.5) { //they are far enough so test .
00726         Point3f naxis = (target ^ start_pivot).Normalize();
00727         Point3f d1 = naxis^start_pivot;
00728         Point3f d2 = target^naxis;          
00729         
00730         for(int i = 0; i < targets.size(); i++) {
00731           int id = targets[i];
00732           if(id == Hinge.v0 || id == Hinge.v1 || id == Hinge.v2 || id == min) continue;
00733           if(mesh.vert[id].IsD()) {
00734             continue;
00735           }
00736 
00737           Point3f intruder = mesh.vert[targets[i]].P() - hinge;
00738           float h = intruder*naxis;
00739           if(fabs(h) > radius) continue;
00740           intruder -= naxis*h;
00741           assert(fabs(intruder *naxis) < 0.01);
00742           float off = radius - intruder.Norm(); //(distance from the center ring of the thorus
00743           if(h*h + off*off > radius*radius) continue; //outside of thorus
00744           if(d1*intruder < 0 || d2*intruder < 0) continue; //ouside of sector
00745           cout << "could not pivot while touching;\n";
00746           return false;
00747         }
00748         
00749       }          
00750     }*/
00751 
00752 
00753 #endif


shape_reconstruction
Author(s): Roberto Martín-Martín
autogenerated on Sat Jun 8 2019 18:34:10