poly_triangulator.h
Go to the documentation of this file.
00001 #ifndef POLY_TRIANGULATOR_H
00002 #define POLY_TRIANGULATOR_H
00003 
00004 #include "util_dae.h"
00005 #include <wrap/gl/glu_tesselator.h>
00006 
00007 namespace vcg {
00008 namespace tri {
00009 namespace io {  
00010                 // These two classes is used for temporary storing of the
00011                 // collected data of the polgons during the reading of files. 
00012                 
00013         template<typename VERTEX_TYPE>
00014         class MyPolygon 
00015         {
00016         public:
00017                 typedef VERTEX_TYPE BaseVertexType;
00018 
00019                 int _nvert;
00020                 std::vector<VERTEX_TYPE*> _pv;
00021                 std::vector< vcg::TexCoord2<float> > _txc;
00022 
00023 
00024                 MyPolygon(int n)
00025                 :_nvert(n),_pv(_nvert),_txc(_nvert)
00026                 {
00027                 }
00028         };
00029 
00030         template<typename POLYGONAL_TYPE>
00031         class PolygonalMesh
00032         {
00033         public:
00034                 typedef POLYGONAL_TYPE FaceType;
00035 
00036                 enum PERWEDGEATTRIBUTETYPE {NONE = 0,NORMAL = 1,MULTITEXTURECOORD = 2,MULTICOLOR = 4};
00037 
00038                 typedef typename FaceType::BaseVertexType VertexType;
00039                 typedef VertexType* VertexPointer;
00040                 typedef typename std::vector<VertexType>::iterator VertexIterator; 
00041                 typedef typename std::vector<FaceType>::iterator PolygonIterator; 
00042 
00043                 vcg::Box3<float> bbox;
00044 
00045                 std::vector<VertexType> vert;
00046                 std::vector<FaceType> _pols;
00047 
00048                 void generatePointsVector(std::vector<std::vector<vcg::Point3f> >& v)
00049                 {
00050                         for(typename PolygonalMesh::PolygonIterator itp = _pols.begin();itp != _pols.end();++itp)
00051                         {
00052                                 v.push_back(std::vector<vcg::Point3f>());
00053                                 for(typename std::vector<VertexPointer>::iterator itv = itp->_pv.begin();itv != itp->_pv.end();++itv)
00054                                 {
00055                                         v[v.size() - 1].push_back((*itv)->P());
00056                                 }       
00057                         }
00058                 }
00059 
00060                 void usePerWedgeAttributes(PERWEDGEATTRIBUTETYPE att,const unsigned int multitexture = 1,const unsigned int multicolor = 1)
00061                 {
00062                         if (att != NONE)
00063                         {
00064                                 for(PolygonIterator itp = _pols.begin();itp != _pols.end();++itp)
00065                                 {
00066                                         if (att & MULTICOLOR) itp->usePerWedgeColor(multicolor);
00067                                         if (att & MULTITEXTURECOORD) itp->usePerWedgeMultiTexture(multitexture);
00068                                         if (att & NORMAL) itp->usePerWedgeNormal();
00069                                 }
00070                         }
00071                 }
00072 
00073                 template<class TRIMESH>
00074                 void triangulate(TRIMESH& mesh)
00075                 {
00076                         std::vector<std::vector<vcg::Point3f> > pl;
00077                         mesh.vert.resize(vert.size());
00078                         int multicoor = 0;
00079                         //PolygonalMesh's points has been copied in TriangularMesh
00080                         for(size_t jj = 0;jj < mesh.vert.size();++jj)
00081                                 mesh.vert[jj].P() = vert[jj].P();
00082 
00083                         bool texen = mesh.face.IsWedgeTexEnabled();
00084                         unsigned int totaltri = 0;
00085                         for(size_t ii = 0;ii < _pols.size();++ii)
00086                                         totaltri += _pols[ii]._nvert - 2;
00087                                 
00088                         mesh.face.resize(totaltri);
00089 
00090                         //transform the polygonal mesh in a vector<vector<Point>>
00091                         generatePointsVector(pl);
00092 
00093 
00094                         int trioff = 0;
00095                         //foreach Polygon
00096                         for(size_t ii = 0;ii < pl.size();++ii)
00097                         {
00098                                 std::vector<int> tx;
00099                                 std::vector<std::vector<vcg::Point3f> > pl2(1);
00100                                 pl2[0] = pl[ii];
00101 
00102                                 vcg::glu_tesselator::tesselate(pl2,tx);
00103                                 size_t ntri = tx.size() / 3;
00104                                 assert(tx.size() % 3 == 0);
00105                                         
00106 
00107                                 int polvert = 0;
00108                                 //foreach triangle
00109                                 for(size_t tr = 0;tr < ntri;++tr)
00110                                 {
00111                                                 
00112                                         //typename TRIMESH::FaceType& f = mesh.face[tr];
00113 
00114                                         //typename TRIMESH::FaceType& f = mesh.face[tr];
00115                                         for(unsigned int tt = 0;tt < 3; ++tt)
00116                                         {
00117                                                 mesh.face[trioff + tr].V(tt) = &(mesh.vert[_pols[ii]._pv[tx[3 * tr + tt]] - &(vert[0])]);
00118                                                 //vcg::Point3f ppp = mesh.face[tr].V(tt)->P();
00119                                                 if (texen)
00120                                                 {
00121                                                 /*      f.WT(multicoor).U() = _pols[ii]._txc[polvert].U();
00122                                                         f.WT(multicoor).V() = _pols[ii]._txc[polvert].V();
00123                                                         f.WT(multicoor).N() = _pols[ii]._txc[polvert].N();*/
00124                                                                 
00125                                                 }
00126                                                 polvert = (polvert + 1) % _pols[ii]._nvert;
00127                                         }
00128                                         //mesh.face.push_back(f);
00129                                 }
00130                                 trioff += ntri;
00131                         }
00132                         assert(trioff == totaltri);
00133                 }
00134         };
00135 }
00136 }
00137 }
00138 
00139 #endif


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