26 template <
typename InputType,
typename ComputeType>
41 inline std::vector<std::array<int, 3>>
const&
GetTriangles()
const;
59 bool operator()(Polygon
const& outer, Polygon
const& inner);
65 bool operator()(Polygon
const& outer, std::vector<Polygon>
const& inners);
78 std::vector<std::shared_ptr<Tree>>
child;
83 bool operator()(std::shared_ptr<Tree>
const& tree);
99 Polygon
const& inner, std::map<int, int>& indexMap,
100 std::vector<int>& combined);
108 std::vector<Polygon>
const& inners, std::map<int, int>& indexMap,
109 std::vector<int>& combined);
172 template <
typename InputType,
typename ComputeType>
196 template <
typename InputType,
typename ComputeType>
220 template <
typename InputType,
typename ComputeType>
inline 226 template <
typename InputType,
typename ComputeType>
238 for (
int j = 0; j < 2; ++j)
256 template <
typename InputType,
typename ComputeType>
263 int const numIndices =
static_cast<int>(polygon.size());
264 int const*
indices = polygon.data();
265 for (
int i = 0; i < numIndices; ++i)
267 int index = indices[i];
271 for (
int j = 0; j < 2; ++j)
289 template <
typename InputType,
typename ComputeType>
298 if (numPointsPlusExtras > static_cast<int>(
mComputePoints.size()))
309 int const numOuterIndices =
static_cast<int>(outer.size());
310 int const* outerIndices = outer.data();
311 for (
int i = 0; i < numOuterIndices; ++i)
313 int index = outerIndices[i];
317 for (
int j = 0; j < 2; ++j)
324 int const numInnerIndices =
static_cast<int>(inner.size());
325 int const* innerIndices = inner.data();
326 for (
int i = 0; i < numInnerIndices; ++i)
328 int index = innerIndices[i];
332 for (
int j = 0; j < 2; ++j)
344 std::map<int, int> indexMap;
345 std::vector<int> combined;
354 int numVertices =
static_cast<int>(combined.size());
355 int*
const indices = &combined[0];
369 template <
typename InputType,
typename ComputeType>
378 int numPointsPlusExtras =
mNumPoints + 2 * (
int)inners.size();
379 if (numPointsPlusExtras > static_cast<int>(
mComputePoints.size()))
383 for (
int i =
mNumPoints; i < numPointsPlusExtras; ++i)
392 int const numOuterIndices =
static_cast<int>(outer.size());
393 int const* outerIndices = outer.data();
394 for (
int i = 0; i < numOuterIndices; ++i)
396 int index = outerIndices[i];
400 for (
int j = 0; j < 2; ++j)
407 for (
auto const& inner : inners)
409 int const numInnerIndices =
static_cast<int>(inner.size());
410 int const* innerIndices = inner.data();
411 for (
int i = 0; i < numInnerIndices; ++i)
413 int index = innerIndices[i];
417 for (
int j = 0; j < 2; ++j)
429 std::map<int, int> indexMap;
430 std::vector<int> combined;
439 int numVertices =
static_cast<int>(combined.size());
440 int*
const indices = &combined[0];
454 template <
typename InputType,
typename ComputeType>
464 if (numPointsPlusExtras > static_cast<int>(
mComputePoints.size()))
468 for (
int i =
mNumPoints; i < numPointsPlusExtras; ++i)
476 std::map<int, int> indexMap;
478 std::queue<std::shared_ptr<Tree>> treeQueue;
479 treeQueue.push(tree);
480 while (treeQueue.size() > 0)
482 std::shared_ptr<Tree> outer = treeQueue.front();
485 int numChildren =
static_cast<int>(outer->child.size());
489 if (numChildren == 0)
493 numVertices =
static_cast<int>(outer->polygon.size());
494 indices = outer->polygon.data();
502 std::vector<Polygon> inners(numChildren);
503 for (
int c = 0;
c < numChildren; ++
c)
505 std::shared_ptr<Tree> inner = outer->child[
c];
506 inners[
c] = inner->polygon;
507 int numGrandChildren =
static_cast<int>(inner->child.size());
508 for (
int g = 0;
g < numGrandChildren; ++
g)
510 treeQueue.push(inner->child[
g]);
517 std::vector<int> combined;
522 numVertices =
static_cast<int>(combined.size());
523 indices = &combined[0];
539 template <
typename InputType,
typename ComputeType>
553 int numVerticesM1 = numVertices - 1;
554 for (
int i = 0; i <= numVerticesM1; ++i)
557 vertex.
index = (indices ? indices[i] : i);
558 vertex.
vPrev = (i > 0 ? i - 1 : numVerticesM1);
559 vertex.
vNext = (i < numVerticesM1 ? i + 1 : 0);
566 for (
int i = 0; i <= numVerticesM1; ++i)
579 template <
typename InputType,
typename ComputeType>
585 int numVerticesM1 = numVertices - 1;
588 for (
int i = 1; i < numVerticesM1; ++i)
590 mTriangles.push_back({ { indices[0], indices[i], indices[i + 1] } });
595 for (
int i = 1; i < numVerticesM1; ++i)
622 bool bRemoveAnEar =
true;
632 if (--numVertices == 3)
639 bRemoveAnEar =
false;
700 template <
typename InputType,
typename ComputeType>
702 Polygon const& outer,
Polygon const& inner, std::map<int, int>& indexMap,
703 std::vector<int>& combined)
705 int const numOuterIndices =
static_cast<int>(outer.size());
706 int const* outerIndices = outer.data();
707 int const numInnerIndices =
static_cast<int>(inner.size());
708 int const* innerIndices = inner.data();
713 for (
int i = 1; i < numInnerIndices; ++i)
726 ComputeType
const cmax =
static_cast<ComputeType
>(std::numeric_limits<InputType>::max());
727 ComputeType
const zero =
static_cast<ComputeType
>(0);
729 int v0min = -1, v1min = -1, endMin = -1;
731 ComputeType
s = cmax;
732 ComputeType
t = cmax;
733 for (i0 = numOuterIndices - 1, i1 = 0; i1 < numOuterIndices; i0 = i1++)
749 int currentEndMin = -1;
756 s = diff0[1] / (diff0[1] - diff1[1]);
757 t = diff0[0] + s * (diff1[0] - diff0[0]);
778 if (diff0[0] < diff1[0])
791 if (zero <= t && t < intr[0])
796 if (currentEndMin == -1)
804 endMin = currentEndMin;
807 else if (t == intr[0])
811 if (endMin == -1 || currentEndMin == -1)
824 int other = (endMin == v0min ? v1min : v0min);
830 ComputeType dotperp =
DotPerp(diff0, diff1);
836 endMin = currentEndMin;
850 if (v0min < 0 || v1min < 0)
852 LogError(
"Is this an invalid nested polygon?");
883 ComputeType maxSqrLen =
Dot(diff, diff);
884 ComputeType maxCos = diff[0] * diff[0] / maxSqrLen;
886 maxCosIndex = pIndex;
887 for (
int i = 0; i < numOuterIndices; ++i)
894 int curr = outerIndices[i];
895 int prev = outerIndices[(i + numOuterIndices - 1) % numOuterIndices];
896 int next = outerIndices[(i + 1) % numOuterIndices];
902 ComputeType sqrLen =
Dot(diff, diff);
903 ComputeType cs = diff[0] * diff[0] / sqrLen;
913 else if (cs == maxCos && sqrLen < maxSqrLen)
926 maxCosIndex = endMin;
936 combined.resize(numOuterIndices + numInnerIndices + 2);
938 for (
int i = 0; i <= maxCosIndex; ++i, ++cIndex)
940 combined[cIndex] = outerIndices[i];
943 for (
int i = 0; i < numInnerIndices; ++i, ++cIndex)
945 int j = (xmaxIndex + i) % numInnerIndices;
946 combined[cIndex] = innerIndices[j];
949 int innerIndex = innerIndices[xmaxIndex];
951 combined[cIndex] = nextElement;
952 auto iter = indexMap.find(innerIndex);
953 if (iter != indexMap.end())
955 innerIndex = iter->second;
957 indexMap[nextElement] = innerIndex;
961 int outerIndex = outerIndices[maxCosIndex];
963 combined[cIndex] = nextElement;
964 iter = indexMap.find(outerIndex);
965 if (iter != indexMap.end())
967 outerIndex = iter->second;
969 indexMap[nextElement] = outerIndex;
973 for (
int i = maxCosIndex + 1; i < numOuterIndices; ++i, ++cIndex)
975 combined[cIndex] = outerIndices[i];
980 template <
typename InputType,
typename ComputeType>
982 Polygon const& outer, std::vector<Polygon>
const& inners,
983 std::map<int, int>& indexMap, std::vector<int>& combined)
986 int numInners =
static_cast<int>(inners.size());
987 std::vector<std::pair<ComputeType, int>> pairs(numInners);
988 for (
int p = 0;
p < numInners; ++
p)
990 int numIndices =
static_cast<int>(inners[
p].size());
991 int const*
indices = inners[
p].data();
993 for (
int j = 1; j < numIndices; ++j)
1001 pairs[
p].first = xmax;
1002 pairs[
p].second =
p;
1004 std::sort(pairs.begin(), pairs.end());
1007 Polygon currentPolygon = outer;
1008 for (
int p = numInners - 1;
p >= 0; --
p)
1010 Polygon const& polygon = inners[pairs[
p].second];
1012 if (!
CombinePolygons(nextElement, currentPolygon, polygon, indexMap, currentCombined))
1016 currentPolygon = std::move(currentCombined);
1020 for (
auto index : currentPolygon)
1022 combined.push_back(
index);
1027 template <
typename InputType,
typename ComputeType>
1034 for (
int i = 0; i < 3; ++i)
1036 auto iter = indexMap.find(tri[i]);
1037 if (iter != indexMap.end())
1039 tri[i] = iter->second;
1045 template <
typename InputType,
typename ComputeType>
1050 int numExtraPoints = 0;
1052 std::queue<std::shared_ptr<Tree>> treeQueue;
1053 treeQueue.push(tree);
1054 while (treeQueue.size() > 0)
1057 std::shared_ptr<Tree> outer = treeQueue.front();
1061 int numChildren =
static_cast<int>(outer->child.size());
1062 numExtraPoints += 2 * numChildren;
1065 int const numOuterIndices =
static_cast<int>(outer->polygon.size());
1066 int const* outerIndices = outer->polygon.data();
1067 for (
int i = 0; i < numOuterIndices; ++i)
1069 int index = outerIndices[i];
1073 for (
int j = 0; j < 2; ++j)
1082 for (
int c = 0;
c < numChildren; ++
c)
1085 std::shared_ptr<Tree> inner = outer->child[
c];
1088 int const numInnerIndices =
static_cast<int>(inner->polygon.size());
1089 int const* innerIndices = inner->polygon.data();
1090 for (
int i = 0; i < numInnerIndices; ++i)
1092 int index = innerIndices[i];
1096 for (
int j = 0; j < 2; ++j)
1103 int numGrandChildren =
static_cast<int>(inner->child.size());
1104 for (
int g = 0;
g < numGrandChildren; ++
g)
1106 treeQueue.push(inner->child[
g]);
1111 return numExtraPoints;
1114 template <
typename InputType,
typename ComputeType>
1129 template <
typename InputType,
typename ComputeType>
inline 1135 template <
typename InputType,
typename ComputeType>
1139 int curr = vertex.
index;
1146 template <
typename InputType,
typename ComputeType>
1154 vertex.
isEar =
true;
1161 int curr = vertex.
index;
1163 vertex.
isEar =
true;
1167 if (j == vertex.
vPrev || j == i || j == vertex.
vNext)
1188 vertex.
isEar =
false;
1193 return vertex.
isEar;
1196 template <
typename InputType,
typename ComputeType>
1212 template <
typename InputType,
typename ComputeType>
1228 template <
typename InputType,
typename ComputeType>
1242 template <
typename InputType,
typename ComputeType>
1246 int currENext = first.
eNext;
1249 vertex.
eNext = currENext;
1254 template <
typename InputType,
typename ComputeType>
1258 int currEPrev = first.
ePrev;
1260 vertex.
ePrev = currEPrev;
1266 template <
typename InputType,
typename ComputeType>
1269 int currVPrev =
V(i).
vPrev;
1270 int currVNext =
V(i).
vNext;
1271 V(currVPrev).
vNext = currVNext;
1272 V(currVNext).
vPrev = currVPrev;
1275 template <
typename InputType,
typename ComputeType>
1278 int currEPrev =
V(i).
ePrev;
1279 int currENext =
V(i).
eNext;
1280 V(currEPrev).
eNext = currENext;
1281 V(currENext).
ePrev = currEPrev;
1285 template <
typename InputType,
typename ComputeType>
1310 int currSPrev =
V(i).
sPrev;
1311 int currSNext =
V(i).
sNext;
1312 V(currSPrev).
sNext = currSNext;
1313 V(currSNext).
sPrev = currSPrev;
PrimalQuery2< ComputeType > mQuery
void Set(int numVertices, Vector2< Real > const *vertices)
#define LogAssert(condition, message)
std::vector< int > Polygon
std::vector< std::array< int, 3 > > mTriangles
Vector2< InputType > const * mPoints
void DoEarClipping(int numVertices, int const *indices)
bool ProcessOuterAndInners(int &nextElement, Polygon const &outer, std::vector< Polygon > const &inners, std::map< int, int > &indexMap, std::vector< int > &combined)
GLfixed GLfixed GLint GLint GLfixed points
void RemapIndices(std::map< int, int > const &indexMap)
int ToLine(int i, int v0, int v1) const
GLsizei GLenum const void * indices
typedef int(WINAPI *PFNWGLRELEASEPBUFFERDCARBPROC)(HPBUFFERARB hPbuffer
#define LogError(message)
std::vector< std::shared_ptr< Tree > > child
Real DotPerp(Vector2< Real > const &v0, Vector2< Real > const &v1)
DualQuaternion< Real > Dot(DualQuaternion< Real > const &d0, DualQuaternion< Real > const &d1)
int ToTriangle(int i, int v0, int v1, int v2) const
std::vector< std::array< int, 3 > > const & GetTriangles() const
bool CombinePolygons(int nextElement, Polygon const &outer, Polygon const &inner, std::map< int, int > &indexMap, std::vector< int > &combined)
std::vector< Vector2< ComputeType > > mComputePoints
void InsertBeforeE(int i)
int InitializeFromTree(std::shared_ptr< Tree > const &tree)
std::vector< Vertex > mVertices
void InitializeVertices(int numVertices, int const *indices)
TriangulateEC(int numPoints, Vector2< InputType > const *points)
std::vector< bool > mIsConverted