polygonmesh.cpp
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-2012                                           \/)\/    *
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 
00024 #include <vcg/complex/complex.h>
00025 
00026 /*include the algorithms for updating: */
00027 #include <vcg/complex/algorithms/update/topology.h>
00028 #include <vcg/complex/algorithms/update/bounding.h>
00029 #include <vcg/complex/algorithms/update/normal.h>
00030 
00031 #include <vcg/complex/algorithms/clean.h>
00032 #include <vcg/complex/algorithms/create/platonic.h>
00033 
00034 #include <wrap/io_trimesh/import.h>
00035 #include <wrap/io_trimesh/export_ply.h>
00036 
00037 /* include the support for polygon meshes (function to convert from/to trimesh)*/
00038 //#include <vcg/complex/algorithms/polygon_support.h>
00039 
00040 /* include the support for half edges */
00041 #include <vcg/complex/algorithms/update/halfedge_indexed.h>
00042 
00043 
00044 using namespace vcg;
00045 using namespace std;
00046 
00047 // forward declarations
00048 class TFace;
00049 class TVertex;
00050 
00051 struct TUsedTypes: public vcg::UsedTypes< vcg::Use<TVertex>::AsVertexType, vcg::Use<TFace>::AsFaceType >{};
00052 
00053 
00054 
00055 /* Definition of a mesh of triangles
00056 */
00057 class TVertex : public Vertex< TUsedTypes,
00058     vertex::BitFlags,
00059     vertex::Coord3f,
00060     vertex::Normal3f,
00061     vertex::Mark >{};
00062 
00063 class TFace   : public Face<   TUsedTypes,
00064     face::VertexRef,    // three pointers to vertices
00065     face::Normal3f,             // normal
00066     face::BitFlags,             // flags
00067     face::FFAdj                 // three pointers to adjacent faces
00068 > {};
00069 
00070 /* the mesh is a container of vertices and a container of faces */
00071 class TMesh   : public vcg::tri::TriMesh< vector<TVertex>, vector<TFace> > {};
00072 
00073 
00074 /* Definition of a mesh of polygons that also supports half-edges
00075 */
00076 class PFace;
00077 class PVertex;
00078 class PHEdge;
00079 class PEdge;
00080 
00081 struct PUsedTypes: public vcg::UsedTypes<vcg::Use<PVertex>  ::AsVertexType,
00082                                             vcg::Use<PEdge>     ::AsEdgeType,
00083                                             vcg::Use<PHEdge>::AsHEdgeType,
00084                                             vcg::Use<PFace>     ::AsFaceType
00085                                             >{};
00086 
00087 //class DummyEdge: public vcg::Edge<PolyUsedTypes>{};
00088 class PVertex:public vcg::Vertex<       PUsedTypes,
00089                                         vcg::vertex::Coord3f,
00090                                         vcg::vertex::Normal3f,
00091                                         vcg::vertex::Mark,
00092                                         vcg::vertex::BitFlags,
00093                                         vcg::vertex::VHAdj>{} ;
00094 
00095 class PEdge : public Edge<PUsedTypes>{};
00096 class PHEdge : public HEdge< PUsedTypes, hedge::BitFlags,
00097     //hedge::HFAdj,             // pointer to the face
00098     //hedge::HOppAdj,   // pointer to the opposite edge
00099     //hedge::HVAdj,             // pointer to the vertex
00100     //hedge::HNextAdj,  // pointer to the next halfedge
00101     hedge::HEdgeData            // the previous 4 components (just more handy, you can comment this and uncomment the previous four lines)
00102     //,hedge::HPrevAdj  // pointer to the previous halfedge
00103 >{};
00104 
00105 class PFace:public vcg::Face<
00106      PUsedTypes
00107     ,vcg::face::PolyInfo // this is necessary  if you use component in vcg/simplex/face/component_polygon.h
00108                          // It says "this class is a polygon and the memory for its components (e.g. pointer to its vertices
00109                          // will be allocated dynamically")
00110     ,vcg::face::PFVAdj   // Pointer to the vertices (just like FVAdj )
00111     ,vcg::face::PFVAdj
00112     ,vcg::face::PFFAdj   // Pointer to edge-adjacent face (just like FFAdj )
00113     ,vcg::face::PFHAdj   // Pointer its half -edges  ( you may need this if you use half edges)
00114     ,vcg::face::BitFlags // bit flags
00115     ,vcg::face::Normal3f // normal
00116 > {};
00117 
00118 class PMesh: public
00119     vcg::tri::TriMesh<
00120     std::vector<PVertex>,       // the vector of vertices
00121     std::vector<PFace >,                                                // the vector of faces
00122     std::vector<PHEdge>         ,                                               // the vector of edges
00123     std::vector<PEdge>                                                          // the vector of edges
00124     >{};
00125 
00126 PMesh pm;
00127 TMesh tm0;
00128 
00129 int     main(int argc, char *argv[]) {
00130 
00131     int loadmask;
00132 
00133 if(true){
00134     /*
00135     first way:
00136     1) read a polygon mesh that will be automatically converted in a triangle mesh tagging
00137       the internal edges (i.e. the edges that have been added for triangulating the polygons)
00138     2) make some cleaning
00139     3) import the tagged triangle mesh in a polygon mesh
00140     */
00141 //      vcg::tri::io::ImporterOBJ<CMesh>::Open(mesh,argv[1],loadmask);
00142 //    vcg::tri::io::ImporterOFF<TMesh>::Open(tm0,argv[1],loadmask);
00143     vcg::tri::Hexahedron(tm0);
00144     vcg::tri::Clean<TMesh>::RemoveUnreferencedVertex(tm0);
00145     vcg::tri::Clean<TMesh>::RemoveZeroAreaFace(tm0);
00146     vcg::tri::UpdateTopology<TMesh>::FaceFace(tm0);
00147     vcg::tri::Clean<TMesh>::RemoveNonManifoldFace(tm0);
00148     vcg::tri::UpdateTopology<TMesh>::FaceFace(tm0);
00149     assert(vcg::tri::Clean<TMesh>::CountNonManifoldEdgeFF(tm0)==0);
00150     assert(vcg::tri::Clean<TMesh>::CountNonManifoldVertexFF(tm0)==0);
00151 
00152     // create a polygon meshe from a trimesh with tagged faces
00153     vcg::tri::PolygonSupport<TMesh,PMesh>::ImportFromTriMesh(pm,tm0);
00154 }
00155 else
00156 {
00157     /* second way:
00158     Load into a polygon mesh straight away.
00159     */
00160     vcg::tri::io::ImporterOBJ<PMesh>::Open(pm,argv[1],loadmask);
00161     vcg::tri::UpdateTopology<PMesh>::FaceFace(pm);
00162     vcg::tri::Clean<PMesh>::RemoveNonManifoldFace(pm);
00163     vcg::tri::UpdateTopology<PMesh>::FaceFace(pm);
00164     assert(vcg::tri::Clean<PMesh>::CountNonManifoldEdgeFF(pm));
00165 }
00166 
00167 
00168     // compute the half edges because I'm a half-edge programmer
00169     vcg::tri::UpdateHalfEdges<PMesh>::FromIndexed(pm);
00170 
00171     // .... my half edge based code ......
00172 
00173     // check for consistency
00174     assert(vcg::tri::UpdateHalfEdges<PMesh>::CheckConsistency(pm));
00175 
00176     int size =  pm.face.size();
00177 
00178     // add a face to each face with more than 3 vertices ( just one pass)
00179 
00180     for(int i = 0; i < size; ++i)
00181         if(!(pm.face[i].IsD()))
00182         if(pm.face[i].VN()>3){
00183             PMesh::HEdgePointer ef =  pm.face[i].FHp();
00184             PMesh::HEdgePointer ef1 = ef -> HNp();
00185             ef1 = ef1->HNp();
00186             vcg::tri::UpdateHalfEdges<PMesh>::AddHEdge(pm, ef, ef1 );
00187         }
00188     assert(vcg::tri::UpdateHalfEdges<PMesh>::CheckConsistency(pm));
00189     size =  pm.face.size();
00190 
00191     // remove an edge for each face
00192 
00193     for(int i = 0; i < size; ++i)
00194         if(!(pm.face[i].IsD() ))
00195         {
00196             PMesh::HEdgePointer ef =  pm.face[i].FHp();
00197             if( ef->HOp()->HFp() !=NULL){
00198                 vcg::tri::UpdateHalfEdges<PMesh>::RemoveHEdge(pm,ef);
00199             }
00200         }
00201 
00202     // check for consistency
00203     assert(vcg::tri::UpdateHalfEdges<PMesh>::CheckConsistency(pm));
00204 
00205     // recompute indexed data structure from the half edge data structure
00206 //    vcg::tri::UpdateIndexed<PMesh>::FromHalfEdges(pm );
00207 
00208     // create a triangle mesh from a polygon mesh
00209     TMesh tm1;
00210     vcg::tri::PolygonSupport<TMesh,PMesh>::ImportFromPolyMesh(tm1,pm);
00211 
00212     vcg::tri::io::PlyInfo pi;
00213     vcg::tri::io::ExporterPLY<TMesh>::Save(tm1,"converted_tri.ply",false,pi);
00214     vcg::tri::io::ExporterPLY<PMesh>::Save(pm,"converted_poly.ply",false,pi);
00215 }
00216 
00217 
00218 


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