quadrangulator.h
Go to the documentation of this file.
00001 #ifndef MIQ_QUADRANGULATOR_H
00002 #define MIQ_QUADRANGULATOR_H
00003 
00004 #include <vcg/complex/complex.h>
00005 #include <vcg/simplex/face/pos.h>
00006 #include <vcg/simplex/face/jumping_pos.h>
00007 #include <vcg/complex/algorithms/attribute_seam.h>
00008 #include <vcg/complex/algorithms/refine.h>
00009 #include <vcg/complex/algorithms/smooth.h>
00010 #include <vcg/complex/algorithms/clean.h>
00011 #include <vcg/complex/algorithms/update/bounding.h>
00012 #include <wrap/io_trimesh/export.h>
00013 #include <vcg/complex/algorithms/update/texture.h>
00014 
00015 #define precisionQ 0.0000000001
00016 
00017 namespace vcg {
00018 namespace tri {
00019 template <class TriMesh,class PolyMesh>
00020 class Quadrangulator
00021 {
00022 
00023 public:
00024     typedef typename TriMesh::FaceType TriFaceType;
00025     typedef typename TriMesh::VertexType TriVertexType;
00026     typedef typename TriMesh::CoordType CoordType;
00027     typedef typename TriMesh::ScalarType ScalarType;
00028 
00029     typedef typename PolyMesh::FaceType PolyFaceType;
00030     typedef typename PolyMesh::VertexType PolyVertexType;
00031     typedef typename PolyMesh::CoordType PolyCoordType;
00032     typedef typename PolyMesh::ScalarType PolyScalarType;
00033 
00034 
00035     struct InterpolationInfo
00036     {
00037         CoordType Pos3D;
00038         vcg::Point2<ScalarType> PosUV;
00039         ScalarType alpha;
00040         bool to_split;
00041 
00042         InterpolationInfo()
00043         {
00044             Pos3D=CoordType(0,0,0);
00045             PosUV=vcg::Point2<ScalarType>(0,0);
00046             to_split=false;
00047             alpha=-1;
00048         }
00049     };
00050 
00051     //the interpolation map that is saved once to be univoque per edge
00052     typedef std::pair<CoordType,CoordType > KeyEdgeType;
00053 
00054     std::map<KeyEdgeType,InterpolationInfo> InterpMap;
00055 
00056     //ScalarType UVtolerance;
00057 
00058 private:
00059 
00060     bool ToSplit(const vcg::Point2<ScalarType> &uv0,
00061                  const vcg::Point2<ScalarType> &uv1,
00062                  int Dir,
00063                  ScalarType &alpha)
00064     {
00065         ScalarType val0=uv0.V(Dir);
00066         ScalarType val1=uv1.V(Dir);
00067         int IntegerLine0=floor(val0);
00068         int IntegerLine1=floor(val1);
00069         if (IntegerLine0==IntegerLine1)
00070             return false;//no integer line pass throught the edge
00071 
00072         bool swapped=false;
00073         if (IntegerLine0>IntegerLine1)
00074         {
00075             std::swap(IntegerLine0,IntegerLine1);
00076             std::swap(val0,val1);
00077             assert(val1>=val0);
00078             swapped=true;
00079         }
00080 
00081         //then get the first if extist that overcome the threshold
00082         int IntegerSplit=IntegerLine0+1;
00083         bool found=false;
00084         ScalarType dist1,dist0;
00085         for (int i=IntegerSplit;i<=IntegerLine1;i++)
00086         {
00087             dist1=fabs(val1-IntegerSplit);
00088             dist0=fabs(val0-IntegerSplit);
00089 
00090 //            if ((dist0>=UVtolerance)&&
00091 //                (dist1>=UVtolerance))
00092             if ((val0!=IntegerSplit)&&
00093                 (val1!=IntegerSplit))
00094             {
00095                 found=true;
00096                 break;
00097             }
00098             IntegerSplit++;
00099         }
00100         if (!found)return false;
00101 
00102         //have to check distance also in opposite direction
00103         ScalarType lenght=val1-val0;
00104         assert(lenght>=0);
00105         //alpha=1.0-(dist/lenght);
00106         alpha=(dist1/lenght);
00107         if (swapped)alpha=1-alpha;
00108         assert((alpha>0)&&(alpha<1));
00109         return true;
00110     }
00111 
00112     void RoundInitial(TriMesh &to_split)
00113     {
00114         ScalarType minTolerance=precisionQ;
00115         //first add all eddge
00116         for (int i=0;i<to_split.face.size();i++)
00117         {
00118             TriFaceType *f=&to_split.face[i];
00119             for (int j =0;j<3;j++)
00120             {
00121                 vcg::Point2<ScalarType> UV=f->WT(j).P();
00122 
00123                 int int0=floor(UV.X()+0.5);
00124                 int int1=floor(UV.Y()+0.5);
00125 
00126                 ScalarType diff0=(fabs(UV.X()-(ScalarType)int0));
00127                 ScalarType diff1=(fabs(UV.Y()-(ScalarType)int1));
00128 
00129                 if (diff0<minTolerance)
00130                     UV.X()=(ScalarType)int0;
00131                 if (diff1<minTolerance)
00132                     UV.Y()=(ScalarType)int1;
00133 
00134                 f->WT(j).P()=UV;
00135             }
00136         }
00137     }
00138 
00139     void RoundSplits(TriMesh &to_split,int dir)
00140     {
00141         ScalarType minTolerance=precisionQ;
00142         //first add all eddge
00143         for (size_t i=0;i<to_split.face.size();i++)
00144         {
00145             TriFaceType *f=&to_split.face[i];
00146             for (int j =0;j<3;j++)
00147             {
00148                 CoordType p0=f->P0(j);
00149                 CoordType p1=f->P1(j);
00150                 KeyEdgeType k(p0,p1);
00151                 assert(InterpMap.count(k)==1);
00152                 if (!InterpMap[k].to_split)continue;
00153                 //then get the intepolated value
00154                 vcg::Point2<ScalarType> UV=InterpMap[k].PosUV;
00155 
00156                 int int0=floor(UV.X()+0.5);
00157                 int int1=floor(UV.Y()+0.5);
00158 
00159                 ScalarType diff0=(fabs(UV.X()-(ScalarType)int0));
00160                 ScalarType diff1=(fabs(UV.Y()-(ScalarType)int1));
00161 
00162                 if (diff0<minTolerance)
00163                     UV.X()=(ScalarType)int0;
00164                 if (diff1<minTolerance)
00165                     UV.Y()=(ScalarType)int1;
00166 
00167                 InterpMap[k].PosUV=UV;
00168             }
00169         }
00170     }
00171 
00172     void InitSplitMap(TriMesh &to_split,
00173                       int dir)
00174     {
00175        assert((dir==0)||(dir==1));
00176        InterpMap.clear();
00177        //printf("direction %d\n",dir );
00178        //first add all eddge
00179        for (int i=0;i<to_split.face.size();i++)
00180        {
00181            TriFaceType *f=&to_split.face[i];
00182            for (int j =0;j<3;j++)
00183            {
00184                CoordType p0=f->P0(j);
00185                CoordType p1=f->P1(j);
00186                vcg::Point2<ScalarType> Uv0=f->V0(j)->T().P();
00187                vcg::Point2<ScalarType> Uv1=f->V1(j)->T().P();
00188                KeyEdgeType k(p0,p1);
00189 //               printf("p0 (%5.5f,%5.5f,%5.5f) p1(%5.5f,%5.5f,%5.5f) \n",p0.X(),p0.Y(),p0.Z(),p1.X(),p1.Y(),p1.Z());
00190 //               printf("uv0 (%5.5f,%5.5f) uv1(%5.5f,%5.5f) \n",Uv0.X(),Uv0.Y(),Uv1.X(),Uv1.Y());
00191 //               fflush(stdout);
00192                assert(InterpMap.count(k)==0);
00193                InterpMap[k]=InterpolationInfo();
00194            }
00195        }
00196 
00197        //then set the ones to be splitted
00198        for (size_t i=0;i<to_split.face.size();i++)
00199        {
00200            TriFaceType *f=&to_split.face[i];
00201            for (int j =0;j<3;j++)
00202            {
00203                CoordType p0=f->P0(j);
00204                CoordType p1=f->P1(j);
00205                vcg::Point2<ScalarType> uv0=f->V0(j)->T().P();
00206                vcg::Point2<ScalarType> uv1=f->V1(j)->T().P();
00207 
00208                ScalarType alpha;
00209                if (!ToSplit(uv0,uv1,dir,alpha))continue;
00210 
00211                KeyEdgeType k(p0,p1);
00212                assert(InterpMap.count(k)==1);
00213                InterpMap[k].Pos3D=p0*alpha+p1*(1-alpha);
00214                InterpMap[k].PosUV=uv0*alpha+uv1*(1-alpha);
00215                InterpMap[k].to_split=true;
00216                InterpMap[k].alpha=alpha;
00217            }
00218        }
00219 
00220        //then make them coherent
00221        for (size_t i=0;i<to_split.face.size();i++)
00222        {
00223            TriFaceType *f=&to_split.face[i];
00224            for (int j =0;j<3;j++)
00225            {
00226                CoordType p0=f->P0(j);
00227                CoordType p1=f->P1(j);
00228                vcg::Point2<ScalarType> uv0=f->V0(j)->T().P();
00229                vcg::Point2<ScalarType> uv1=f->V1(j)->T().P();
00230 //               if (p0>p1)continue; //only one verse of coherence
00231 
00232                KeyEdgeType k0(p0,p1);
00233                assert(InterpMap.count(k0)==1);//there should be already in the
00234                                               //table and it should be coherent
00235 
00236                KeyEdgeType k1(p1,p0);
00237                if(InterpMap.count(k1)==0)continue;//REAL border, no need for update
00238 
00239                bool to_split0=InterpMap[k0].to_split;
00240                bool to_split1=InterpMap[k1].to_split;
00241 
00242                //the find all possible cases
00243                if ((!to_split0)&&(!to_split1))continue;
00244 
00245                if ((to_split0)&&(to_split1))
00246                {
00247                    CoordType Pos3D=InterpMap[k1].Pos3D;
00248                    InterpMap[k0].Pos3D=Pos3D;
00249 
00250                    //check if need to make coherent also the UV Position
00251                    //skip the fake border and do the rest
00252                    bool IsBorderFF=(f->FFp(j)==f);
00253 
00254                    if (!IsBorderFF) //in this case they should have same UVs
00255                        InterpMap[k0].PosUV=InterpMap[k1].PosUV;
00256                    else
00257                    {
00258                        ScalarType alpha=InterpMap[k1].alpha;
00259                        assert((alpha>=0)&&(alpha<=1));
00260                        alpha=1-alpha;
00261                        InterpMap[k0].PosUV=alpha*uv0+(1-alpha)*uv1;
00262                        InterpMap[k0].alpha=alpha;
00263                    }
00264 
00265                }
00266                else
00267                if ((!to_split0)&&(to_split1))
00268                {
00269                    CoordType Pos3D=InterpMap[k1].Pos3D;
00270                    InterpMap[k0].Pos3D=Pos3D;
00271 
00272                    //check if need to make coherent also the UV Position
00273                    //skip the fake border and do the rest
00274                    bool IsBorderFF=(f->FFp(j)==f);
00275 
00276                    InterpMap[k0].to_split=true;
00277 
00278                    if (!IsBorderFF) //in this case they should have same UVs
00279                        InterpMap[k0].PosUV=InterpMap[k1].PosUV;
00280                    else //recalculate , it pass across a seam
00281                    {
00282                        ScalarType alpha=InterpMap[k1].alpha;
00283                        assert((alpha>=0)&&(alpha<=1));
00284                        alpha=1-alpha;
00285                        InterpMap[k0].PosUV=alpha*uv0+(1-alpha)*uv1;
00286                        InterpMap[k0].alpha=alpha;
00287                    }
00288               }
00289            }
00290        }
00291 
00292        RoundSplits(to_split,dir);
00293     }
00294 
00295     // Basic subdivision class
00296     // This class must provide methods for finding the position of the newly created vertices
00297     // In this implemenation we simply put the new vertex in the MidPoint position.
00298     // Color and TexCoords are interpolated accordingly.
00299     template<class MESH_TYPE>
00300     struct SplitMidPoint : public   std::unary_function<vcg::face::Pos<typename MESH_TYPE::FaceType> ,  typename MESH_TYPE::CoordType >
00301     {
00302         typedef typename MESH_TYPE::VertexType VertexType;
00303         typedef typename MESH_TYPE::FaceType FaceType;
00304         typedef typename MESH_TYPE::CoordType CoordType;
00305 
00306         std::map<KeyEdgeType,InterpolationInfo> *MapEdge;
00307 
00308         void operator()(typename MESH_TYPE::VertexType &nv,
00309                         vcg::face::Pos<typename MESH_TYPE::FaceType>  ep)
00310         {
00311             VertexType* v0=ep.f->V0(ep.z);
00312             VertexType* v1=ep.f->V1(ep.z);
00313             assert(v0!=v1);
00314 
00315             CoordType p0=v0->P();
00316             CoordType p1=v1->P();
00317             assert(p0!=p1);
00318 
00319             KeyEdgeType k(p0,p1);
00320             bool found=(MapEdge->count(k)==1);
00321             assert(found);
00322             bool to_split=(*MapEdge)[k].to_split;
00323             assert(to_split);
00324 
00325             //get the value on which the edge must be splitted
00326             nv.P()= (*MapEdge)[k].Pos3D;
00327             //nv.N()= v0->N()*alpha+v1->N()*(1.0-alpha);
00328             nv.T().P()=(*MapEdge)[k].PosUV;
00329         }
00330 
00331         vcg::TexCoord2<ScalarType> WedgeInterp(vcg::TexCoord2<ScalarType> &t0,
00332                                                vcg::TexCoord2<ScalarType> &t1)
00333         {
00334             return (vcg::TexCoord2<ScalarType>(0,0));
00335         }
00336 
00337         SplitMidPoint(std::map<KeyEdgeType,InterpolationInfo> *_MapEdge){MapEdge=_MapEdge;}
00338     };
00339 
00340     template <class MESH_TYPE>
00341     class EdgePredicate
00342     {
00343         typedef typename MESH_TYPE::VertexType VertexType;
00344         typedef typename MESH_TYPE::FaceType FaceType;
00345         typedef typename MESH_TYPE::ScalarType ScalarType;
00346 
00347         std::map<KeyEdgeType,InterpolationInfo> *MapEdge;
00348 
00349     public:
00350 
00351         bool operator()(vcg::face::Pos<typename MESH_TYPE::FaceType> ep) const
00352         {
00353             VertexType* v0=ep.f->V0(ep.z);
00354             VertexType* v1=ep.f->V1(ep.z);
00355             assert(v0!=v1);
00356 
00357             CoordType p0=v0->P();
00358             CoordType p1=v1->P();
00359             assert(p0!=p1);
00360 
00361             KeyEdgeType k(p0,p1);
00362             bool found=(MapEdge->count(k)==1);
00363             assert(found);
00364             bool to_split=(*MapEdge)[k].to_split;
00365             return(to_split);
00366         }
00367 
00368         EdgePredicate(std::map<KeyEdgeType,InterpolationInfo> *_MapEdge){MapEdge=_MapEdge;}
00369     };
00370 
00371     void SplitTrisDir(TriMesh &to_split,
00372                        int dir)
00373     {
00374         bool done=true;
00375         //int step=0;
00376         while (done)
00377         {
00378             printf("Number of Vertices %d \n",to_split.vn);
00379             fflush(stdout);
00380 
00381             InitSplitMap(to_split,dir);
00382 
00383             SplitMidPoint<TriMesh> splMd(&InterpMap);
00384             EdgePredicate<TriMesh> eP(&InterpMap);
00385 
00386             done=vcg::tri::RefineE<TriMesh,SplitMidPoint<TriMesh>,EdgePredicate<TriMesh> >(to_split,splMd,eP);
00387 
00388         }
00389         printf("Number of Vertices %d \n",to_split.vn);
00390         fflush(stdout);
00391          fflush(stdout);
00392     }
00393 
00394 
00395     bool IsOnIntegerLine(vcg::Point2<ScalarType> uv0,
00396                          vcg::Point2<ScalarType> uv1)
00397     {
00398         for (int dir=0;dir<2;dir++)
00399         {
00400             ScalarType val0=uv0.V(dir);
00401             ScalarType val1=uv1.V(dir);
00402             int integer0=floor(uv0.V(dir)+0.5);
00403             int integer1=floor(uv1.V(dir)+0.5);
00404             if (integer0!=integer1)continue;
00405 //            if ((fabs(val0-(ScalarType)integer0))>=UVtolerance)continue;
00406 //            if ((fabs(val1-(ScalarType)integer1))>=UVtolerance)continue;
00407             if (val0!=(ScalarType)floor(val0))continue;
00408             if (val1!=(ScalarType)floor(val1))continue;
00409             return true;
00410         }
00411         return false;
00412     }
00413 
00414     bool IsOnIntegerVertex(vcg::Point2<ScalarType> uv,
00415                            bool IsB)
00416     {
00417         int onIntegerL=0;
00418         for (int dir=0;dir<2;dir++)
00419         {
00420             ScalarType val0=uv.V(dir);
00421             int integer0=floor(val0+0.5);
00422             //if ((fabs(val0-(ScalarType)integer0))<UVtolerance)onIntegerL++;
00423             if (val0==(ScalarType)floor(val0))onIntegerL++;
00424         }
00425         if ((IsB)&&(onIntegerL>0))return true;
00426         return (onIntegerL==2);
00427     }
00428 
00429 
00430     void InitIntegerEdgesVert(TriMesh &Tmesh)
00431     {
00432         //IntegerEdges.clear();
00433         vcg::tri::UpdateFlags<TriMesh>::FaceSetF(Tmesh);
00434         vcg::tri::UpdateFlags<TriMesh>::FaceClearS(Tmesh);
00435         vcg::tri::UpdateFlags<TriMesh>::VertexClearS(Tmesh);
00436 
00437         for (unsigned int i=0;i<Tmesh.face.size();i++)
00438         {
00439             TriFaceType *f=&Tmesh.face[i];
00440             if (f->IsD())continue;
00441             for (int j=0;j<3;j++)
00442             {
00443                 bool IsBorder=f->IsB(j);
00444                 if (IsBorder)
00445                     f->ClearF(j);
00446                 else
00447                 {
00448                     vcg::Point2<ScalarType> uv0=f->WT(j).P();
00449                     vcg::Point2<ScalarType> uv1=f->WT((j+1)%3).P();
00450 
00451                     if (IsOnIntegerLine(uv0,uv1))
00452                     {
00453                         f->ClearF(j);
00454                         TriFaceType *f1=f->FFp(j);
00455                         int z=f->FFi(j);
00456                         assert(f1!=f);
00457                         f1->ClearF(z);
00458                     }
00459                 }
00460 
00461                 bool BorderV=f->V(j)->IsB();
00462 
00463                 if (IsOnIntegerVertex(f->WT(j).P(),BorderV))
00464                     f->V(j)->SetS();
00465             }
00466         }
00467     }
00468 
00469     short int AlignmentEdge(TriFaceType *f,
00470                       int edge_index)
00471     {
00472         vcg::Point2<ScalarType> uv0=f->WT(edge_index).P();
00473         vcg::Point2<ScalarType> uv1=f->WT((edge_index+1)%3).P();
00474         if (uv0.X()==uv1.X())return 0;
00475         if (uv0.Y()==uv1.Y())return 1;
00476         return -1;
00477     }
00478 
00479     void FindPolygon(vcg::face::Pos<TriFaceType> &currPos,
00480                      std::vector<TriVertexType *> &poly,
00481                      std::vector<short int> &UVpoly)
00482     {
00483         currPos.F()->SetV();
00484         currPos.F()->C()=vcg::Color4b(255,0,0,255);
00485         poly.clear();
00486         assert(currPos.V()->IsS());
00487         TriVertexType *v_init=currPos.V();
00488         poly.push_back(currPos.V());
00489 
00490         //retrieve UV
00491         int indexV0=currPos.E();
00492 
00493         short int Align=AlignmentEdge(currPos.F(),currPos.E());
00494 
00495         std::vector<short int> TempUVpoly;
00496         TempUVpoly.push_back(Align);
00497 
00498         do
00499         {
00500             currPos.NextNotFaux();
00501             currPos.F()->SetV();
00502             currPos.F()->C()=vcg::Color4b(255,0,0,255);
00503 
00504             if ((currPos.V()->IsS())&&(currPos.V()!=v_init))
00505             {
00506                 poly.push_back(currPos.V());
00507 
00508                 short int Align=AlignmentEdge(currPos.F(),currPos.E());
00509 
00510                 TempUVpoly.push_back(Align);
00511             }
00512 
00513         }while (currPos.V()!=v_init);
00514 
00515         //then shift the order of UV by one
00516         //to be consistent with edge ordering
00517         int size=TempUVpoly.size();
00518         for (int i=0;i<size;i++)
00519             UVpoly.push_back(TempUVpoly[(i+1)%size]);
00520     }
00521 
00522     void FindPolygons(TriMesh &Tmesh,
00523                       std::vector<std::vector<TriVertexType *> > &polygons,
00524                       std::vector<std::vector<short int> > &UV)
00525     {
00526         vcg::tri::UpdateFlags<TriMesh>::FaceClearV(Tmesh);
00527         for (unsigned int i=0;i<Tmesh.face.size();i++)
00528         {
00529             TriFaceType * f=&Tmesh.face[i];
00530             if (f->IsV())continue;
00531 
00532             for (int j=0;j<3;j++)
00533             {
00534                 TriVertexType* v0=f->V0(j);
00535                 if (!v0->IsS())continue;
00536                 if (f->IsF(j))continue;
00537 
00538                 vcg::face::Pos<TriFaceType> startPos(f,j);
00539 
00540                 std::vector<TriVertexType *> poly;
00541                 std::vector< short int> UVpoly;
00542 
00543                 FindPolygon(startPos,poly,UVpoly);
00544 
00545                 if (poly.size()>2)
00546                 {
00547                    assert(poly.size()==UVpoly.size());
00548                    std::reverse(poly.begin(),poly.end());
00549 //                    std::reverse(UVpoly.begin(),UVpoly.end());
00550 
00551                     polygons.push_back(poly);
00552                     UV.push_back(UVpoly);
00553 
00554                 }
00555                 //only one polygon per initial face
00556                 break;
00557             }
00558         }
00559 
00560     }
00561 
00562     //FUNCTIONS NEEDED BY "UV WEDGE TO VERTEX" FILTER
00563     static void ExtractVertex(const TriMesh & srcMesh,
00564                               const TriFaceType & f,
00565                               int whichWedge,
00566                               const TriMesh & dstMesh,
00567                               TriVertexType & v)
00568     {
00569         (void)srcMesh;
00570         (void)dstMesh;
00571         // This is done to preserve every single perVertex property
00572         // perVextex Texture Coordinate is instead obtained from perWedge one.
00573         v.ImportData(*f.cV(whichWedge));
00574         v.T() = f.cWT(whichWedge);
00575     }
00576 
00577     static bool CompareVertex(const TriMesh & m,
00578                               TriVertexType & vA,
00579                               TriVertexType & vB)
00580     {
00581         (void)m;
00582         return (vA.cT() == vB.cT());
00583     }
00584 
00585     void ConvertWTtoVT(TriMesh &Tmesh)
00586     {
00587         int vn = Tmesh.vn;
00588         vcg::tri::AttributeSeam::SplitVertex(Tmesh, ExtractVertex, CompareVertex);
00589         vcg::tri::UpdateTopology<TriMesh>::FaceFace(Tmesh);
00590        // vcg::tri::UpdateFlags<TriMesh>::FaceBorderFromFF(Tmesh);
00591     }
00592 
00593     void ConvertVTtoWT(TriMesh &Tmesh)
00594     {
00595         vcg::tri::UpdateTexture<TriMesh>::WedgeTexFromVertexTex(Tmesh);
00596         vcg::tri::Clean<TriMesh>::RemoveDuplicateVertex(Tmesh);
00597     }
00598 
00599     void ReupdateMesh(TriMesh &Tmesh)
00600     {
00601         vcg::tri::UpdateNormal<TriMesh>::PerFaceNormalized(Tmesh);       // update Normals
00602         vcg::tri::UpdateNormal<TriMesh>::PerVertexNormalized(Tmesh);// update Normals
00603         //compact the mesh
00604         vcg::tri::Allocator<TriMesh>::CompactVertexVector(Tmesh);
00605         vcg::tri::Allocator<TriMesh>::CompactFaceVector(Tmesh);
00606         vcg::tri::UpdateTopology<TriMesh>::FaceFace(Tmesh);                      // update Topology
00607         vcg::tri::UpdateTopology<TriMesh>::TestFaceFace(Tmesh);          //and test it
00608         //set flags
00609         vcg::tri::UpdateFlags<TriMesh>::VertexClearV(Tmesh);
00610         vcg::tri::UpdateFlags<TriMesh>::FaceBorderFromFF(Tmesh);
00611         vcg::tri::UpdateFlags<TriMesh>::VertexBorderFromFaceBorder(Tmesh);
00612     }
00613 
00614 public:
00615 
00616 
00617     void TestIsProper(TriMesh &Tmesh)
00618     {
00619 
00620 
00621         //test manifoldness
00622         int test=vcg::tri::Clean<TriMesh>::CountNonManifoldVertexFF(Tmesh);
00623         //assert(test==0);
00624         if (test != 0)
00625             cerr << "Assertion failed: TestIsProper NonManifoldVertices!" << endl;
00626 
00627         test=vcg::tri::Clean<TriMesh>::CountNonManifoldEdgeFF(Tmesh);
00628         //assert(test==0);
00629         if (test != 0)
00630             cerr << "Assertion failed: TestIsProper NonManifoldEdges" << endl;
00631 
00632         for (unsigned int i=0;i<Tmesh.face.size();i++)
00633         {
00634             TriFaceType *f=&Tmesh.face[i];
00635             assert (!f->IsD());
00636             for (int z=0;z<3;z++)
00637             {
00638                 //int indexOpp=f->FFi(z);
00639                 TriFaceType *Fopp=f->FFp(z);
00640                 if (Fopp==f) continue;
00641                 //assert( f->FFp(z)->FFp(f->FFi(z))==f );
00642                 if (f->FFp(z)->FFp(f->FFi(z))!=f)
00643                     cerr << "Assertion failed: TestIsProper f->FFp(z)->FFp(f->FFi(z))!=f " << endl;
00644             }
00645         }
00646     }
00647 
00648 
00649 
00650     void Quadrangulate(TriMesh &Tmesh,
00651                        PolyMesh &Pmesh,
00652                        std::vector< std::vector< short int> > &UV)
00653     {
00654         UV.clear();
00655         Pmesh.Clear();
00656 
00657         TestIsProper(Tmesh);
00658 
00659         RoundInitial(Tmesh);
00660 
00661         //UVtolerance=tolerance;
00662 
00663         //split to per vert
00664         ConvertWTtoVT(Tmesh);
00665 
00666 
00667         vcg::tri::Allocator<TriMesh>::CompactVertexVector(Tmesh);
00668         vcg::tri::Allocator<TriMesh>::CompactFaceVector(Tmesh);
00669         vcg::tri::UpdateTopology<TriMesh>::FaceFace(Tmesh);
00670         (void)Pmesh;
00671         //TestIsProper(Tmesh);
00672 
00673         //then split the tris along X
00674         SplitTrisDir(Tmesh,0);
00675         SplitTrisDir(Tmesh,1);
00676 
00677         //merge back the mesh and WT coords
00678         ConvertVTtoWT(Tmesh);
00679 
00680         //CleanMesh(Pmesh);
00681 
00682         //update properties of the mesh
00683         ReupdateMesh(Tmesh);
00684 
00685         //test manifoldness
00686         TestIsProper(Tmesh);
00687 
00688         InitIntegerEdgesVert(Tmesh);
00689 
00690         for (int i=0;i<Tmesh.face.size();i++)
00691             Tmesh.face[i].C()=vcg::Color4b(255,255,255,255);
00692 
00693         std::vector<std::vector<TriVertexType *> > polygons;
00694         FindPolygons(Tmesh,polygons,UV);
00695 
00696         //then add to the polygonal mesh
00697         Pmesh.Clear();
00698 
00699         int numV=vcg::tri::UpdateSelection<TriMesh>::VertexCount(Tmesh);
00700 
00701         //first create vertices
00702         vcg::tri::Allocator<PolyMesh>::AddVertices(Pmesh,numV);
00703 
00704         std::map<CoordType,int> VertMap;
00705         int index=0;
00706         for(unsigned int i=0;i<Tmesh.vert.size();i++)
00707         {
00708             if (!Tmesh.vert[i].IsS())continue;
00709 
00710             CoordType pos=Tmesh.vert[i].P();
00711             CoordType norm=Tmesh.vert[i].N();
00712             vcg::Point2<ScalarType> UV=Tmesh.vert[i].T().P();
00713             Pmesh.vert[index].P()=typename PolyMesh::CoordType(pos.X(),pos.Y(),pos.Z());
00714             Pmesh.vert[index].N()=typename PolyMesh::CoordType(norm.X(),norm.Y(),norm.Z());
00715             Pmesh.vert[index].T().P()=UV;
00716             VertMap[pos]=index;
00717             index++;
00718         }
00719 
00720         //then add polygonal mesh
00721         vcg::tri::Allocator<PolyMesh>::AddFaces(Pmesh,polygons.size());
00722         for (unsigned int i=0;i<polygons.size();i++)
00723         {
00724             int size=polygons[i].size();
00725             Pmesh.face[i].Alloc(size);
00726             for (int j=0;j<size;j++)
00727             {
00728                 CoordType pos=(polygons[i][j])->P();
00729                 assert(VertMap.count(pos)==1);
00730                 int index=VertMap[pos];
00731                 Pmesh.face[i].V(j)=&(Pmesh.vert[index]);
00732             }
00733         }
00734 
00735 
00736     }
00737 };
00738 }
00739 }
00740 #endif


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