13 template <std::
size_t I,
typename T>
struct nth {
14 inline static typename std::tuple_element<I, T>::type
15 get(
const T& t) {
return std::get<I>(t); };
22 template <
typename N = u
int32_t>
26 std::size_t vertices = 0;
28 template <
typename Polygon>
29 void operator()(
const Polygon& points);
33 Node(N index,
double x_,
double y_) : i(index),
x(x_),
y(y_) {}
35 Node& operator=(
const Node&) =
delete;
58 template <
typename Ring>
Node* linkedList(
const Ring& points,
const bool clockwise);
60 void earcutLinked(
Node* ear,
int pass = 0);
61 bool isEar(
Node* ear);
62 bool isEarHashed(
Node* ear);
63 Node* cureLocalIntersections(
Node* start);
64 void splitEarcut(
Node* start);
65 template <
typename Polygon>
Node* eliminateHoles(
const Polygon& points,
Node* outerNode);
66 void eliminateHole(
Node* hole,
Node* outerNode);
68 void indexCurve(
Node* start);
70 int32_t zOrder(
const double x_,
const double y_);
72 bool pointInTriangle(
double ax,
double ay,
double bx,
double by,
double cx,
double cy,
double px,
double py)
const;
73 bool isValidDiagonal(
Node* a,
Node* b);
74 double area(
const Node* p,
const Node* q,
const Node* r)
const;
76 bool intersects(
const Node* p1,
const Node* q1,
const Node* p2,
const Node* q2);
77 bool intersectsPolygon(
const Node* a,
const Node* b);
78 bool locallyInside(
const Node* a,
const Node* b);
79 bool middleInside(
const Node* a,
const Node* b);
81 template <
typename Po
int>
Node* insertNode(std::size_t i,
const Point& p,
Node* last);
82 void removeNode(
Node* p);
89 template <
typename T,
typename Alloc = std::allocator<T>>
99 template <
typename... Args>
101 if (currentIndex >= blockSize) {
102 currentBlock = alloc_traits::allocate(alloc, blockSize);
103 allocations.emplace_back(currentBlock);
106 T*
object = ¤tBlock[currentIndex++];
107 alloc_traits::construct(alloc,
object, std::forward<Args>(
args)...);
110 void reset(std::size_t newBlockSize) {
111 for (
auto allocation : allocations) {
112 alloc_traits::deallocate(alloc, allocation, blockSize);
115 blockSize = std::max<std::size_t>(1, newBlockSize);
116 currentBlock =
nullptr;
117 currentIndex = blockSize;
121 T* currentBlock =
nullptr;
122 std::size_t currentIndex = 1;
123 std::size_t blockSize = 1;
131 template <
typename N>
template <
typename Polygon>
137 if (points.empty())
return;
144 for (
size_t i = 0; threshold >= 0 && i < points.size(); i++) {
145 threshold -=
static_cast<int>(points[i].size());
146 len += points[i].size();
150 nodes.reset(len * 3 / 2);
151 indices.reserve(len + points[0].size());
153 Node* outerNode = linkedList(points[0],
true);
154 if (!outerNode || outerNode->
prev == outerNode->
next)
return;
156 if (points.size() > 1) outerNode = eliminateHoles(points, outerNode);
159 hashing = threshold < 0;
162 minX = maxX = outerNode->
x;
163 minY = maxY = outerNode->
y;
167 minX = std::min<double>(minX, x);
168 minY = std::min<double>(minY, y);
169 maxX = std::max<double>(maxX, x);
170 maxY = std::max<double>(maxY, y);
172 }
while (p != outerNode);
175 inv_size = std::max<double>(maxX - minX, maxY - minY);
176 inv_size = inv_size != .0 ? (1. / inv_size) : .0;
179 earcutLinked(outerNode);
185 template <
typename N>
template <
typename Ring>
188 using Point =
typename Ring::value_type;
190 const std::size_t len = points.size();
192 Node* last =
nullptr;
195 for (i = 0, j = len > 0 ? len - 1 : 0; i < len; j = i++) {
196 const auto& p1 = points[i];
197 const auto& p2 = points[j];
202 sum += (p20 - p10) * (p11 + p21);
206 if (clockwise == (sum > 0)) {
207 for (i = 0; i < len; i++) last = insertNode(vertices + i, points[i], last);
209 for (i = len; i-- > 0;) last = insertNode(vertices + i, points[i], last);
223 template <
typename N>
226 if (!end) end = start;
237 if (p == p->
next)
break;
243 }
while (again || p != end);
249 template <
typename N>
254 if (!pass && hashing) indexCurve(ear);
268 if (hashing ? isEarHashed(ear) : isEar(ear)) {
270 indices.emplace_back(prev->
i);
271 indices.emplace_back(ear->
i);
272 indices.emplace_back(next->
i);
288 if (!pass) earcutLinked(filterPoints(ear), 1);
291 else if (pass == 1) {
292 ear = cureLocalIntersections(ear);
293 earcutLinked(ear, 2);
296 }
else if (pass == 2) splitEarcut(ear);
304 template <
typename N>
310 if (area(a, b, c) >= 0)
return false;
315 while (p != ear->
prev) {
316 if (pointInTriangle(a->
x, a->
y, b->
x, b->
y, c->
x, c->
y, p->
x, p->
y) &&
317 area(p->
prev, p, p->
next) >= 0)
return false;
324 template <
typename N>
330 if (area(a, b, c) >= 0)
return false;
333 const double minTX = std::min<double>(a->
x, std::min<double>(b->
x, c->
x));
334 const double minTY = std::min<double>(a->
y, std::min<double>(b->
y, c->
y));
335 const double maxTX = std::max<double>(a->
x, std::max<double>(b->
x, c->
x));
336 const double maxTY = std::max<double>(a->
y, std::max<double>(b->
y, c->
y));
339 const int32_t minZ = zOrder(minTX, minTY);
340 const int32_t maxZ = zOrder(maxTX, maxTY);
345 while (p && p->
z <= maxZ) {
346 if (p != ear->
prev && p != ear->
next &&
347 pointInTriangle(a->
x, a->
y, b->
x, b->
y, c->
x, c->
y, p->
x, p->
y) &&
348 area(p->
prev, p, p->
next) >= 0)
return false;
355 while (p && p->
z >= minZ) {
356 if (p != ear->
prev && p != ear->
next &&
357 pointInTriangle(a->
x, a->
y, b->
x, b->
y, c->
x, c->
y, p->
x, p->
y) &&
358 area(p->
prev, p, p->
next) >= 0)
return false;
366 template <
typename N>
375 if (!
equals(a, b) && intersects(a, p, p->
next, b) && locallyInside(a, b) && locallyInside(b, a)) {
376 indices.emplace_back(a->
i);
377 indices.emplace_back(p->
i);
378 indices.emplace_back(b->
i);
387 }
while (p != start);
393 template <
typename N>
399 while (b != a->
prev) {
400 if (a->
i != b->
i && isValidDiagonal(a, b)) {
402 Node* c = splitPolygon(a, b);
405 a = filterPoints(a, a->
next);
406 c = filterPoints(c, c->
next);
416 }
while (a != start);
420 template <
typename N>
template <
typename Polygon>
423 const size_t len = points.size();
425 std::vector<Node*> queue;
426 for (
size_t i = 1; i < len; i++) {
427 Node* list = linkedList(points[i],
false);
430 queue.push_back(getLeftmost(list));
433 std::sort(queue.begin(), queue.end(), [](
const Node* a,
const Node* b) {
438 for (
size_t i = 0; i < queue.size(); i++) {
439 eliminateHole(queue[i], outerNode);
440 outerNode = filterPoints(outerNode, outerNode->
next);
447 template <
typename N>
449 outerNode = findHoleBridge(hole, outerNode);
451 Node* b = splitPolygon(outerNode, hole);
452 filterPoints(b, b->
next);
457 template <
typename N>
463 double qx = -std::numeric_limits<double>::infinity();
469 if (hy <= p->
y && hy >= p->
next->
y && p->
next->
y != p->
y) {
470 double x = p->
x + (hy - p->
y) * (p->
next->
x - p->
x) / (p->
next->
y - p->
y);
471 if (x <= hx && x > qx) {
474 if (hy == p->
y)
return p;
481 }
while (p != outerNode);
485 if (hx == qx)
return m->
prev;
491 const Node* stop = m;
492 double tanMin = std::numeric_limits<double>::infinity();
500 if (hx >= p->
x && p->
x >= mx && hx != p->
x &&
501 pointInTriangle(hy < my ? hx : qx, hy, mx, my, hy < my ? qx : hx, hy, p->
x, p->
y)) {
503 tanCur = std::abs(hy - p->
y) / (hx - p->
x);
505 if ((tanCur < tanMin || (tanCur == tanMin && p->
x > m->
x)) && locallyInside(p, hole)) {
518 template <
typename N>
524 p->
z = p->
z ? p->
z : zOrder(p->
x, p->
y);
528 }
while (p != start);
538 template <
typename N>
546 int i, numMerges, pSize, qSize;
559 for (i = 0; i < inSize; i++) {
567 while (pSize > 0 || (qSize > 0 && q)) {
573 }
else if (qSize == 0 || !q) {
577 }
else if (p->
z <= q->
z) {
587 if (tail) tail->
nextZ = e;
597 tail->
nextZ =
nullptr;
599 if (numMerges <= 1)
return list;
606 template <
typename N>
609 int32_t
x =
static_cast<int32_t
>(32767.0 * (x_ - minX) * inv_size);
610 int32_t
y =
static_cast<int32_t
>(32767.0 * (y_ - minY) * inv_size);
612 x = (x | (x << 8)) & 0x00FF00FF;
613 x = (x | (x << 4)) & 0x0F0F0F0F;
614 x = (x | (x << 2)) & 0x33333333;
615 x = (x | (x << 1)) & 0x55555555;
617 y = (y | (y << 8)) & 0x00FF00FF;
618 y = (y | (y << 4)) & 0x0F0F0F0F;
619 y = (y | (y << 2)) & 0x33333333;
620 y = (y | (y << 1)) & 0x55555555;
626 template <
typename N>
630 Node* leftmost = start;
632 if (p->
x < leftmost->
x || (p->
x == leftmost->
x && p->
y < leftmost->
y))
635 }
while (p != start);
641 template <
typename N>
643 return (cx - px) * (ay - py) - (ax - px) * (cy - py) >= 0 &&
644 (ax - px) * (by - py) - (bx - px) * (ay - py) >= 0 &&
645 (bx - px) * (cy - py) - (cx - px) * (by - py) >= 0;
649 template <
typename N>
651 return a->
next->
i != b->
i && a->
prev->
i != b->
i && !intersectsPolygon(a, b) &&
652 locallyInside(a, b) && locallyInside(b, a) && middleInside(a, b);
656 template <
typename N>
658 return (q->
y - p->
y) * (r->
x - q->
x) - (q->
x - p->
x) * (r->
y - q->
y);
662 template <
typename N>
664 return p1->
x == p2->
x && p1->
y == p2->
y;
668 template <
typename N>
672 return (area(p1, q1, p2) > 0) != (area(p1, q1, q2) > 0) &&
673 (area(p2, q2, p1) > 0) != (area(p2, q2, q1) > 0);
677 template <
typename N>
681 if (p->
i != a->
i && p->
next->
i != a->
i && p->
i != b->
i && p->
next->
i != b->
i &&
682 intersects(p, p->
next, a, b))
return true;
690 template <
typename N>
692 return area(a->
prev, a, a->
next) < 0 ?
693 area(a, b, a->
next) >= 0 && area(a, a->
prev, b) >= 0 :
694 area(a, b, a->
prev) < 0 || area(a, a->
next, b) < 0;
698 template <
typename N>
702 double px = (a->
x + b->
x) / 2;
703 double py = (a->
y + b->
y) / 2;
705 if (((p->
y > py) != (p->
next->
y > py)) && p->
next->
y != p->
y &&
706 (px < (p->
next->
x - p->
x) * (py - p->
y) / (p->
next->
y - p->
y) + p->
x))
717 template <
typename N>
720 Node* a2 = nodes.construct(a->
i, a->
x, a->
y);
721 Node* b2 = nodes.construct(b->
i, b->
x, b->
y);
741 template <
typename N>
template <
typename Po
int>
760 template <
typename N>
770 template <
typename N = u
int32_t,
typename Polygon>
771 std::vector<N>
earcut(
const Polygon& poly) {
774 return std::move(earcut.
indices);
ObjectPool(std::size_t blockSize_)
std::vector< T * > allocations
bool equals(const nav_2d_msgs::Polygon2D &polygon0, const nav_2d_msgs::Polygon2D &polygon1)
check if two polygons are equal. Used in testing
TFSIMD_FORCE_INLINE const tfScalar & y() const
Node(N index, double x_, double y_)
std::allocator_traits< Alloc > alloc_traits
static std::tuple_element< I, T >::type get(const T &t)
TFSIMD_FORCE_INLINE const tfScalar & x() const
std::vector< N > earcut(const Polygon &poly)
TFSIMD_FORCE_INLINE const tfScalar & z() const
void reset(std::size_t newBlockSize)
T * construct(Args &&...args)