polypartition.h
Go to the documentation of this file.
00001 //Copyright (C) 2011 by Ivan Fratric
00002 //
00003 //Permission is hereby granted, free of charge, to any person obtaining a copy
00004 //of this software and associated documentation files (the "Software"), to deal
00005 //in the Software without restriction, including without limitation the rights
00006 //to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
00007 //copies of the Software, and to permit persons to whom the Software is
00008 //furnished to do so, subject to the following conditions:
00009 //
00010 //The above copyright notice and this permission notice shall be included in
00011 //all copies or substantial portions of the Software.
00012 //
00013 //THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
00014 //IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
00015 //FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
00016 //AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
00017 //LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
00018 //OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
00019 //THE SOFTWARE.
00020 
00021 
00022 #include <list>
00023 using namespace std;
00024 
00025 typedef double tppl_float;
00026 
00027 #define TPPL_CCW 1
00028 #define TPPL_CW -1
00029 
00030 //2D point structure
00031 struct TPPLPoint {
00032         tppl_float x;
00033         tppl_float y;
00034 
00035         TPPLPoint operator + (const TPPLPoint& p) const {
00036                 TPPLPoint r;
00037                 r.x = x + p.x;
00038                 r.y = y + p.y;
00039                 return r;
00040         }
00041 
00042         TPPLPoint operator - (const TPPLPoint& p) const {
00043                 TPPLPoint r;
00044                 r.x = x - p.x;
00045                 r.y = y - p.y;
00046                 return r;
00047         }
00048 
00049         TPPLPoint operator * (const tppl_float f ) const {
00050                 TPPLPoint r;
00051                 r.x = x*f;
00052                 r.y = y*f;
00053                 return r;
00054         }
00055 
00056         TPPLPoint operator / (const tppl_float f ) const {
00057                 TPPLPoint r;
00058                 r.x = x/f;
00059                 r.y = y/f;
00060                 return r;
00061         }
00062 
00063         bool operator==(const TPPLPoint& p) const {
00064                 if((x == p.x)&&(y==p.y)) return true;
00065                 else return false;
00066         }
00067 
00068         bool operator!=(const TPPLPoint& p) const {
00069                 if((x == p.x)&&(y==p.y)) return false;
00070                 else return true;
00071         }
00072 };
00073 
00074 //Polygon implemented as an array of points with a 'hole' flag
00075 class TPPLPoly {
00076 protected:
00077 
00078         TPPLPoint *points;
00079         long numpoints;
00080         bool hole;
00081 
00082 public:
00083 
00084         //constructors/destructors
00085         TPPLPoly();
00086         ~TPPLPoly();
00087 
00088         TPPLPoly(const TPPLPoly &src);
00089         TPPLPoly& operator=(const TPPLPoly &src);
00090 
00091         //getters and setters
00092         long GetNumPoints() {
00093                 return numpoints;
00094         }
00095 
00096         bool IsHole() {
00097                 return hole;
00098         }
00099 
00100         void SetHole(bool hole) {
00101                 this->hole = hole;
00102         }
00103 
00104         TPPLPoint &GetPoint(long i) {
00105                 return points[i];
00106         }
00107 
00108         TPPLPoint *GetPoints() {
00109                 return points;
00110         }
00111 
00112         TPPLPoint& operator[] (int i) {
00113                 return points[i];       
00114         }
00115 
00116         //clears the polygon points
00117         void Clear();
00118 
00119         //inits the polygon with numpoints vertices
00120         void Init(long numpoints);
00121 
00122         //creates a triangle with points p1,p2,p3
00123         void Triangle(TPPLPoint &p1, TPPLPoint &p2, TPPLPoint &p3);
00124 
00125         //inverts the orfer of vertices
00126         void Invert();
00127 
00128         //returns the orientation of the polygon
00129         //possible values:
00130         //   TPPL_CCW : polygon vertices are in counter-clockwise order
00131         //   TPPL_CW : polygon vertices are in clockwise order
00132         //       0 : the polygon has no (measurable) area
00133         int GetOrientation();
00134 
00135         //sets the polygon orientation
00136         //orientation can be
00137         //   TPPL_CCW : sets vertices in counter-clockwise order
00138         //   TPPL_CW : sets vertices in clockwise order
00139         void SetOrientation(int orientation);
00140 };
00141 
00142 class TPPLPartition {
00143 protected:
00144         struct PartitionVertex {
00145                 bool isActive;
00146                 bool isConvex;
00147                 bool isEar;
00148 
00149                 TPPLPoint p;
00150                 tppl_float angle;
00151                 PartitionVertex *previous;
00152                 PartitionVertex *next;
00153         };
00154 
00155         struct MonotoneVertex {
00156                 TPPLPoint p;
00157                 long previous;
00158                 long next;
00159         };
00160 
00161         class VertexSorter{
00162                 MonotoneVertex *vertices;
00163         public:
00164                 VertexSorter(MonotoneVertex *v) : vertices(v) {}
00165                 bool operator() (long index1, long index2);
00166         };
00167 
00168         struct Diagonal {
00169                 long index1;
00170                 long index2;
00171         };
00172 
00173         //dynamic programming state for minimum-weight triangulation
00174         struct DPState {
00175                 bool visible;
00176                 tppl_float weight;
00177                 long bestvertex;
00178         };
00179 
00180         //dynamic programming state for convex partitioning
00181         struct DPState2 {
00182                 bool visible;
00183                 long weight;
00184                 list<Diagonal> pairs;
00185         };
00186 
00187         //edge that intersects the scanline
00188         struct ScanLineEdge {
00189                 long index;
00190                 TPPLPoint p1;
00191                 TPPLPoint p2;
00192 
00193                 //determines if the edge is to the left of another edge
00194                 bool operator< (const ScanLineEdge & other) const;
00195 
00196                 bool IsConvex(const TPPLPoint& p1, const TPPLPoint& p2, const TPPLPoint& p3) const;
00197         };
00198 
00199         //standard helper functions
00200         bool IsConvex(TPPLPoint& p1, TPPLPoint& p2, TPPLPoint& p3);
00201         bool IsReflex(TPPLPoint& p1, TPPLPoint& p2, TPPLPoint& p3);
00202         bool IsInside(TPPLPoint& p1, TPPLPoint& p2, TPPLPoint& p3, TPPLPoint &p);
00203         
00204         bool InCone(TPPLPoint &p1, TPPLPoint &p2, TPPLPoint &p3, TPPLPoint &p);
00205         bool InCone(PartitionVertex *v, TPPLPoint &p);
00206 
00207         int Intersects(TPPLPoint &p11, TPPLPoint &p12, TPPLPoint &p21, TPPLPoint &p22);
00208 
00209         TPPLPoint Normalize(const TPPLPoint &p);
00210         tppl_float Distance(const TPPLPoint &p1, const TPPLPoint &p2);
00211 
00212         //helper functions for Triangulate_EC
00213         void UpdateVertexReflexity(PartitionVertex *v);
00214         void UpdateVertex(PartitionVertex *v,PartitionVertex *vertices, long numvertices);
00215 
00216         //helper functions for ConvexPartition_OPT
00217         void UpdateState(long a, long b, long w, long i, long j, DPState2 **dpstates);
00218         void TypeA(long i, long j, long k, PartitionVertex *vertices, DPState2 **dpstates);
00219         void TypeB(long i, long j, long k, PartitionVertex *vertices, DPState2 **dpstates);
00220 
00221         //helper functions for MonotonePartition
00222         bool Below(TPPLPoint &p1, TPPLPoint &p2);
00223         void AddDiagonal(MonotoneVertex *vertices, long *numvertices, long index1, long index2);
00224 
00225         //triangulates a monotone polygon, used in Triangulate_MONO
00226         int TriangulateMonotone(TPPLPoly *inPoly, list<TPPLPoly> *triangles);
00227 
00228 public:
00229 
00230         //simple heuristic procedure for removing holes from a list of polygons
00231         //works by creating a diagonal from the rightmost hole vertex to some visible vertex
00232         //time complexity: O(h*(n^2)), h is the number of holes, n is the number of vertices
00233         //space complexity: O(n)
00234         //params:
00235         //   inpolys : a list of polygons that can contain holes
00236         //             vertices of all non-hole polys have to be in counter-clockwise order
00237         //             vertices of all hole polys have to be in clockwise order
00238         //   outpolys : a list of polygons without holes
00239         //returns 1 on success, 0 on failure
00240         int RemoveHoles(list<TPPLPoly> *inpolys, list<TPPLPoly> *outpolys);
00241 
00242         //triangulates a polygon by ear clipping
00243         //time complexity O(n^2), n is the number of vertices
00244         //space complexity: O(n)
00245         //params:
00246         //   poly : an input polygon to be triangulated
00247         //          vertices have to be in counter-clockwise order
00248         //   triangles : a list of triangles (result)
00249         //returns 1 on success, 0 on failure
00250         int Triangulate_EC(TPPLPoly *poly, list<TPPLPoly> *triangles);
00251 
00252         //triangulates a list of polygons that may contain holes by ear clipping algorithm
00253         //first calls RemoveHoles to get rid of the holes, and then Triangulate_EC for each resulting polygon
00254         //time complexity: O(h*(n^2)), h is the number of holes, n is the number of vertices
00255         //space complexity: O(n)
00256         //params:
00257         //   inpolys : a list of polygons to be triangulated (can contain holes)
00258         //             vertices of all non-hole polys have to be in counter-clockwise order
00259         //             vertices of all hole polys have to be in clockwise order
00260         //   triangles : a list of triangles (result)
00261         //returns 1 on success, 0 on failure
00262         int Triangulate_EC(list<TPPLPoly> *inpolys, list<TPPLPoly> *triangles);
00263 
00264         //creates an optimal polygon triangulation in terms of minimal edge length
00265         //time complexity: O(n^3), n is the number of vertices
00266         //space complexity: O(n^2)
00267         //params:
00268         //   poly : an input polygon to be triangulated
00269         //          vertices have to be in counter-clockwise order
00270         //   triangles : a list of triangles (result)
00271         //returns 1 on success, 0 on failure
00272         int Triangulate_OPT(TPPLPoly *poly, list<TPPLPoly> *triangles);
00273 
00274         //triangulates a polygons by firstly partitioning it into monotone polygons
00275         //time complexity: O(n*log(n)), n is the number of vertices
00276         //space complexity: O(n)
00277         //params:
00278         //   poly : an input polygon to be triangulated
00279         //          vertices have to be in counter-clockwise order
00280         //   triangles : a list of triangles (result)
00281         //returns 1 on success, 0 on failure
00282         int Triangulate_MONO(TPPLPoly *poly, list<TPPLPoly> *triangles);
00283 
00284         //triangulates a list of polygons by firstly partitioning them into monotone polygons
00285         //time complexity: O(n*log(n)), n is the number of vertices
00286         //space complexity: O(n)
00287         //params:
00288         //   inpolys : a list of polygons to be triangulated (can contain holes)
00289         //             vertices of all non-hole polys have to be in counter-clockwise order
00290         //             vertices of all hole polys have to be in clockwise order
00291         //   triangles : a list of triangles (result)
00292         //returns 1 on success, 0 on failure
00293         int Triangulate_MONO(list<TPPLPoly> *inpolys, list<TPPLPoly> *triangles);
00294 
00295         //creates a monotone partition of a list of polygons that can contain holes
00296         //time complexity: O(n*log(n)), n is the number of vertices
00297         //space complexity: O(n)
00298         //params:
00299         //   inpolys : a list of polygons to be triangulated (can contain holes)
00300         //             vertices of all non-hole polys have to be in counter-clockwise order
00301         //             vertices of all hole polys have to be in clockwise order
00302         //   monotonePolys : a list of monotone polygons (result)
00303         //returns 1 on success, 0 on failure
00304         int MonotonePartition(list<TPPLPoly> *inpolys, list<TPPLPoly> *monotonePolys);
00305 
00306         //partitions a polygon into convex polygons by using Hertel-Mehlhorn algorithm
00307         //the algorithm gives at most four times the number of parts as the optimal algorithm
00308         //however, in practice it works much better than that and often gives optimal partition
00309         //uses triangulation obtained by ear clipping as intermediate result
00310         //time complexity O(n^2), n is the number of vertices
00311         //space complexity: O(n)
00312         //params:
00313         //   poly : an input polygon to be partitioned
00314         //          vertices have to be in counter-clockwise order
00315         //   parts : resulting list of convex polygons
00316         //returns 1 on success, 0 on failure
00317         int ConvexPartition_HM(TPPLPoly *poly, list<TPPLPoly> *parts);
00318 
00319         //partitions a list of polygons into convex parts by using Hertel-Mehlhorn algorithm
00320         //the algorithm gives at most four times the number of parts as the optimal algorithm
00321         //however, in practice it works much better than that and often gives optimal partition
00322         //uses triangulation obtained by ear clipping as intermediate result
00323         //time complexity O(n^2), n is the number of vertices
00324         //space complexity: O(n)
00325         //params:
00326         //   inpolys : an input list of polygons to be partitioned
00327         //             vertices of all non-hole polys have to be in counter-clockwise order
00328         //             vertices of all hole polys have to be in clockwise order
00329         //   parts : resulting list of convex polygons
00330         //returns 1 on success, 0 on failure
00331         int ConvexPartition_HM(list<TPPLPoly> *inpolys, list<TPPLPoly> *parts);
00332 
00333         //optimal convex partitioning (in terms of number of resulting convex polygons)
00334         //using the Keil-Snoeyink algorithm
00335         //M. Keil, J. Snoeyink, "On the time bound for convex decomposition of simple polygons", 1998
00336         //time complexity O(n^3), n is the number of vertices
00337         //space complexity: O(n^3)
00338         //   poly : an input polygon to be partitioned
00339         //          vertices have to be in counter-clockwise order
00340         //   parts : resulting list of convex polygons
00341         //returns 1 on success, 0 on failure
00342         int ConvexPartition_OPT(TPPLPoly *poly, list<TPPLPoly> *parts);
00343 };


polypartition
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:02:14