planar_polygon_tessellation.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 
00024 #ifndef __VCGLIB_PLANAR_POLYGON_TESSELLATOR
00025 #define __VCGLIB_PLANAR_POLYGON_TESSELLATOR
00026 
00027 #include <assert.h>
00028 #include <vcg/space/segment2.h>
00029 #include <vcg/math/random_generator.h>
00030 
00031 namespace vcg {
00032 
00040         template <class ScalarType> 
00041         bool Cross(      const Point2<ScalarType> & p00,
00042                                  const Point2<ScalarType> & p01,
00043                                  const Point2<ScalarType> & p10,
00044                                  const Point2<ScalarType> & p11)
00045         {
00046                 Point2<ScalarType> vec0 = p01-p00;
00047                 Point2<ScalarType> vec1 = p11-p10;
00048                 if ( ( vec0^ (p11-p00)) *  ( vec0^ (p10 - p00)) >=0) return false;
00049                 if ( ( vec1^ (p01-p10)) *  ( vec1^ (p00 - p10)) >=0) return false;
00050                 return true;
00051         }
00052 
00053         template <class S>
00054         bool Intersect(size_t cur , int v2, std::vector<int> & next, std::vector<Point2<S> > & points2){
00055                 for(size_t i  = 0; i < points2.size();++i)
00056                         if( (next[i]!=-1) && (i!=cur))
00057                                 if( Cross(points2[cur], points2[v2],points2[i],points2[next[i]]))
00058                                         return true;
00059                 return false;
00060         }
00061 
00062 
00063         template <class POINT_CONTAINER>
00064         void TessellatePlanarPolygon2( POINT_CONTAINER &  points2, std::vector<int> & output){
00065                 typedef typename POINT_CONTAINER::value_type Point2x;
00066                 typedef typename Point2x::ScalarType S;
00067                 // tessellate
00068                 //  first very inefficient implementation
00069                 std::vector<int> next,prev;
00070                 for(size_t i = 0; i < points2.size(); ++i) next.push_back((i+1)%points2.size());
00071                 for(size_t i = 0; i < points2.size(); ++i) prev.push_back((i+points2.size()-1)%points2.size());
00072                 int v1,v2;
00073                 // check orientation
00074                 S orient = 0.0;
00075                 for(size_t i = 0 ; i < points2.size(); ++i){
00076                         v1 =  next[i];
00077                         v2 =  next[v1];
00078                         orient+= (points2[v1] - points2[0]) ^ (points2[v2] - points2[0]);
00079                 }
00080                 orient = (orient>0)? 1.0:-1.0;
00081 
00082                 int cur = 0;
00083                 while(output.size()<3*(points2.size()-2)){
00084                         v1 =  next[cur];
00085                         v2 =  next[v1];
00086                         if( ( (orient*((points2[v1] - points2[cur]) ^ (points2[v2] - points2[cur]))) >= 0.0) && 
00087                                   !Intersect(cur, v2,next,points2))
00088                         {
00089                                 // output the face
00090                                 output.push_back(cur);
00091                                 output.push_back(v1);
00092                                 output.push_back(v2);
00093 
00094                                 // readjust the topology
00095                                 next[cur] = v2;
00096                                 prev[v2] = cur;
00097                                 prev[v1] = -1;//unnecessary
00098                                 next[v1] = -1;//unnecessary
00099                         } 
00100                         else
00101                                 do{cur = (cur+1)%points2.size();} while(next[cur]==-1);
00102                 }
00103         }
00104 
00112         template <class POINT_CONTAINER>
00113         void TessellatePlanarPolygon3( POINT_CONTAINER &  points, std::vector<int> & output){
00114                 typedef typename POINT_CONTAINER::value_type Point3x;
00115                 typedef typename Point3x::ScalarType S;
00116                 Point3x n;
00117 
00118                 math::SubtractiveRingRNG rg;
00119                 size_t i12[2];
00120                 S bestsn = -1.0;
00121                 Point3x bestn,u,v;
00122                 for(size_t i  =0; i < points.size();++i){
00123                         for(size_t j = 0; j < 2; ++j){ i12[j] = i; while(i12[j]==i) i12[j] = rg.generate(points.size()-1);}
00124                         n = (points[i12[0]]-points[i])^(points[i12[1]]-points[i]);
00125                         S sn = n.SquaredNorm();
00126                         if(sn > bestsn){ bestsn = sn; bestn = n;} 
00127                 }
00128                 
00129                 GetUV(n,u,v);
00130                 // project the coordinates
00131                 std::vector<Point2<S> > points2;
00132                 for(size_t i = 0; i < points.size(); ++i){
00133                         Point3x & p = points[i];
00134                         points2.push_back(Point2<S>(p*u,p*v));
00135                 }
00136                 TessellatePlanarPolygon2( points2,output);
00137         }
00138 
00140 } // end namespace
00141 #endif


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