Welcome to mirror list, hosted at ThFree Co, Russian Federation.

github.com/prusa3d/PrusaSlicer.git - Unnamed repository; edit this file 'description' to name the repository.
summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
Diffstat (limited to 'src/poly2tri/sweep')
-rw-r--r--src/poly2tri/sweep/advancing_front.cc108
-rw-r--r--src/poly2tri/sweep/advancing_front.h118
-rw-r--r--src/poly2tri/sweep/cdt.cc71
-rw-r--r--src/poly2tri/sweep/cdt.h105
-rw-r--r--src/poly2tri/sweep/sweep.cc808
-rw-r--r--src/poly2tri/sweep/sweep.h285
-rw-r--r--src/poly2tri/sweep/sweep_context.cc211
-rw-r--r--src/poly2tri/sweep/sweep_context.h186
8 files changed, 1892 insertions, 0 deletions
diff --git a/src/poly2tri/sweep/advancing_front.cc b/src/poly2tri/sweep/advancing_front.cc
new file mode 100644
index 000000000..38723beef
--- /dev/null
+++ b/src/poly2tri/sweep/advancing_front.cc
@@ -0,0 +1,108 @@
+/*
+ * Poly2Tri Copyright (c) 2009-2010, Poly2Tri Contributors
+ * http://code.google.com/p/poly2tri/
+ *
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ *
+ * * Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * * Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * * Neither the name of Poly2Tri nor the names of its contributors may be
+ * used to endorse or promote products derived from this software without specific
+ * prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+ * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR
+ * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
+ * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
+ * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
+ * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
+ * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+#include "advancing_front.h"
+
+namespace p2t {
+
+AdvancingFront::AdvancingFront(Node& head, Node& tail)
+{
+ head_ = &head;
+ tail_ = &tail;
+ search_node_ = &head;
+}
+
+Node* AdvancingFront::LocateNode(double x)
+{
+ Node* node = search_node_;
+
+ if (x < node->value) {
+ while ((node = node->prev) != NULL) {
+ if (x >= node->value) {
+ search_node_ = node;
+ return node;
+ }
+ }
+ } else {
+ while ((node = node->next) != NULL) {
+ if (x < node->value) {
+ search_node_ = node->prev;
+ return node->prev;
+ }
+ }
+ }
+ return NULL;
+}
+
+Node* AdvancingFront::FindSearchNode(double x)
+{
+ (void)x; // suppress compiler warnings "unused parameter 'x'"
+ // TODO: implement BST index
+ return search_node_;
+}
+
+Node* AdvancingFront::LocatePoint(const Point* point)
+{
+ const double px = point->x;
+ Node* node = FindSearchNode(px);
+ const double nx = node->point->x;
+
+ if (px == nx) {
+ if (point != node->point) {
+ // We might have two nodes with same x value for a short time
+ if (point == node->prev->point) {
+ node = node->prev;
+ } else if (point == node->next->point) {
+ node = node->next;
+ } else {
+ assert(0);
+ }
+ }
+ } else if (px < nx) {
+ while ((node = node->prev) != NULL) {
+ if (point == node->point) {
+ break;
+ }
+ }
+ } else {
+ while ((node = node->next) != NULL) {
+ if (point == node->point)
+ break;
+ }
+ }
+ if(node) search_node_ = node;
+ return node;
+}
+
+AdvancingFront::~AdvancingFront()
+{
+}
+
+} \ No newline at end of file
diff --git a/src/poly2tri/sweep/advancing_front.h b/src/poly2tri/sweep/advancing_front.h
new file mode 100644
index 000000000..645dcec97
--- /dev/null
+++ b/src/poly2tri/sweep/advancing_front.h
@@ -0,0 +1,118 @@
+/*
+ * Poly2Tri Copyright (c) 2009-2010, Poly2Tri Contributors
+ * http://code.google.com/p/poly2tri/
+ *
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ *
+ * * Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * * Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * * Neither the name of Poly2Tri nor the names of its contributors may be
+ * used to endorse or promote products derived from this software without specific
+ * prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+ * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR
+ * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
+ * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
+ * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
+ * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
+ * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef ADVANCED_FRONT_H
+#define ADVANCED_FRONT_H
+
+#include "../common/shapes.h"
+
+namespace p2t {
+
+struct Node;
+
+// Advancing front node
+struct Node {
+ Point* point;
+ Triangle* triangle;
+
+ Node* next;
+ Node* prev;
+
+ double value;
+
+ Node(Point& p) : point(&p), triangle(NULL), next(NULL), prev(NULL), value(p.x)
+ {
+ }
+
+ Node(Point& p, Triangle& t) : point(&p), triangle(&t), next(NULL), prev(NULL), value(p.x)
+ {
+ }
+
+};
+
+// Advancing front
+class AdvancingFront {
+public:
+
+AdvancingFront(Node& head, Node& tail);
+// Destructor
+~AdvancingFront();
+
+Node* head();
+void set_head(Node* node);
+Node* tail();
+void set_tail(Node* node);
+Node* search();
+void set_search(Node* node);
+
+/// Locate insertion point along advancing front
+Node* LocateNode(double x);
+
+Node* LocatePoint(const Point* point);
+
+private:
+
+Node* head_, *tail_, *search_node_;
+
+Node* FindSearchNode(double x);
+};
+
+inline Node* AdvancingFront::head()
+{
+ return head_;
+}
+inline void AdvancingFront::set_head(Node* node)
+{
+ head_ = node;
+}
+
+inline Node* AdvancingFront::tail()
+{
+ return tail_;
+}
+inline void AdvancingFront::set_tail(Node* node)
+{
+ tail_ = node;
+}
+
+inline Node* AdvancingFront::search()
+{
+ return search_node_;
+}
+
+inline void AdvancingFront::set_search(Node* node)
+{
+ search_node_ = node;
+}
+
+}
+
+#endif \ No newline at end of file
diff --git a/src/poly2tri/sweep/cdt.cc b/src/poly2tri/sweep/cdt.cc
new file mode 100644
index 000000000..09d088ae3
--- /dev/null
+++ b/src/poly2tri/sweep/cdt.cc
@@ -0,0 +1,71 @@
+/*
+ * Poly2Tri Copyright (c) 2009-2010, Poly2Tri Contributors
+ * http://code.google.com/p/poly2tri/
+ *
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ *
+ * * Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * * Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * * Neither the name of Poly2Tri nor the names of its contributors may be
+ * used to endorse or promote products derived from this software without specific
+ * prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+ * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR
+ * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
+ * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
+ * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
+ * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
+ * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+#include "cdt.h"
+
+namespace p2t {
+
+CDT::CDT(const std::vector<Point*>& polyline)
+{
+ sweep_context_ = new SweepContext(polyline);
+ sweep_ = new Sweep;
+}
+
+void CDT::AddHole(const std::vector<Point*>& polyline)
+{
+ sweep_context_->AddHole(polyline);
+}
+
+void CDT::AddPoint(Point* point) {
+ sweep_context_->AddPoint(point);
+}
+
+void CDT::Triangulate()
+{
+ sweep_->Triangulate(*sweep_context_);
+}
+
+std::vector<p2t::Triangle*> CDT::GetTriangles()
+{
+ return sweep_context_->GetTriangles();
+}
+
+std::list<p2t::Triangle*> CDT::GetMap()
+{
+ return sweep_context_->GetMap();
+}
+
+CDT::~CDT()
+{
+ delete sweep_context_;
+ delete sweep_;
+}
+
+} \ No newline at end of file
diff --git a/src/poly2tri/sweep/cdt.h b/src/poly2tri/sweep/cdt.h
new file mode 100644
index 000000000..ea3286d9a
--- /dev/null
+++ b/src/poly2tri/sweep/cdt.h
@@ -0,0 +1,105 @@
+/*
+ * Poly2Tri Copyright (c) 2009-2010, Poly2Tri Contributors
+ * http://code.google.com/p/poly2tri/
+ *
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ *
+ * * Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * * Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * * Neither the name of Poly2Tri nor the names of its contributors may be
+ * used to endorse or promote products derived from this software without specific
+ * prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+ * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR
+ * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
+ * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
+ * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
+ * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
+ * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef CDT_H
+#define CDT_H
+
+#include "advancing_front.h"
+#include "sweep_context.h"
+#include "sweep.h"
+
+/**
+ *
+ * @author Mason Green <mason.green@gmail.com>
+ *
+ */
+
+namespace p2t {
+
+class CDT
+{
+public:
+
+ /**
+ * Constructor - add polyline with non repeating points
+ *
+ * @param polyline
+ */
+ CDT(const std::vector<Point*>& polyline);
+
+ /**
+ * Destructor - clean up memory
+ */
+ ~CDT();
+
+ /**
+ * Add a hole
+ *
+ * @param polyline
+ */
+ void AddHole(const std::vector<Point*>& polyline);
+
+ /**
+ * Add a steiner point
+ *
+ * @param point
+ */
+ void AddPoint(Point* point);
+
+ /**
+ * Triangulate - do this AFTER you've added the polyline, holes, and Steiner points
+ */
+ void Triangulate();
+
+ /**
+ * Get CDT triangles
+ */
+ std::vector<Triangle*> GetTriangles();
+
+ /**
+ * Get triangle map
+ */
+ std::list<Triangle*> GetMap();
+
+ private:
+
+ /**
+ * Internals
+ */
+
+ SweepContext* sweep_context_;
+ Sweep* sweep_;
+
+};
+
+}
+
+#endif \ No newline at end of file
diff --git a/src/poly2tri/sweep/sweep.cc b/src/poly2tri/sweep/sweep.cc
new file mode 100644
index 000000000..8d2b576e8
--- /dev/null
+++ b/src/poly2tri/sweep/sweep.cc
@@ -0,0 +1,808 @@
+/*
+ * Poly2Tri Copyright (c) 2009-2010, Poly2Tri Contributors
+ * http://code.google.com/p/poly2tri/
+ *
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ *
+ * * Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * * Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * * Neither the name of Poly2Tri nor the names of its contributors may be
+ * used to endorse or promote products derived from this software without specific
+ * prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+ * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR
+ * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
+ * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
+ * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
+ * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
+ * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+#include <stdexcept>
+#include "sweep.h"
+#include "sweep_context.h"
+#include "advancing_front.h"
+#include "../common/utils.h"
+
+namespace p2t {
+
+// Triangulate simple polygon with holes
+void Sweep::Triangulate(SweepContext& tcx)
+{
+ tcx.InitTriangulation();
+ tcx.CreateAdvancingFront(nodes_);
+ // Sweep points; build mesh
+ SweepPoints(tcx);
+ // Clean up
+ FinalizationPolygon(tcx);
+}
+
+void Sweep::SweepPoints(SweepContext& tcx)
+{
+ for (size_t i = 1; i < tcx.point_count(); i++) {
+ Point& point = *tcx.GetPoint(i);
+ Node* node = &PointEvent(tcx, point);
+ for (unsigned int i = 0; i < point.edge_list.size(); i++) {
+ EdgeEvent(tcx, point.edge_list[i], node);
+ }
+ }
+}
+
+void Sweep::FinalizationPolygon(SweepContext& tcx)
+{
+ // Get an Internal triangle to start with
+ Triangle* t = tcx.front()->head()->next->triangle;
+ Point* p = tcx.front()->head()->next->point;
+ while (!t->GetConstrainedEdgeCW(*p)) {
+ t = t->NeighborCCW(*p);
+ }
+
+ // Collect interior triangles constrained by edges
+ tcx.MeshClean(*t);
+}
+
+Node& Sweep::PointEvent(SweepContext& tcx, Point& point)
+{
+ Node& node = tcx.LocateNode(point);
+ Node& new_node = NewFrontTriangle(tcx, point, node);
+
+ // Only need to check +epsilon since point never have smaller
+ // x value than node due to how we fetch nodes from the front
+ if (point.x <= node.point->x + EPSILON) {
+ Fill(tcx, node);
+ }
+
+ //tcx.AddNode(new_node);
+
+ FillAdvancingFront(tcx, new_node);
+ return new_node;
+}
+
+void Sweep::EdgeEvent(SweepContext& tcx, Edge* edge, Node* node)
+{
+ tcx.edge_event.constrained_edge = edge;
+ tcx.edge_event.right = (edge->p->x > edge->q->x);
+
+ if (IsEdgeSideOfTriangle(*node->triangle, *edge->p, *edge->q)) {
+ return;
+ }
+
+ // For now we will do all needed filling
+ // TODO: integrate with flip process might give some better performance
+ // but for now this avoid the issue with cases that needs both flips and fills
+ FillEdgeEvent(tcx, edge, node);
+ EdgeEvent(tcx, *edge->p, *edge->q, node->triangle, *edge->q);
+}
+
+void Sweep::EdgeEvent(SweepContext& tcx, Point& ep, Point& eq, Triangle* triangle, Point& point)
+{
+ if (IsEdgeSideOfTriangle(*triangle, ep, eq)) {
+ return;
+ }
+
+ Point* p1 = triangle->PointCCW(point);
+ Orientation o1 = Orient2d(eq, *p1, ep);
+ if (o1 == COLLINEAR) {
+ if( triangle->Contains(&eq, p1)) {
+ triangle->MarkConstrainedEdge(&eq, p1 );
+ // We are modifying the constraint maybe it would be better to
+ // not change the given constraint and just keep a variable for the new constraint
+ tcx.edge_event.constrained_edge->q = p1;
+ triangle = &triangle->NeighborAcross(point);
+ EdgeEvent( tcx, ep, *p1, triangle, *p1 );
+ } else {
+ std::runtime_error("EdgeEvent - collinear points not supported");
+ assert(0);
+ }
+ return;
+ }
+
+ Point* p2 = triangle->PointCW(point);
+ Orientation o2 = Orient2d(eq, *p2, ep);
+ if (o2 == COLLINEAR) {
+ if( triangle->Contains(&eq, p2)) {
+ triangle->MarkConstrainedEdge(&eq, p2 );
+ // We are modifying the constraint maybe it would be better to
+ // not change the given constraint and just keep a variable for the new constraint
+ tcx.edge_event.constrained_edge->q = p2;
+ triangle = &triangle->NeighborAcross(point);
+ EdgeEvent( tcx, ep, *p2, triangle, *p2 );
+ } else {
+ std::runtime_error("EdgeEvent - collinear points not supported");
+ assert(0);
+ }
+ return;
+ }
+
+ if (o1 == o2) {
+ // Need to decide if we are rotating CW or CCW to get to a triangle
+ // that will cross edge
+ if (o1 == CW) {
+ triangle = triangle->NeighborCCW(point);
+ } else{
+ triangle = triangle->NeighborCW(point);
+ }
+ EdgeEvent(tcx, ep, eq, triangle, point);
+ } else {
+ // This triangle crosses constraint so lets flippin start!
+ FlipEdgeEvent(tcx, ep, eq, triangle, point);
+ }
+}
+
+bool Sweep::IsEdgeSideOfTriangle(Triangle& triangle, Point& ep, Point& eq)
+{
+ const int index = triangle.EdgeIndex(&ep, &eq);
+
+ if (index != -1) {
+ triangle.MarkConstrainedEdge(index);
+ Triangle* t = triangle.GetNeighbor(index);
+ if (t) {
+ t->MarkConstrainedEdge(&ep, &eq);
+ }
+ return true;
+ }
+ return false;
+}
+
+Node& Sweep::NewFrontTriangle(SweepContext& tcx, Point& point, Node& node)
+{
+ Triangle* triangle = new Triangle(point, *node.point, *node.next->point);
+
+ triangle->MarkNeighbor(*node.triangle);
+ tcx.AddToMap(triangle);
+
+ Node* new_node = new Node(point);
+ nodes_.push_back(new_node);
+
+ new_node->next = node.next;
+ new_node->prev = &node;
+ node.next->prev = new_node;
+ node.next = new_node;
+
+ if (!Legalize(tcx, *triangle)) {
+ tcx.MapTriangleToNodes(*triangle);
+ }
+
+ return *new_node;
+}
+
+void Sweep::Fill(SweepContext& tcx, Node& node)
+{
+ Triangle* triangle = new Triangle(*node.prev->point, *node.point, *node.next->point);
+
+ // TODO: should copy the constrained_edge value from neighbor triangles
+ // for now constrained_edge values are copied during the legalize
+ triangle->MarkNeighbor(*node.prev->triangle);
+ triangle->MarkNeighbor(*node.triangle);
+
+ tcx.AddToMap(triangle);
+
+ // Update the advancing front
+ node.prev->next = node.next;
+ node.next->prev = node.prev;
+
+ // If it was legalized the triangle has already been mapped
+ if (!Legalize(tcx, *triangle)) {
+ tcx.MapTriangleToNodes(*triangle);
+ }
+
+}
+
+void Sweep::FillAdvancingFront(SweepContext& tcx, Node& n)
+{
+
+ // Fill right holes
+ Node* node = n.next;
+
+ while (node->next) {
+ // if HoleAngle exceeds 90 degrees then break.
+ if (LargeHole_DontFill(node)) break;
+ Fill(tcx, *node);
+ node = node->next;
+ }
+
+ // Fill left holes
+ node = n.prev;
+
+ while (node->prev) {
+ // if HoleAngle exceeds 90 degrees then break.
+ if (LargeHole_DontFill(node)) break;
+ Fill(tcx, *node);
+ node = node->prev;
+ }
+
+ // Fill right basins
+ if (n.next && n.next->next) {
+ const double angle = BasinAngle(n);
+ if (angle < PI_3div4) {
+ FillBasin(tcx, n);
+ }
+ }
+}
+
+// True if HoleAngle exceeds 90 degrees.
+bool Sweep::LargeHole_DontFill(const Node* node) const {
+
+ const Node* nextNode = node->next;
+ const Node* prevNode = node->prev;
+ if (!AngleExceeds90Degrees(node->point, nextNode->point, prevNode->point))
+ return false;
+
+ // Check additional points on front.
+ const Node* next2Node = nextNode->next;
+ // "..Plus.." because only want angles on same side as point being added.
+ if ((next2Node != NULL) && !AngleExceedsPlus90DegreesOrIsNegative(node->point, next2Node->point, prevNode->point))
+ return false;
+
+ const Node* prev2Node = prevNode->prev;
+ // "..Plus.." because only want angles on same side as point being added.
+ if ((prev2Node != NULL) && !AngleExceedsPlus90DegreesOrIsNegative(node->point, nextNode->point, prev2Node->point))
+ return false;
+
+ return true;
+}
+
+bool Sweep::AngleExceeds90Degrees(const Point* origin, const Point* pa, const Point* pb) const {
+ const double angle = Angle(origin, pa, pb);
+ return ((angle > PI_div2) || (angle < -PI_div2));
+}
+
+bool Sweep::AngleExceedsPlus90DegreesOrIsNegative(const Point* origin, const Point* pa, const Point* pb) const {
+ const double angle = Angle(origin, pa, pb);
+ return (angle > PI_div2) || (angle < 0);
+}
+
+double Sweep::Angle(const Point* origin, const Point* pa, const Point* pb) const {
+ /* Complex plane
+ * ab = cosA +i*sinA
+ * ab = (ax + ay*i)(bx + by*i) = (ax*bx + ay*by) + i(ax*by-ay*bx)
+ * atan2(y,x) computes the principal value of the argument function
+ * applied to the complex number x+iy
+ * Where x = ax*bx + ay*by
+ * y = ax*by - ay*bx
+ */
+ const double px = origin->x;
+ const double py = origin->y;
+ const double ax = pa->x- px;
+ const double ay = pa->y - py;
+ const double bx = pb->x - px;
+ const double by = pb->y - py;
+ const double x = ax * by - ay * bx;
+ const double y = ax * bx + ay * by;
+ return atan2(x, y);
+}
+
+double Sweep::BasinAngle(const Node& node) const
+{
+ const double ax = node.point->x - node.next->next->point->x;
+ const double ay = node.point->y - node.next->next->point->y;
+ return atan2(ay, ax);
+}
+
+double Sweep::HoleAngle(const Node& node) const
+{
+ /* Complex plane
+ * ab = cosA +i*sinA
+ * ab = (ax + ay*i)(bx + by*i) = (ax*bx + ay*by) + i(ax*by-ay*bx)
+ * atan2(y,x) computes the principal value of the argument function
+ * applied to the complex number x+iy
+ * Where x = ax*bx + ay*by
+ * y = ax*by - ay*bx
+ */
+ const double ax = node.next->point->x - node.point->x;
+ const double ay = node.next->point->y - node.point->y;
+ const double bx = node.prev->point->x - node.point->x;
+ const double by = node.prev->point->y - node.point->y;
+ return atan2(ax * by - ay * bx, ax * bx + ay * by);
+}
+
+bool Sweep::Legalize(SweepContext& tcx, Triangle& t)
+{
+ // To legalize a triangle we start by finding if any of the three edges
+ // violate the Delaunay condition
+ for (int i = 0; i < 3; i++) {
+ if (t.delaunay_edge[i])
+ continue;
+
+ Triangle* ot = t.GetNeighbor(i);
+
+ if (ot) {
+ Point* p = t.GetPoint(i);
+ Point* op = ot->OppositePoint(t, *p);
+ int oi = ot->Index(op);
+
+ // If this is a Constrained Edge or a Delaunay Edge(only during recursive legalization)
+ // then we should not try to legalize
+ if (ot->constrained_edge[oi] || ot->delaunay_edge[oi]) {
+ t.constrained_edge[i] = ot->constrained_edge[oi];
+ continue;
+ }
+
+ bool inside = Incircle(*p, *t.PointCCW(*p), *t.PointCW(*p), *op);
+
+ if (inside) {
+ // Lets mark this shared edge as Delaunay
+ t.delaunay_edge[i] = true;
+ ot->delaunay_edge[oi] = true;
+
+ // Lets rotate shared edge one vertex CW to legalize it
+ RotateTrianglePair(t, *p, *ot, *op);
+
+ // We now got one valid Delaunay Edge shared by two triangles
+ // This gives us 4 new edges to check for Delaunay
+
+ // Make sure that triangle to node mapping is done only one time for a specific triangle
+ bool not_legalized = !Legalize(tcx, t);
+ if (not_legalized) {
+ tcx.MapTriangleToNodes(t);
+ }
+
+ not_legalized = !Legalize(tcx, *ot);
+ if (not_legalized)
+ tcx.MapTriangleToNodes(*ot);
+
+ // Reset the Delaunay edges, since they only are valid Delaunay edges
+ // until we add a new triangle or point.
+ // XXX: need to think about this. Can these edges be tried after we
+ // return to previous recursive level?
+ t.delaunay_edge[i] = false;
+ ot->delaunay_edge[oi] = false;
+
+ // If triangle have been legalized no need to check the other edges since
+ // the recursive legalization will handles those so we can end here.
+ return true;
+ }
+ }
+ }
+ return false;
+}
+
+bool Sweep::Incircle(const Point& pa, const Point& pb, const Point& pc, const Point& pd) const
+{
+ const double adx = pa.x - pd.x;
+ const double ady = pa.y - pd.y;
+ const double bdx = pb.x - pd.x;
+ const double bdy = pb.y - pd.y;
+
+ const double adxbdy = adx * bdy;
+ const double bdxady = bdx * ady;
+ const double oabd = adxbdy - bdxady;
+
+ if (oabd <= 0)
+ return false;
+
+ const double cdx = pc.x - pd.x;
+ const double cdy = pc.y - pd.y;
+
+ const double cdxady = cdx * ady;
+ const double adxcdy = adx * cdy;
+ const double ocad = cdxady - adxcdy;
+
+ if (ocad <= 0)
+ return false;
+
+ const double bdxcdy = bdx * cdy;
+ const double cdxbdy = cdx * bdy;
+
+ const double alift = adx * adx + ady * ady;
+ const double blift = bdx * bdx + bdy * bdy;
+ const double clift = cdx * cdx + cdy * cdy;
+
+ const double det = alift * (bdxcdy - cdxbdy) + blift * ocad + clift * oabd;
+
+ return det > 0;
+}
+
+void Sweep::RotateTrianglePair(Triangle& t, Point& p, Triangle& ot, Point& op) const
+{
+ Triangle* n1, *n2, *n3, *n4;
+ n1 = t.NeighborCCW(p);
+ n2 = t.NeighborCW(p);
+ n3 = ot.NeighborCCW(op);
+ n4 = ot.NeighborCW(op);
+
+ bool ce1, ce2, ce3, ce4;
+ ce1 = t.GetConstrainedEdgeCCW(p);
+ ce2 = t.GetConstrainedEdgeCW(p);
+ ce3 = ot.GetConstrainedEdgeCCW(op);
+ ce4 = ot.GetConstrainedEdgeCW(op);
+
+ bool de1, de2, de3, de4;
+ de1 = t.GetDelunayEdgeCCW(p);
+ de2 = t.GetDelunayEdgeCW(p);
+ de3 = ot.GetDelunayEdgeCCW(op);
+ de4 = ot.GetDelunayEdgeCW(op);
+
+ t.Legalize(p, op);
+ ot.Legalize(op, p);
+
+ // Remap delaunay_edge
+ ot.SetDelunayEdgeCCW(p, de1);
+ t.SetDelunayEdgeCW(p, de2);
+ t.SetDelunayEdgeCCW(op, de3);
+ ot.SetDelunayEdgeCW(op, de4);
+
+ // Remap constrained_edge
+ ot.SetConstrainedEdgeCCW(p, ce1);
+ t.SetConstrainedEdgeCW(p, ce2);
+ t.SetConstrainedEdgeCCW(op, ce3);
+ ot.SetConstrainedEdgeCW(op, ce4);
+
+ // Remap neighbors
+ // XXX: might optimize the markNeighbor by keeping track of
+ // what side should be assigned to what neighbor after the
+ // rotation. Now mark neighbor does lots of testing to find
+ // the right side.
+ t.ClearNeighbors();
+ ot.ClearNeighbors();
+ if (n1) ot.MarkNeighbor(*n1);
+ if (n2) t.MarkNeighbor(*n2);
+ if (n3) t.MarkNeighbor(*n3);
+ if (n4) ot.MarkNeighbor(*n4);
+ t.MarkNeighbor(ot);
+}
+
+void Sweep::FillBasin(SweepContext& tcx, Node& node)
+{
+ if (Orient2d(*node.point, *node.next->point, *node.next->next->point) == CCW) {
+ tcx.basin.left_node = node.next->next;
+ } else {
+ tcx.basin.left_node = node.next;
+ }
+
+ // Find the bottom and right node
+ tcx.basin.bottom_node = tcx.basin.left_node;
+ while (tcx.basin.bottom_node->next
+ && tcx.basin.bottom_node->point->y >= tcx.basin.bottom_node->next->point->y) {
+ tcx.basin.bottom_node = tcx.basin.bottom_node->next;
+ }
+ if (tcx.basin.bottom_node == tcx.basin.left_node) {
+ // No valid basin
+ return;
+ }
+
+ tcx.basin.right_node = tcx.basin.bottom_node;
+ while (tcx.basin.right_node->next
+ && tcx.basin.right_node->point->y < tcx.basin.right_node->next->point->y) {
+ tcx.basin.right_node = tcx.basin.right_node->next;
+ }
+ if (tcx.basin.right_node == tcx.basin.bottom_node) {
+ // No valid basins
+ return;
+ }
+
+ tcx.basin.width = tcx.basin.right_node->point->x - tcx.basin.left_node->point->x;
+ tcx.basin.left_highest = tcx.basin.left_node->point->y > tcx.basin.right_node->point->y;
+
+ FillBasinReq(tcx, tcx.basin.bottom_node);
+}
+
+void Sweep::FillBasinReq(SweepContext& tcx, Node* node)
+{
+ // if shallow stop filling
+ if (IsShallow(tcx, *node)) {
+ return;
+ }
+
+ Fill(tcx, *node);
+
+ if (node->prev == tcx.basin.left_node && node->next == tcx.basin.right_node) {
+ return;
+ } else if (node->prev == tcx.basin.left_node) {
+ Orientation o = Orient2d(*node->point, *node->next->point, *node->next->next->point);
+ if (o == CW) {
+ return;
+ }
+ node = node->next;
+ } else if (node->next == tcx.basin.right_node) {
+ Orientation o = Orient2d(*node->point, *node->prev->point, *node->prev->prev->point);
+ if (o == CCW) {
+ return;
+ }
+ node = node->prev;
+ } else {
+ // Continue with the neighbor node with lowest Y value
+ if (node->prev->point->y < node->next->point->y) {
+ node = node->prev;
+ } else {
+ node = node->next;
+ }
+ }
+
+ FillBasinReq(tcx, node);
+}
+
+bool Sweep::IsShallow(SweepContext& tcx, Node& node)
+{
+ double height;
+
+ if (tcx.basin.left_highest) {
+ height = tcx.basin.left_node->point->y - node.point->y;
+ } else {
+ height = tcx.basin.right_node->point->y - node.point->y;
+ }
+
+ // if shallow stop filling
+ if (tcx.basin.width > height) {
+ return true;
+ }
+ return false;
+}
+
+void Sweep::FillEdgeEvent(SweepContext& tcx, Edge* edge, Node* node)
+{
+ if (tcx.edge_event.right) {
+ FillRightAboveEdgeEvent(tcx, edge, node);
+ } else {
+ FillLeftAboveEdgeEvent(tcx, edge, node);
+ }
+}
+
+void Sweep::FillRightAboveEdgeEvent(SweepContext& tcx, Edge* edge, Node* node)
+{
+ while (node->next->point->x < edge->p->x) {
+ // Check if next node is below the edge
+ if (Orient2d(*edge->q, *node->next->point, *edge->p) == CCW) {
+ FillRightBelowEdgeEvent(tcx, edge, *node);
+ } else {
+ node = node->next;
+ }
+ }
+}
+
+void Sweep::FillRightBelowEdgeEvent(SweepContext& tcx, Edge* edge, Node& node)
+{
+ if (node.point->x < edge->p->x) {
+ if (Orient2d(*node.point, *node.next->point, *node.next->next->point) == CCW) {
+ // Concave
+ FillRightConcaveEdgeEvent(tcx, edge, node);
+ } else{
+ // Convex
+ FillRightConvexEdgeEvent(tcx, edge, node);
+ // Retry this one
+ FillRightBelowEdgeEvent(tcx, edge, node);
+ }
+ }
+}
+
+void Sweep::FillRightConcaveEdgeEvent(SweepContext& tcx, Edge* edge, Node& node)
+{
+ Fill(tcx, *node.next);
+ if (node.next->point != edge->p) {
+ // Next above or below edge?
+ if (Orient2d(*edge->q, *node.next->point, *edge->p) == CCW) {
+ // Below
+ if (Orient2d(*node.point, *node.next->point, *node.next->next->point) == CCW) {
+ // Next is concave
+ FillRightConcaveEdgeEvent(tcx, edge, node);
+ } else {
+ // Next is convex
+ }
+ }
+ }
+
+}
+
+void Sweep::FillRightConvexEdgeEvent(SweepContext& tcx, Edge* edge, Node& node)
+{
+ // Next concave or convex?
+ if (Orient2d(*node.next->point, *node.next->next->point, *node.next->next->next->point) == CCW) {
+ // Concave
+ FillRightConcaveEdgeEvent(tcx, edge, *node.next);
+ } else{
+ // Convex
+ // Next above or below edge?
+ if (Orient2d(*edge->q, *node.next->next->point, *edge->p) == CCW) {
+ // Below
+ FillRightConvexEdgeEvent(tcx, edge, *node.next);
+ } else{
+ // Above
+ }
+ }
+}
+
+void Sweep::FillLeftAboveEdgeEvent(SweepContext& tcx, Edge* edge, Node* node)
+{
+ while (node->prev->point->x > edge->p->x) {
+ // Check if next node is below the edge
+ if (Orient2d(*edge->q, *node->prev->point, *edge->p) == CW) {
+ FillLeftBelowEdgeEvent(tcx, edge, *node);
+ } else {
+ node = node->prev;
+ }
+ }
+}
+
+void Sweep::FillLeftBelowEdgeEvent(SweepContext& tcx, Edge* edge, Node& node)
+{
+ if (node.point->x > edge->p->x) {
+ if (Orient2d(*node.point, *node.prev->point, *node.prev->prev->point) == CW) {
+ // Concave
+ FillLeftConcaveEdgeEvent(tcx, edge, node);
+ } else {
+ // Convex
+ FillLeftConvexEdgeEvent(tcx, edge, node);
+ // Retry this one
+ FillLeftBelowEdgeEvent(tcx, edge, node);
+ }
+ }
+}
+
+void Sweep::FillLeftConvexEdgeEvent(SweepContext& tcx, Edge* edge, Node& node)
+{
+ // Next concave or convex?
+ if (Orient2d(*node.prev->point, *node.prev->prev->point, *node.prev->prev->prev->point) == CW) {
+ // Concave
+ FillLeftConcaveEdgeEvent(tcx, edge, *node.prev);
+ } else{
+ // Convex
+ // Next above or below edge?
+ if (Orient2d(*edge->q, *node.prev->prev->point, *edge->p) == CW) {
+ // Below
+ FillLeftConvexEdgeEvent(tcx, edge, *node.prev);
+ } else{
+ // Above
+ }
+ }
+}
+
+void Sweep::FillLeftConcaveEdgeEvent(SweepContext& tcx, Edge* edge, Node& node)
+{
+ Fill(tcx, *node.prev);
+ if (node.prev->point != edge->p) {
+ // Next above or below edge?
+ if (Orient2d(*edge->q, *node.prev->point, *edge->p) == CW) {
+ // Below
+ if (Orient2d(*node.point, *node.prev->point, *node.prev->prev->point) == CW) {
+ // Next is concave
+ FillLeftConcaveEdgeEvent(tcx, edge, node);
+ } else{
+ // Next is convex
+ }
+ }
+ }
+
+}
+
+void Sweep::FlipEdgeEvent(SweepContext& tcx, Point& ep, Point& eq, Triangle* t, Point& p)
+{
+ Triangle& ot = t->NeighborAcross(p);
+ Point& op = *ot.OppositePoint(*t, p);
+
+ if (&ot == NULL) {
+ // If we want to integrate the fillEdgeEvent do it here
+ // With current implementation we should never get here
+ //throw new RuntimeException( "[BUG:FIXME] FLIP failed due to missing triangle");
+ assert(0);
+ }
+
+ if (InScanArea(p, *t->PointCCW(p), *t->PointCW(p), op)) {
+ // Lets rotate shared edge one vertex CW
+ RotateTrianglePair(*t, p, ot, op);
+ tcx.MapTriangleToNodes(*t);
+ tcx.MapTriangleToNodes(ot);
+
+ if (p == eq && op == ep) {
+ if (eq == *tcx.edge_event.constrained_edge->q && ep == *tcx.edge_event.constrained_edge->p) {
+ t->MarkConstrainedEdge(&ep, &eq);
+ ot.MarkConstrainedEdge(&ep, &eq);
+ Legalize(tcx, *t);
+ Legalize(tcx, ot);
+ } else {
+ // XXX: I think one of the triangles should be legalized here?
+ }
+ } else {
+ Orientation o = Orient2d(eq, op, ep);
+ t = &NextFlipTriangle(tcx, (int)o, *t, ot, p, op);
+ FlipEdgeEvent(tcx, ep, eq, t, p);
+ }
+ } else {
+ Point& newP = NextFlipPoint(ep, eq, ot, op);
+ FlipScanEdgeEvent(tcx, ep, eq, *t, ot, newP);
+ EdgeEvent(tcx, ep, eq, t, p);
+ }
+}
+
+Triangle& Sweep::NextFlipTriangle(SweepContext& tcx, int o, Triangle& t, Triangle& ot, Point& p, Point& op)
+{
+ if (o == CCW) {
+ // ot is not crossing edge after flip
+ int edge_index = ot.EdgeIndex(&p, &op);
+ ot.delaunay_edge[edge_index] = true;
+ Legalize(tcx, ot);
+ ot.ClearDelunayEdges();
+ return t;
+ }
+
+ // t is not crossing edge after flip
+ int edge_index = t.EdgeIndex(&p, &op);
+
+ t.delaunay_edge[edge_index] = true;
+ Legalize(tcx, t);
+ t.ClearDelunayEdges();
+ return ot;
+}
+
+Point& Sweep::NextFlipPoint(Point& ep, Point& eq, Triangle& ot, Point& op)
+{
+ Orientation o2d = Orient2d(eq, op, ep);
+ if (o2d == CW) {
+ // Right
+ return *ot.PointCCW(op);
+ } else if (o2d == CCW) {
+ // Left
+ return *ot.PointCW(op);
+ }
+ throw std::runtime_error("[Unsupported] Opposing point on constrained edge");
+}
+
+void Sweep::FlipScanEdgeEvent(SweepContext& tcx, Point& ep, Point& eq, Triangle& flip_triangle,
+ Triangle& t, Point& p)
+{
+ Triangle& ot = t.NeighborAcross(p);
+ Point& op = *ot.OppositePoint(t, p);
+
+ if (&t.NeighborAcross(p) == NULL) {
+ // If we want to integrate the fillEdgeEvent do it here
+ // With current implementation we should never get here
+ //throw new RuntimeException( "[BUG:FIXME] FLIP failed due to missing triangle");
+ assert(0);
+ }
+
+ if (InScanArea(eq, *flip_triangle.PointCCW(eq), *flip_triangle.PointCW(eq), op)) {
+ // flip with new edge op->eq
+ FlipEdgeEvent(tcx, eq, op, &ot, op);
+ // TODO: Actually I just figured out that it should be possible to
+ // improve this by getting the next ot and op before the the above
+ // flip and continue the flipScanEdgeEvent here
+ // set new ot and op here and loop back to inScanArea test
+ // also need to set a new flip_triangle first
+ // Turns out at first glance that this is somewhat complicated
+ // so it will have to wait.
+ } else{
+ Point& newP = NextFlipPoint(ep, eq, ot, op);
+ FlipScanEdgeEvent(tcx, ep, eq, flip_triangle, ot, newP);
+ }
+}
+
+Sweep::~Sweep() {
+
+ // Clean up memory
+ for(size_t i = 0; i < nodes_.size(); i++) {
+ delete nodes_[i];
+ }
+
+}
+
+}
+
diff --git a/src/poly2tri/sweep/sweep.h b/src/poly2tri/sweep/sweep.h
new file mode 100644
index 000000000..33e34a714
--- /dev/null
+++ b/src/poly2tri/sweep/sweep.h
@@ -0,0 +1,285 @@
+/*
+ * Poly2Tri Copyright (c) 2009-2010, Poly2Tri Contributors
+ * http://code.google.com/p/poly2tri/
+ *
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ *
+ * * Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * * Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * * Neither the name of Poly2Tri nor the names of its contributors may be
+ * used to endorse or promote products derived from this software without specific
+ * prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+ * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR
+ * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
+ * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
+ * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
+ * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
+ * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+/**
+ * Sweep-line, Constrained Delauney Triangulation (CDT) See: Domiter, V. and
+ * Zalik, B.(2008)'Sweep-line algorithm for constrained Delaunay triangulation',
+ * International Journal of Geographical Information Science
+ *
+ * "FlipScan" Constrained Edge Algorithm invented by Thomas ?hl?n, thahlen@gmail.com
+ */
+
+#ifndef SWEEP_H
+#define SWEEP_H
+
+#include <vector>
+
+namespace p2t {
+
+class SweepContext;
+struct Node;
+struct Point;
+struct Edge;
+class Triangle;
+
+class Sweep
+{
+public:
+
+ /**
+ * Triangulate
+ *
+ * @param tcx
+ */
+ void Triangulate(SweepContext& tcx);
+
+ /**
+ * Destructor - clean up memory
+ */
+ ~Sweep();
+
+private:
+
+ /**
+ * Start sweeping the Y-sorted point set from bottom to top
+ *
+ * @param tcx
+ */
+ void SweepPoints(SweepContext& tcx);
+
+ /**
+ * Find closes node to the left of the new point and
+ * create a new triangle. If needed new holes and basins
+ * will be filled to.
+ *
+ * @param tcx
+ * @param point
+ * @return
+ */
+ Node& PointEvent(SweepContext& tcx, Point& point);
+
+ /**
+ *
+ *
+ * @param tcx
+ * @param edge
+ * @param node
+ */
+ void EdgeEvent(SweepContext& tcx, Edge* edge, Node* node);
+
+ void EdgeEvent(SweepContext& tcx, Point& ep, Point& eq, Triangle* triangle, Point& point);
+
+ /**
+ * Creates a new front triangle and legalize it
+ *
+ * @param tcx
+ * @param point
+ * @param node
+ * @return
+ */
+ Node& NewFrontTriangle(SweepContext& tcx, Point& point, Node& node);
+
+ /**
+ * Adds a triangle to the advancing front to fill a hole.
+ * @param tcx
+ * @param node - middle node, that is the bottom of the hole
+ */
+ void Fill(SweepContext& tcx, Node& node);
+
+ /**
+ * Returns true if triangle was legalized
+ */
+ bool Legalize(SweepContext& tcx, Triangle& t);
+
+ /**
+ * <b>Requirement</b>:<br>
+ * 1. a,b and c form a triangle.<br>
+ * 2. a and d is know to be on opposite side of bc<br>
+ * <pre>
+ * a
+ * +
+ * / \
+ * / \
+ * b/ \c
+ * +-------+
+ * / d \
+ * / \
+ * </pre>
+ * <b>Fact</b>: d has to be in area B to have a chance to be inside the circle formed by
+ * a,b and c<br>
+ * d is outside B if orient2d(a,b,d) or orient2d(c,a,d) is CW<br>
+ * This preknowledge gives us a way to optimize the incircle test
+ * @param a - triangle point, opposite d
+ * @param b - triangle point
+ * @param c - triangle point
+ * @param d - point opposite a
+ * @return true if d is inside circle, false if on circle edge
+ */
+ bool Incircle(const Point& pa, const Point& pb, const Point& pc, const Point& pd) const;
+
+ /**
+ * Rotates a triangle pair one vertex CW
+ *<pre>
+ * n2 n2
+ * P +-----+ P +-----+
+ * | t /| |\ t |
+ * | / | | \ |
+ * n1| / |n3 n1| \ |n3
+ * | / | after CW | \ |
+ * |/ oT | | oT \|
+ * +-----+ oP +-----+
+ * n4 n4
+ * </pre>
+ */
+ void RotateTrianglePair(Triangle& t, Point& p, Triangle& ot, Point& op) const;
+
+ /**
+ * Fills holes in the Advancing Front
+ *
+ *
+ * @param tcx
+ * @param n
+ */
+ void FillAdvancingFront(SweepContext& tcx, Node& n);
+
+ // Decision-making about when to Fill hole.
+ // Contributed by ToolmakerSteve2
+ bool LargeHole_DontFill(const Node* node) const;
+ bool AngleExceeds90Degrees(const Point* origin, const Point* pa, const Point* pb) const;
+ bool AngleExceedsPlus90DegreesOrIsNegative(const Point* origin, const Point* pa, const Point* pb) const;
+ double Angle(const Point* origin, const Point* pa, const Point* pb) const;
+
+ /**
+ *
+ * @param node - middle node
+ * @return the angle between 3 front nodes
+ */
+ double HoleAngle(const Node& node) const;
+
+ /**
+ * The basin angle is decided against the horizontal line [1,0]
+ */
+ double BasinAngle(const Node& node) const;
+
+ /**
+ * Fills a basin that has formed on the Advancing Front to the right
+ * of given node.<br>
+ * First we decide a left,bottom and right node that forms the
+ * boundaries of the basin. Then we do a reqursive fill.
+ *
+ * @param tcx
+ * @param node - starting node, this or next node will be left node
+ */
+ void FillBasin(SweepContext& tcx, Node& node);
+
+ /**
+ * Recursive algorithm to fill a Basin with triangles
+ *
+ * @param tcx
+ * @param node - bottom_node
+ * @param cnt - counter used to alternate on even and odd numbers
+ */
+ void FillBasinReq(SweepContext& tcx, Node* node);
+
+ bool IsShallow(SweepContext& tcx, Node& node);
+
+ bool IsEdgeSideOfTriangle(Triangle& triangle, Point& ep, Point& eq);
+
+ void FillEdgeEvent(SweepContext& tcx, Edge* edge, Node* node);
+
+ void FillRightAboveEdgeEvent(SweepContext& tcx, Edge* edge, Node* node);
+
+ void FillRightBelowEdgeEvent(SweepContext& tcx, Edge* edge, Node& node);
+
+ void FillRightConcaveEdgeEvent(SweepContext& tcx, Edge* edge, Node& node);
+
+ void FillRightConvexEdgeEvent(SweepContext& tcx, Edge* edge, Node& node);
+
+ void FillLeftAboveEdgeEvent(SweepContext& tcx, Edge* edge, Node* node);
+
+ void FillLeftBelowEdgeEvent(SweepContext& tcx, Edge* edge, Node& node);
+
+ void FillLeftConcaveEdgeEvent(SweepContext& tcx, Edge* edge, Node& node);
+
+ void FillLeftConvexEdgeEvent(SweepContext& tcx, Edge* edge, Node& node);
+
+ void FlipEdgeEvent(SweepContext& tcx, Point& ep, Point& eq, Triangle* t, Point& p);
+
+ /**
+ * After a flip we have two triangles and know that only one will still be
+ * intersecting the edge. So decide which to contiune with and legalize the other
+ *
+ * @param tcx
+ * @param o - should be the result of an orient2d( eq, op, ep )
+ * @param t - triangle 1
+ * @param ot - triangle 2
+ * @param p - a point shared by both triangles
+ * @param op - another point shared by both triangles
+ * @return returns the triangle still intersecting the edge
+ */
+ Triangle& NextFlipTriangle(SweepContext& tcx, int o, Triangle& t, Triangle& ot, Point& p, Point& op);
+
+ /**
+ * When we need to traverse from one triangle to the next we need
+ * the point in current triangle that is the opposite point to the next
+ * triangle.
+ *
+ * @param ep
+ * @param eq
+ * @param ot
+ * @param op
+ * @return
+ */
+ Point& NextFlipPoint(Point& ep, Point& eq, Triangle& ot, Point& op);
+
+ /**
+ * Scan part of the FlipScan algorithm<br>
+ * When a triangle pair isn't flippable we will scan for the next
+ * point that is inside the flip triangle scan area. When found
+ * we generate a new flipEdgeEvent
+ *
+ * @param tcx
+ * @param ep - last point on the edge we are traversing
+ * @param eq - first point on the edge we are traversing
+ * @param flipTriangle - the current triangle sharing the point eq with edge
+ * @param t
+ * @param p
+ */
+ void FlipScanEdgeEvent(SweepContext& tcx, Point& ep, Point& eq, Triangle& flip_triangle, Triangle& t, Point& p);
+
+ void FinalizationPolygon(SweepContext& tcx);
+
+ std::vector<Node*> nodes_;
+
+};
+
+}
+
+#endif \ No newline at end of file
diff --git a/src/poly2tri/sweep/sweep_context.cc b/src/poly2tri/sweep/sweep_context.cc
new file mode 100644
index 000000000..a9f1fdf8e
--- /dev/null
+++ b/src/poly2tri/sweep/sweep_context.cc
@@ -0,0 +1,211 @@
+/*
+ * Poly2Tri Copyright (c) 2009-2010, Poly2Tri Contributors
+ * http://code.google.com/p/poly2tri/
+ *
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ *
+ * * Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * * Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * * Neither the name of Poly2Tri nor the names of its contributors may be
+ * used to endorse or promote products derived from this software without specific
+ * prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+ * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR
+ * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
+ * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
+ * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
+ * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
+ * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+#include "sweep_context.h"
+#include <algorithm>
+#include "advancing_front.h"
+
+namespace p2t {
+
+SweepContext::SweepContext(const std::vector<Point*>& polyline) : points_(polyline),
+ front_(0),
+ head_(0),
+ tail_(0),
+ af_head_(0),
+ af_middle_(0),
+ af_tail_(0)
+{
+ InitEdges(points_);
+}
+
+void SweepContext::AddHole(const std::vector<Point*>& polyline)
+{
+ InitEdges(polyline);
+ for(unsigned int i = 0; i < polyline.size(); i++) {
+ points_.push_back(polyline[i]);
+ }
+}
+
+void SweepContext::AddPoint(Point* point) {
+ points_.push_back(point);
+}
+
+std::vector<Triangle*> &SweepContext::GetTriangles()
+{
+ return triangles_;
+}
+
+std::list<Triangle*> &SweepContext::GetMap()
+{
+ return map_;
+}
+
+void SweepContext::InitTriangulation()
+{
+ double xmax(points_[0]->x), xmin(points_[0]->x);
+ double ymax(points_[0]->y), ymin(points_[0]->y);
+
+ // Calculate bounds.
+ for (unsigned int i = 0; i < points_.size(); i++) {
+ Point& p = *points_[i];
+ if (p.x > xmax)
+ xmax = p.x;
+ if (p.x < xmin)
+ xmin = p.x;
+ if (p.y > ymax)
+ ymax = p.y;
+ if (p.y < ymin)
+ ymin = p.y;
+ }
+
+ double dx = kAlpha * (xmax - xmin);
+ double dy = kAlpha * (ymax - ymin);
+ head_ = new Point(xmax + dx, ymin - dy);
+ tail_ = new Point(xmin - dx, ymin - dy);
+
+ // Sort points along y-axis
+ std::sort(points_.begin(), points_.end(), cmp);
+
+}
+
+void SweepContext::InitEdges(const std::vector<Point*>& polyline)
+{
+ size_t num_points = polyline.size();
+ for (size_t i = 0; i < num_points; i++) {
+ size_t j = i < num_points - 1 ? i + 1 : 0;
+ edge_list.push_back(new Edge(*polyline[i], *polyline[j]));
+ }
+}
+
+Point* SweepContext::GetPoint(size_t index)
+{
+ return points_[index];
+}
+
+void SweepContext::AddToMap(Triangle* triangle)
+{
+ map_.push_back(triangle);
+}
+
+Node& SweepContext::LocateNode(const Point& point)
+{
+ // TODO implement search tree
+ return *front_->LocateNode(point.x);
+}
+
+void SweepContext::CreateAdvancingFront(const std::vector<Node*>& nodes)
+{
+
+ (void) nodes;
+ // Initial triangle
+ Triangle* triangle = new Triangle(*points_[0], *tail_, *head_);
+
+ map_.push_back(triangle);
+
+ af_head_ = new Node(*triangle->GetPoint(1), *triangle);
+ af_middle_ = new Node(*triangle->GetPoint(0), *triangle);
+ af_tail_ = new Node(*triangle->GetPoint(2));
+ front_ = new AdvancingFront(*af_head_, *af_tail_);
+
+ // TODO: More intuitive if head is middles next and not previous?
+ // so swap head and tail
+ af_head_->next = af_middle_;
+ af_middle_->next = af_tail_;
+ af_middle_->prev = af_head_;
+ af_tail_->prev = af_middle_;
+}
+
+void SweepContext::RemoveNode(Node* node)
+{
+ delete node;
+}
+
+void SweepContext::MapTriangleToNodes(Triangle& t)
+{
+ for (int i = 0; i < 3; i++) {
+ if (!t.GetNeighbor(i)) {
+ Node* n = front_->LocatePoint(t.PointCW(*t.GetPoint(i)));
+ if (n)
+ n->triangle = &t;
+ }
+ }
+}
+
+void SweepContext::RemoveFromMap(Triangle* triangle)
+{
+ map_.remove(triangle);
+}
+
+void SweepContext::MeshClean(Triangle& triangle)
+{
+ std::vector<Triangle *> triangles;
+ triangles.push_back(&triangle);
+
+ while(!triangles.empty()){
+ Triangle *t = triangles.back();
+ triangles.pop_back();
+
+ if (t != NULL && !t->IsInterior()) {
+ t->IsInterior(true);
+ triangles_.push_back(t);
+ for (int i = 0; i < 3; i++) {
+ if (!t->constrained_edge[i])
+ triangles.push_back(t->GetNeighbor(i));
+ }
+ }
+ }
+}
+
+SweepContext::~SweepContext()
+{
+
+ // Clean up memory
+
+ delete head_;
+ delete tail_;
+ delete front_;
+ delete af_head_;
+ delete af_middle_;
+ delete af_tail_;
+
+ typedef std::list<Triangle*> type_list;
+
+ for(type_list::iterator iter = map_.begin(); iter != map_.end(); ++iter) {
+ Triangle* ptr = *iter;
+ delete ptr;
+ }
+
+ for(unsigned int i = 0; i < edge_list.size(); i++) {
+ delete edge_list[i];
+ }
+
+}
+
+}
diff --git a/src/poly2tri/sweep/sweep_context.h b/src/poly2tri/sweep/sweep_context.h
new file mode 100644
index 000000000..ba0d06581
--- /dev/null
+++ b/src/poly2tri/sweep/sweep_context.h
@@ -0,0 +1,186 @@
+/*
+ * Poly2Tri Copyright (c) 2009-2010, Poly2Tri Contributors
+ * http://code.google.com/p/poly2tri/
+ *
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ *
+ * * Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * * Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * * Neither the name of Poly2Tri nor the names of its contributors may be
+ * used to endorse or promote products derived from this software without specific
+ * prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+ * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR
+ * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
+ * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
+ * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
+ * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
+ * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef SWEEP_CONTEXT_H
+#define SWEEP_CONTEXT_H
+
+#include <list>
+#include <vector>
+#include <cstddef>
+
+namespace p2t {
+
+// Inital triangle factor, seed triangle will extend 30% of
+// PointSet width to both left and right.
+const double kAlpha = 0.3;
+
+struct Point;
+class Triangle;
+struct Node;
+struct Edge;
+class AdvancingFront;
+
+class SweepContext {
+public:
+
+/// Constructor
+SweepContext(const std::vector<Point*>& polyline);
+/// Destructor
+~SweepContext();
+
+void set_head(Point* p1);
+
+Point* head() const;
+
+void set_tail(Point* p1);
+
+Point* tail() const;
+
+size_t point_count() const;
+
+Node& LocateNode(const Point& point);
+
+void RemoveNode(Node* node);
+
+void CreateAdvancingFront(const std::vector<Node*>& nodes);
+
+/// Try to map a node to all sides of this triangle that don't have a neighbor
+void MapTriangleToNodes(Triangle& t);
+
+void AddToMap(Triangle* triangle);
+
+Point* GetPoint(size_t index);
+
+Point* GetPoints();
+
+void RemoveFromMap(Triangle* triangle);
+
+void AddHole(const std::vector<Point*>& polyline);
+
+void AddPoint(Point* point);
+
+AdvancingFront* front() const;
+
+void MeshClean(Triangle& triangle);
+
+std::vector<Triangle*> &GetTriangles();
+std::list<Triangle*> &GetMap();
+
+std::vector<Edge*> edge_list;
+
+struct Basin {
+ Node* left_node;
+ Node* bottom_node;
+ Node* right_node;
+ double width;
+ bool left_highest;
+
+ Basin() : left_node(NULL), bottom_node(NULL), right_node(NULL), width(0.0), left_highest(false)
+ {
+ }
+
+ void Clear()
+ {
+ left_node = NULL;
+ bottom_node = NULL;
+ right_node = NULL;
+ width = 0.0;
+ left_highest = false;
+ }
+};
+
+struct EdgeEvent {
+ Edge* constrained_edge;
+ bool right;
+
+ EdgeEvent() : constrained_edge(NULL), right(false)
+ {
+ }
+};
+
+Basin basin;
+EdgeEvent edge_event;
+
+private:
+
+friend class Sweep;
+
+std::vector<Triangle*> triangles_;
+std::list<Triangle*> map_;
+std::vector<Point*> points_;
+
+// Advancing front
+AdvancingFront* front_;
+// head point used with advancing front
+Point* head_;
+// tail point used with advancing front
+Point* tail_;
+
+Node *af_head_, *af_middle_, *af_tail_;
+
+void InitTriangulation();
+void InitEdges(const std::vector<Point*>& polyline);
+
+};
+
+inline AdvancingFront* SweepContext::front() const
+{
+ return front_;
+}
+
+inline size_t SweepContext::point_count() const
+{
+ return points_.size();
+}
+
+inline void SweepContext::set_head(Point* p1)
+{
+ head_ = p1;
+}
+
+inline Point* SweepContext::head() const
+{
+ return head_;
+}
+
+inline void SweepContext::set_tail(Point* p1)
+{
+ tail_ = p1;
+}
+
+inline Point* SweepContext::tail() const
+{
+ return tail_;
+}
+
+}
+
+#endif