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         int id;
00035 
00036         TPPLPoint operator + (const TPPLPoint& p) const {
00037                 TPPLPoint r;
00038                 r.x = x + p.x;
00039                 r.y = y + p.y;
00040                 return r;
00041         }
00042 
00043         TPPLPoint operator - (const TPPLPoint& p) const {
00044                 TPPLPoint r;
00045                 r.x = x - p.x;
00046                 r.y = y - p.y;
00047                 return r;
00048         }
00049 
00050         TPPLPoint operator * (const tppl_float f ) const {
00051                 TPPLPoint r;
00052                 r.x = x*f;
00053                 r.y = y*f;
00054                 return r;
00055         }
00056 
00057         TPPLPoint operator / (const tppl_float f ) const {
00058                 TPPLPoint r;
00059                 r.x = x/f;
00060                 r.y = y/f;
00061                 return r;
00062         }
00063 
00064         bool operator==(const TPPLPoint& p) const {
00065                 if((x == p.x)&&(y==p.y)) return true;
00066                 else return false;
00067         }
00068 
00069         bool operator!=(const TPPLPoint& p) const {
00070                 if((x == p.x)&&(y==p.y)) return false;
00071                 else return true;
00072         }
00073 };
00074 
00075 //Polygon implemented as an array of points with a 'hole' flag
00076 class TPPLPoly {
00077 protected:
00078 
00079         TPPLPoint *points;
00080         long numpoints;
00081         bool hole;
00082 
00083 public:
00084 
00085         //constructors/destructors
00086         TPPLPoly();
00087         ~TPPLPoly();
00088 
00089         TPPLPoly(const TPPLPoly &src);
00090         TPPLPoly& operator=(const TPPLPoly &src);
00091 
00092         //getters and setters
00093         long GetNumPoints() {
00094                 return numpoints;
00095         }
00096 
00097         bool IsHole() {
00098                 return hole;
00099         }
00100 
00101         void SetHole(bool hole) {
00102                 this->hole = hole;
00103         }
00104 
00105         TPPLPoint &GetPoint(long i) {
00106                 return points[i];
00107         }
00108 
00109         TPPLPoint *GetPoints() {
00110                 return points;
00111         }
00112 
00113         TPPLPoint& operator[] (int i) {
00114                 return points[i];       
00115         }
00116 
00117         //clears the polygon points
00118         void Clear();
00119 
00120         //inits the polygon with numpoints vertices
00121         void Init(long numpoints);
00122 
00123         //creates a triangle with points p1,p2,p3
00124         void Triangle(TPPLPoint &p1, TPPLPoint &p2, TPPLPoint &p3);
00125 
00126         //inverts the orfer of vertices
00127         void Invert();
00128 
00129         //returns the orientation of the polygon
00130         //possible values:
00131         //   TPPL_CCW : polygon vertices are in counter-clockwise order
00132         //   TPPL_CW : polygon vertices are in clockwise order
00133         //       0 : the polygon has no (measurable) area
00134         int GetOrientation();
00135 
00136         //sets the polygon orientation
00137         //orientation can be
00138         //   TPPL_CCW : sets vertices in counter-clockwise order
00139         //   TPPL_CW : sets vertices in clockwise order
00140         void SetOrientation(int orientation);
00141 };
00142 
00143 class TPPLPartition {
00144 protected:
00145         struct PartitionVertex {
00146                 bool isActive;
00147                 bool isConvex;
00148                 bool isEar;
00149 
00150                 TPPLPoint p;
00151                 tppl_float angle;
00152                 PartitionVertex *previous;
00153                 PartitionVertex *next;
00154         };
00155 
00156         struct MonotoneVertex {
00157                 TPPLPoint p;
00158                 long previous;
00159                 long next;
00160         };
00161 
00162         class VertexSorter{
00163                 MonotoneVertex *vertices;
00164         public:
00165                 VertexSorter(MonotoneVertex *v) : vertices(v) {}
00166                 bool operator() (long index1, long index2);
00167         };
00168 
00169         struct Diagonal {
00170                 long index1;
00171                 long index2;
00172         };
00173 
00174         //dynamic programming state for minimum-weight triangulation
00175         struct DPState {
00176                 bool visible;
00177                 tppl_float weight;
00178                 long bestvertex;
00179         };
00180 
00181         //dynamic programming state for convex partitioning
00182         struct DPState2 {
00183                 bool visible;
00184                 long weight;
00185                 list<Diagonal> pairs;
00186         };
00187 
00188         //edge that intersects the scanline
00189         struct ScanLineEdge {
00190                 long index;
00191                 TPPLPoint p1;
00192                 TPPLPoint p2;
00193 
00194                 //determines if the edge is to the left of another edge
00195                 bool operator< (const ScanLineEdge & other) const;
00196 
00197                 bool IsConvex(const TPPLPoint& p1, const TPPLPoint& p2, const TPPLPoint& p3) const;
00198         };
00199 
00200         //standard helper functions
00201         bool IsConvex(TPPLPoint& p1, TPPLPoint& p2, TPPLPoint& p3);
00202         bool IsReflex(TPPLPoint& p1, TPPLPoint& p2, TPPLPoint& p3);
00203         bool IsInside(TPPLPoint& p1, TPPLPoint& p2, TPPLPoint& p3, TPPLPoint &p);
00204         
00205         bool InCone(TPPLPoint &p1, TPPLPoint &p2, TPPLPoint &p3, TPPLPoint &p);
00206         bool InCone(PartitionVertex *v, TPPLPoint &p);
00207 
00208         int Intersects(TPPLPoint &p11, TPPLPoint &p12, TPPLPoint &p21, TPPLPoint &p22);
00209 
00210         TPPLPoint Normalize(const TPPLPoint &p);
00211         tppl_float Distance(const TPPLPoint &p1, const TPPLPoint &p2);
00212 
00213         //helper functions for Triangulate_EC
00214         void UpdateVertexReflexity(PartitionVertex *v);
00215         void UpdateVertex(PartitionVertex *v,PartitionVertex *vertices, long numvertices);
00216 
00217         //helper functions for ConvexPartition_OPT
00218         void UpdateState(long a, long b, long w, long i, long j, DPState2 **dpstates);
00219         void TypeA(long i, long j, long k, PartitionVertex *vertices, DPState2 **dpstates);
00220         void TypeB(long i, long j, long k, PartitionVertex *vertices, DPState2 **dpstates);
00221 
00222         //helper functions for MonotonePartition
00223         bool Below(TPPLPoint &p1, TPPLPoint &p2);
00224         void AddDiagonal(MonotoneVertex *vertices, long *numvertices, long index1, long index2);
00225 
00226         //triangulates a monotone polygon, used in Triangulate_MONO
00227         int TriangulateMonotone(TPPLPoly *inPoly, list<TPPLPoly> *triangles);
00228 
00229 public:
00230 
00231         //simple heuristic procedure for removing holes from a list of polygons
00232         //works by creating a diagonal from the rightmost hole vertex to some visible vertex
00233         //time complexity: O(h*(n^2)), h is the number of holes, n is the number of vertices
00234         //space complexity: O(n)
00235         //params:
00236         //   inpolys : a list of polygons that can contain holes
00237         //             vertices of all non-hole polys have to be in counter-clockwise order
00238         //             vertices of all hole polys have to be in clockwise order
00239         //   outpolys : a list of polygons without holes
00240         //returns 1 on success, 0 on failure
00241         int RemoveHoles(list<TPPLPoly> *inpolys, list<TPPLPoly> *outpolys);
00242 
00243         //triangulates a polygon by ear clipping
00244         //time complexity O(n^2), n is the number of vertices
00245         //space complexity: O(n)
00246         //params:
00247         //   poly : an input polygon to be triangulated
00248         //          vertices have to be in counter-clockwise order
00249         //   triangles : a list of triangles (result)
00250         //returns 1 on success, 0 on failure
00251         int Triangulate_EC(TPPLPoly *poly, list<TPPLPoly> *triangles);
00252 
00253         //triangulates a list of polygons that may contain holes by ear clipping algorithm
00254         //first calls RemoveHoles to get rid of the holes, and then Triangulate_EC for each resulting polygon
00255         //time complexity: O(h*(n^2)), h is the number of holes, n is the number of vertices
00256         //space complexity: O(n)
00257         //params:
00258         //   inpolys : a list of polygons to be triangulated (can contain holes)
00259         //             vertices of all non-hole polys have to be in counter-clockwise order
00260         //             vertices of all hole polys have to be in clockwise order
00261         //   triangles : a list of triangles (result)
00262         //returns 1 on success, 0 on failure
00263         int Triangulate_EC(list<TPPLPoly> *inpolys, list<TPPLPoly> *triangles);
00264 
00265         //creates an optimal polygon triangulation in terms of minimal edge length
00266         //time complexity: O(n^3), n is the number of vertices
00267         //space complexity: O(n^2)
00268         //params:
00269         //   poly : an input polygon to be triangulated
00270         //          vertices have to be in counter-clockwise order
00271         //   triangles : a list of triangles (result)
00272         //returns 1 on success, 0 on failure
00273         int Triangulate_OPT(TPPLPoly *poly, list<TPPLPoly> *triangles);
00274 
00275         //triangulates a polygons by firstly partitioning it into monotone polygons
00276         //time complexity: O(n*log(n)), n is the number of vertices
00277         //space complexity: O(n)
00278         //params:
00279         //   poly : an input polygon to be triangulated
00280         //          vertices have to be in counter-clockwise order
00281         //   triangles : a list of triangles (result)
00282         //returns 1 on success, 0 on failure
00283         int Triangulate_MONO(TPPLPoly *poly, list<TPPLPoly> *triangles);
00284 
00285         //triangulates a list of polygons by firstly partitioning them into monotone polygons
00286         //time complexity: O(n*log(n)), n is the number of vertices
00287         //space complexity: O(n)
00288         //params:
00289         //   inpolys : a list of polygons to be triangulated (can contain holes)
00290         //             vertices of all non-hole polys have to be in counter-clockwise order
00291         //             vertices of all hole polys have to be in clockwise order
00292         //   triangles : a list of triangles (result)
00293         //returns 1 on success, 0 on failure
00294         int Triangulate_MONO(list<TPPLPoly> *inpolys, list<TPPLPoly> *triangles);
00295 
00296         //creates a monotone partition of a list of polygons that can contain holes
00297         //time complexity: O(n*log(n)), n is the number of vertices
00298         //space complexity: O(n)
00299         //params:
00300         //   inpolys : a list of polygons to be triangulated (can contain holes)
00301         //             vertices of all non-hole polys have to be in counter-clockwise order
00302         //             vertices of all hole polys have to be in clockwise order
00303         //   monotonePolys : a list of monotone polygons (result)
00304         //returns 1 on success, 0 on failure
00305         int MonotonePartition(list<TPPLPoly> *inpolys, list<TPPLPoly> *monotonePolys);
00306 
00307         //partitions a polygon into convex polygons by using Hertel-Mehlhorn algorithm
00308         //the algorithm gives at most four times the number of parts as the optimal algorithm
00309         //however, in practice it works much better than that and often gives optimal partition
00310         //uses triangulation obtained by ear clipping as intermediate result
00311         //time complexity O(n^2), n is the number of vertices
00312         //space complexity: O(n)
00313         //params:
00314         //   poly : an input polygon to be partitioned
00315         //          vertices have to be in counter-clockwise order
00316         //   parts : resulting list of convex polygons
00317         //returns 1 on success, 0 on failure
00318         int ConvexPartition_HM(TPPLPoly *poly, list<TPPLPoly> *parts);
00319 
00320         //partitions a list of polygons into convex parts by using Hertel-Mehlhorn algorithm
00321         //the algorithm gives at most four times the number of parts as the optimal algorithm
00322         //however, in practice it works much better than that and often gives optimal partition
00323         //uses triangulation obtained by ear clipping as intermediate result
00324         //time complexity O(n^2), n is the number of vertices
00325         //space complexity: O(n)
00326         //params:
00327         //   inpolys : an input list of polygons to be partitioned
00328         //             vertices of all non-hole polys have to be in counter-clockwise order
00329         //             vertices of all hole polys have to be in clockwise order
00330         //   parts : resulting list of convex polygons
00331         //returns 1 on success, 0 on failure
00332         int ConvexPartition_HM(list<TPPLPoly> *inpolys, list<TPPLPoly> *parts);
00333 
00334         //optimal convex partitioning (in terms of number of resulting convex polygons)
00335         //using the Keil-Snoeyink algorithm
00336         //M. Keil, J. Snoeyink, "On the time bound for convex decomposition of simple polygons", 1998
00337         //time complexity O(n^3), n is the number of vertices
00338         //space complexity: O(n^3)
00339         //   poly : an input polygon to be partitioned
00340         //          vertices have to be in counter-clockwise order
00341         //   parts : resulting list of convex polygons
00342         //returns 1 on success, 0 on failure
00343         int ConvexPartition_OPT(TPPLPoly *poly, list<TPPLPoly> *parts);
00344 };


srs_env_model_percp
Author(s): Rostislav Hulik (ihulik@fit.vutbr.cz), Tomas Hodan, Michal Spanel (spanel@fit.vutbr.cz)
autogenerated on Sun Jan 5 2014 11:51:56