cylinder_clipping.h
Go to the documentation of this file.
00001 /****************************************************************************
00002  * VCGLib                                                            o o     *
00003  * Visual and Computer Graphics Library                            o     o   *
00004  *                                                                _   O  _   *
00005  * Copyright(C) 2004                                                \/)\/    *
00006  * Visual Computing Lab                                            /\/|      *
00007  * ISTI - Italian National Research Council                           |      *
00008  *                                                                    \      *
00009  * All rights reserved.                                                      *
00010  *                                                                           *
00011  * This program is free software; you can redistribute it and/or modify      *
00012  * it under the terms of the GNU General Public License as published by      *
00013  * the Free Software Foundation; either version 2 of the License, or         *
00014  * (at your option) any later version.                                       *
00015  *                                                                           *
00016  * This program is distributed in the hope that it will be useful,           *
00017  * but WITHOUT ANY WARRANTY; without even the implied warranty of            *
00018  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the             *
00019  * GNU General Public License (http://www.gnu.org/licenses/gpl.txt)          *
00020  * for more details.                                                         *
00021  *                                                                           *
00022  ****************************************************************************/
00023 #ifndef CYLINDER_CLIP_H
00024 #define CYLINDER_CLIP_H
00025 #include <vcg/space/segment3.h>
00026 #include <vcg/complex/algorithms/refine.h>
00027 namespace vcg
00028 {
00029 
00030 // Taken a cylinder and a line calculates whether there is an intersection between these.
00031 // In output are provided, if they exist, any two points of intersection (p0, p1)
00032 // and the parameters t (t0, t1) on the line.
00033 // Returns false if the distance of the line from the axis of the cylinder is greater than
00034 // the radius of the cylinder or, if the calculation of t parameters - obtained by solving the
00035 // quadratic equation - gives a delta less than zero.
00036 // To find the intersection of a line p1+td1 with the axis p+td of the cylinder:
00037 // (p1-p+td1-<v,p1-p+td1>d)^2 -r^2=0, becomes At^2+Bt+C=0.
00038 //
00039 // tmpA = d1 - (<d1,d>/<d,d>)*d.
00040 // tmpB = (p1-p) - (<p1-p,d>/<d,d>)*d.
00041 // A = <tmpA,tmpA>.
00042 // B = 2*<tmpA,tmpB>.
00043 // C = <tmpB,tmpB> - r^2.
00044 // Input:  Cylinder<T> & cyl, Line3<T> & line.
00045 // Output: CoordType & p0,CoordType & p1, T & t0, T &t1.
00046 
00047 template<class T>
00048 static bool IntersectionLineCylinder(const Segment3<T> & cylSeg, T radius, const Line3<T> & line, Point3<T> & p0, Point3<T> & p1, T & t0, T &t1)
00049 {
00050       T dist;
00051       Point3<T> mClosestPoint0,mClosestPoint1;
00052       bool parallel=false;
00053 
00054       Line3<T> tmp;
00055       tmp.Set(cylSeg.P0(), (cylSeg.P1()-cylSeg.P0()).Normalize());
00056       LineLineDistance(tmp,line,parallel,dist,mClosestPoint0,mClosestPoint1);
00057       if(dist>radius)
00058           return false;
00059       if(parallel) return false;
00060       Point3<T> cyl_origin=tmp.Origin();
00061       Point3<T> line_origin=line.Origin();
00062       Point3<T> cyl_direction=tmp.Direction();
00063       Point3<T> line_direction=line.Direction();
00064 
00065       Point3<T> deltaP=line_origin-cyl_origin;
00066 
00067       T dotDirCyl=cyl_direction.SquaredNorm();    //<d,d>
00068 
00069       T scalar=line_direction.dot(cyl_direction);
00070       Point3<T> tmpA=line_direction-(cyl_direction/dotDirCyl)*scalar;
00071       T A=tmpA.SquaredNorm();
00072 
00073       T scalar2=deltaP.dot(cyl_direction);
00074       Point3<T> tmpB=(deltaP-(cyl_direction/dotDirCyl)*scalar2);
00075 
00076       T B=2.0*tmpA.dot(tmpB);
00077 
00078       T C=tmpB.SquaredNorm()-pow(radius,2);
00079 
00080       T delta=pow(B,2)-4*A*C;
00081 
00082       if(delta<0)
00083           return false;
00084 
00085       t0=(-B-sqrt(delta))/(2*A);
00086       t1=(-B+sqrt(delta))/(2*A);
00087 
00088       p0=line.P(t0);
00089       p1=line.P(t1);
00090 
00091       return true;
00092 }
00093 
00094 // Taken a cylinder and a segment calculates the intersection possible using the
00095 // IntersectionLineCylinder() and checking the output of this.
00096 // Whether the t0 and t1 scalars are between 0 and the length of the segment, then the point
00097 // belongs to it and returns true.
00098 // In output are given two points of intersection (p0, p1) and the parameters t (t0, t1) on the line.
00099 // If p1 belongs to the segment and p0 no, it swaps the points (p0, p1) because operator() in the
00100 // MidPointCylinder always takes the first.
00101 // Otherwise, it means that there is no point between the extremes of the segment that intersects
00102 // the cylinder, in this case it returns false.
00103 //
00104 // Input:  Cylinder<MESH_TYPE, Type, T> & cyl, Segment3<T> & seg.
00105 // Output: CoordType & p0,CoordType & p1, T & t0, T &t1.
00106 
00107 template<class T>
00108 static bool IntersectionSegmentCylinder(const Segment3<T> & cylSeg , T radius,  const Segment3<T> & seg, Point3<T> & p0, Point3<T> & p1)
00109 {
00110   const float eps = 10e-5;
00111 
00112   Line3<T> line;
00113   line.SetOrigin(seg.P0());
00114   line.SetDirection((seg.P1()-seg.P0()).Normalize());
00115 
00116   T t0,t1;
00117   if(IntersectionLineCylinder(cylSeg,radius,line,p0,p1,t0,t1)){
00118       bool inters0 = (t0>=0) && (t0<=seg.Length());
00119       bool inters1 = (t1>=0) && (t1<=seg.Length());
00120       if( inters0 && !inters1) p1=p0;  // if only one of the line intersections belong to the segment
00121       if(!inters0 &&  inters1) p0=p1;  // make both of them the same value.
00122       return inters0 || inters1;
00123   }
00124   return false;
00125 }
00126 
00127 template<class T>
00128 static bool PointIsInSegment(const Point3<T> &point, const Segment3<T> &seg){
00129     const float eps = 10e-5;
00130     Line3<T> line;
00131     line.SetOrigin(seg.P0());
00132     line.SetDirection((seg.P1()-seg.P0()));
00133     T t=line.Projection(point);
00134     // Remembers, two points are different if their distance is >=eps
00135     if(t>-eps && t<1+eps)
00136         return true;
00137     return false;
00138 }
00139 
00140 namespace tri
00141 {
00142 
00143 template <class MeshType>
00144 class CylinderClipping
00145 {
00146 public:
00147   typedef typename MeshType::ScalarType          ScalarType;
00148   typedef typename MeshType::VertexType          VertexType;
00149   typedef typename MeshType::VertexPointer       VertexPointer;
00150   typedef typename MeshType::VertexIterator      VertexIterator;
00151   typedef typename MeshType::CoordType           CoordType;
00152   typedef typename MeshType::FaceType            FaceType;
00153   typedef typename MeshType::FacePointer         FacePointer;
00154   typedef typename MeshType::FaceIterator        FaceIterator;
00155   typedef typename face::Pos<FaceType>        PosType;
00156   typedef Segment3<ScalarType> Segment3x;
00157   typedef Plane3<ScalarType> Plane3x;
00158 
00159   // This predicate
00160   class CylPred
00161   {
00162     public:
00163     CylPred(CoordType &_origin, CoordType &_end, ScalarType _radius, ScalarType _maxDist, ScalarType _minEdgeLen):
00164       origin(_origin),end(_end),radius(_radius),maxDist(_maxDist),minEdgeLen(_minEdgeLen){
00165       seg.Set(origin,end);
00166       pl0.Init(origin,(end-origin).Normalize());
00167       pl1.Init(end,(end-origin).Normalize());
00168     }
00169     void Init() { newPtMap.clear(); }
00170     ScalarType radius;
00171     CoordType origin,end;
00172     ScalarType minEdgeLen;
00173     ScalarType maxDist;
00174   private:
00175     Segment3x seg;
00176     Plane3x pl0,pl1;
00177   public:
00178     // This map store for each edge the new position.
00179     // it is intializaed by the predicate itself.
00180     // and it is shared with the midpoint functor.
00181     std::map< std::pair<CoordType,CoordType>,CoordType > newPtMap;
00182 
00183     // Return true if the given edge intersect the cylinder.
00184 
00185     // Verify if exist a point in an edge that intersects the cylinder. Then calculate
00186     // this point and store it for later use.
00187     // The cases possible are:
00188     // 1. Both extremes have distance greater than or equal to the radius, in this case it
00189     //    calculates the point of this segment closest to the axis of the cylinder. If this
00190     //    has distance less than or equal to the radius and is different from the extremes
00191     //    returns true and this point, otherwise false;
00192     // 2. If there is an extreme inside and one outside it returns true because exist the point
00193     //    of intersection that is calculated using the IntersectionSegmentCylinder();
00194     // 3. Otherwise false.
00195     // So a point is inside of the cylinder if its distance from his axis is <radius-eps??,
00196     // is external if the distance is > radius+eps and it is on the circumference if the
00197     // distance is in the range [radius-eps??, radius+eps].
00198     //
00199     // Input:  face::Pos<typename MESH_TYPE::FaceType>  ep, Cylinder<typename MESH_TYPE::ScalarType> cyl,
00200 
00201     bool operator()(PosType ep)
00202     {
00203       VertexType *v0 = ep.V();
00204       VertexType *v1 = ep.VFlip();
00205       ScalarType eps = minEdgeLen/100.0f;
00206 
00207       if(v0>v1) std::swap(v0,v1);
00208       CoordType p0=v0->P();
00209       CoordType p1=v1->P();
00210 
00211       // CASE 0 - For very short edges --- DO NOTHING
00212       if(Distance(p0,p1)< minEdgeLen) return false;
00213 
00214       Segment3x edgeSeg(p0,p1);
00215       CoordType closest0,closest1; // points on the cyl axis
00216       ScalarType dist0,dist1,dist2;
00217 
00218       SegmentPointDistance(this->seg,p0,closest0,dist0);
00219       SegmentPointDistance(this->seg,p1,closest1,dist1);
00220 
00221       // Case 0.5
00222       if(fabs(dist0-radius)<maxDist && fabs(dist1-radius)<maxDist)
00223       {
00224         newPtMap[std::make_pair(p0,p1)] = (p0+p1)*0.5;
00225         return true;
00226       }
00227 
00228       // ************ Case 1;
00229       if((dist0>radius) && (dist1>radius))
00230       {
00231         bool parallel;
00232         SegmentSegmentDistance(edgeSeg,this->seg, dist2, parallel, closest0,closest1);
00233         if((dist2<radius) &&
00234            (Distance(closest0,p0)>minEdgeLen) &&
00235            (Distance(closest0,p1)>minEdgeLen))
00236         {
00237           newPtMap[std::make_pair(p0,p1)] = closest0;
00238           return true;
00239         }
00240       }
00241       else if(((dist0<radius) && (dist1>radius))||((dist0>radius) && (dist1<radius))){
00242           CoordType int0,int1;
00243           // If there is an intersection point between segment and cylinder,
00244           // this must be different from the extremes of the segment and
00245           // his projection must be in the segment.
00246           if(IntersectionSegmentCylinder(this->seg, this->radius,edgeSeg,int0,int1)){
00247               if(PointIsInSegment(int0,this->seg) && (Distance(p0,int0)>eps) && (Distance(p1,int0)>eps))
00248               {
00249                 if(Distance(int0,p0)<maxDist) return false;
00250                 if(Distance(int0,p1)<maxDist) return false;
00251                 newPtMap[std::make_pair(p0,p1)] = int0;
00252                   return true;
00253               }
00254           }
00255       }
00256       // Now check also against the caps
00257       CoordType pt;
00258       if(IntersectionPlaneSegment(pl0,edgeSeg,pt)){
00259         if((Distance(pt,origin)<radius+2.0*minEdgeLen) &&
00260            (Distance(pt,p0)>eps) && (Distance(pt,p1)>eps) )
00261         {
00262               newPtMap[std::make_pair(p0,p1)] = pt;
00263               return true;
00264         }
00265       }
00266       if(IntersectionPlaneSegment(pl1,edgeSeg,pt)){
00267         if( (Distance(pt,end)<radius+2.0*minEdgeLen) &&
00268             (Distance(pt,p0)>eps) && (Distance(pt,p1)>eps) )
00269         {
00270               newPtMap[std::make_pair(p0,p1)] = pt;
00271               return true;
00272         }
00273       }
00274       return false;
00275       //
00276     }
00277   };
00278 
00279   class CylMidPoint : public   std::unary_function<PosType, CoordType>
00280   {
00281   private:
00282     CylMidPoint() {assert(0);}
00283   public:
00284     CylMidPoint(CylPred &ep) : newPtMap(&(ep.newPtMap)) {
00285       assert(newPtMap);
00286     }
00287     std::map< std::pair<CoordType,CoordType>, CoordType > *newPtMap;
00288     void operator()(VertexType &nv, PosType ep)
00289     {
00290       typename std::map< std::pair<CoordType,CoordType>,CoordType >::iterator mi;
00291       VertexType *v0 = ep.V();
00292       VertexType *v1 = ep.VFlip();
00293       assert(newPtMap);
00294       if(v0>v1) std::swap(v0,v1);
00295 
00296       CoordType p0=v0->P();
00297       CoordType p1=v1->P();
00298       mi=newPtMap->find(std::make_pair(v0->P(),v1->P()));
00299       assert(mi!=newPtMap->end());
00300       nv.P()=(*mi).second;
00301     }
00302 
00303     Color4<ScalarType> WedgeInterp(Color4<ScalarType> &c0, Color4<ScalarType> &c1)
00304     {
00305         Color4<ScalarType> cc;
00306         return cc.lerp(c0,c1,0.5f);
00307     }
00308 
00309     TexCoord2<ScalarType,1> WedgeInterp(TexCoord2<ScalarType,1> &t0, TexCoord2<ScalarType,1> &t1)
00310     {
00311         TexCoord2<ScalarType,1> tmp;
00312         assert(t0.n()== t1.n());
00313         tmp.n()=t0.n();
00314         tmp.t()=(t0.t()+t1.t())/2.0;
00315         return tmp;
00316     }
00317   };
00318 
00319   static void Apply(MeshType &m, CoordType &origin, CoordType &end, ScalarType radius)
00320   {
00321     CylPred cylep(origin,end,radius,radius/100.0,m.bbox.Diag()/50.0f);
00322     CylMidPoint cylmp(cylep);
00323     int i=0;
00324     while((tri::RefineE<MeshType, CylMidPoint >(m, cylmp,cylep))&&(i<50)){
00325       cylep.Init();
00326       printf("Refine %d Vertici: %d, Facce: %d\n",i,m.VN(),m.FN());
00327       i++;
00328     }
00329   }
00330 };
00331 } // end namespace tri
00332 } // end namespace vcg
00333 #endif // CYLINDER_CLIP_H


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