Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024 #ifndef __VCGLIB_POLYGON_SUPPORT
00025 #define __VCGLIB_POLYGON_SUPPORT
00026
00027 #include <vcg/simplex/face/jumping_pos.h>
00028 #include <vcg/space/planar_polygon_tessellation.h>
00029
00030 namespace vcg {
00031 namespace tri {
00033
00035
00037
00044 template <class TriMeshType,class PolyMeshType >
00045 class PolygonSupport{
00046 typedef typename TriMeshType::FaceIterator TriFaceIterator;
00047 typedef typename PolyMeshType::FaceIterator PolyFaceIterator;
00048 typedef typename TriMeshType::VertexIterator TriVertexIterator;
00049 typedef typename PolyMeshType::VertexIterator PolyVertexIterator;
00050 typedef typename TriMeshType::CoordType::ScalarType Scalar;
00051
00052 public:
00058 static void MergeFlatFaces(TriMeshType & tm, double tolerance = 0.1E-4)
00059 {
00060 typedef typename TriMeshType::FaceType FaceType;
00061 Scalar minDist = 1 - Scalar(tolerance);
00062 for (TriFaceIterator fi=tm.face.begin(); fi!=tm.face.end(); fi++) {
00063 FaceType *fa = &*fi;
00064 for (int w=0; w<3; w++) {
00065 FaceType *fb = fa->FFp(w);
00066 if ( (fb>fa) && (fa->N()*fb->N() > minDist) ) {
00067 fa->SetF( w );
00068 fb->SetF( fa->FFi(w) );
00069 }
00070 }
00071 }
00072 }
00073
00077 static void ImportFromPolyMesh(TriMeshType & tm, PolyMeshType & pm)
00078 {
00079 tri::RequirePolygonalMesh(pm);
00080 std::vector<typename PolyMeshType::CoordType> points;
00081
00082
00083 PolyVertexIterator vi;
00084 TriVertexIterator tvi = Allocator<TriMeshType>::AddVertices(tm,pm.vert.size());
00085 int cnt = 0;
00086 for(tvi = tm.vert.begin(),vi = pm.vert.begin(); tvi != tm.vert.end(); ++tvi,++vi,++cnt)
00087 if(!(*vi).IsD()) (*tvi).ImportData(*vi); else tri::Allocator<TriMeshType>::DeleteVertex(tm,(*tvi));
00088
00089 for(PolyFaceIterator fi = pm.face.begin(); fi != pm.face.end(); ++fi)
00090 {
00091 if(!((*fi).IsD())){
00092 points.clear();
00093 for(int i = 0; i < (*fi).VN(); ++i) {
00094 typename PolyMeshType::VertexType * v = (*fi).V(i);
00095 points.push_back(v->P());
00096 }
00097 std::vector<int> faces;
00098 TessellatePlanarPolygon3(points,faces);
00099 for(size_t i = 0; i<faces.size();i+=3){
00100 TriFaceIterator tfi = Allocator<TriMeshType>::AddFace(tm,
00101 tri::Index(pm,(*fi).V( faces[i+0] )),
00102 tri::Index(pm,(*fi).V( faces[i+1] )),
00103 tri::Index(pm,(*fi).V( faces[i+2] )) );
00104
00105 tfi->ImportData(*fi);
00106
00107 if( (faces[i ]+1)%points.size() != size_t(faces[i+1])) (*tfi).SetF(0);
00108 if( (faces[i+1]+1)%points.size() != size_t(faces[i+2])) (*tfi).SetF(1);
00109 if( (faces[i+2]+1)%points.size() != size_t(faces[i ])) (*tfi).SetF(2);
00110 }
00111 }
00112 }
00113 }
00114
00115
00121 static void ImportFromTriMesh( PolyMeshType & pm, TriMeshType & tm)
00122 {
00123 tri::RequirePolygonalMesh(pm);
00124 tri::RequireTriangularMesh(tm);
00125
00126 tri::RequireCompactness(tm);
00127 tri::RequireFFAdjacency(tm);
00128 tri::UpdateFlags<TriMeshType>::FaceClearV(tm);
00129
00130 int cnt = 0;
00131 typename TriMeshType ::ConstVertexIterator tvi;
00132 typename PolyMeshType::VertexIterator vi = tri::Allocator<PolyMeshType>::AddVertices(pm,tm.vert.size());
00133 for(tvi = tm.vert.begin(); tvi != tm.vert.end(); ++tvi,++vi,++cnt)
00134 (*vi).ImportData(*tvi);
00135
00136
00137 typename TriMeshType::FaceIterator tfi;
00138 face::JumpingPos<typename TriMeshType::FaceType> p;
00139
00140 for( tfi = tm.face.begin(); tfi != tm.face.end(); ++tfi) if(!(*tfi).IsV())
00141 {
00142 std::vector<typename TriMeshType::VertexPointer> vs;
00143 ExtractPolygon(&*tfi,vs);
00144 std::reverse(vs.begin(),vs.end());
00145
00146 if (vs.size()==0)continue;
00147 typename PolyMeshType::FaceIterator pfi = tri::Allocator<PolyMeshType>::AddFaces(pm,1);
00148 (*pfi).Alloc(vs.size());
00149 for(size_t i = 0 ; i < vs.size(); ++i)
00150 (*pfi).V(i) = ( typename PolyMeshType::VertexType*) & pm.vert[vs[i]-&(*tm.vert.begin())];
00151 if(tri::HasPerFaceColor(tm) && tri::HasPerFaceColor(pm)) pfi->C()=tfi->C();
00152 if(tri::HasPerFaceQuality(tm) && tri::HasPerFaceQuality(pm)) pfi->Q()=tfi->Q();
00153 }
00154 }
00163 static void ExtractPolygon(typename TriMeshType::FacePointer tfp,
00164 std::vector<typename TriMeshType::VertexPointer> &vs,
00165 std::vector<typename TriMeshType::FacePointer> &fs)
00166 {
00167 vs.clear();
00168 fs.clear();
00169
00170 int se = -1;
00171 for(int i=0; i<3; i++) if (!( tfp->IsF(i))) { se = i; break;}
00172
00173
00174 if(se==-1) return;
00175 if(tfp->IsV()) return;
00176
00177
00178 face::Pos<typename TriMeshType::FaceType> start(tfp,se,tfp->V(se));
00179 face::Pos<typename TriMeshType::FaceType> p(start);
00180
00181 fs.push_back(p.F());
00182 p.F()->SetV();
00183
00184 do
00185 {
00186 assert(!p.F()->IsF(p.E()));
00187 vs.push_back(p.V());
00188 p.FlipE();
00189 while( p.F()->IsF(p.E()) )
00190 {
00191 p.FlipF();
00192 if(!p.F()->IsV()) {
00193 fs.push_back(p.F());
00194 p.F()->SetV();
00195 }
00196 p.FlipE();
00197 }
00198 p.FlipV();
00199 } while(p!=start);
00200
00201 }
00202 static void ExtractPolygon(typename TriMeshType::FacePointer tfp, std::vector<typename TriMeshType::VertexPointer> &vs)
00203 {
00204 std::vector<typename TriMeshType::FacePointer> fs;
00205 ExtractPolygon(tfp,vs,fs);
00206 }
00207 };
00208 }}
00209
00210 #endif // __VCGLIB_TRI_CLIP