earcut.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 #include <algorithm>
4 #include <cassert>
5 #include <cmath>
6 #include <memory>
7 #include <vector>
8 
9 namespace mapbox {
10 
11 namespace util {
12 
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); };
16 };
17 
18 }
19 
20 namespace detail {
21 
22 template <typename N = uint32_t>
23 class Earcut {
24 public:
25  std::vector<N> indices;
26  std::size_t vertices = 0;
27 
28  template <typename Polygon>
29  void operator()(const Polygon& points);
30 
31 private:
32  struct Node {
33  Node(N index, double x_, double y_) : i(index), x(x_), y(y_) {}
34  Node(const Node&) = delete;
35  Node& operator=(const Node&) = delete;
36  Node(Node&&) = delete;
37  Node& operator=(Node&&) = delete;
38 
39  const N i;
40  const double x;
41  const double y;
42 
43  // previous and next vertice nodes in a polygon ring
44  Node* prev = nullptr;
45  Node* next = nullptr;
46 
47  // z-order curve value
48  int32_t z = 0;
49 
50  // previous and next nodes in z-order
51  Node* prevZ = nullptr;
52  Node* nextZ = nullptr;
53 
54  // indicates whether this is a steiner point
55  bool steiner = false;
56  };
57 
58  template <typename Ring> Node* linkedList(const Ring& points, const bool clockwise);
59  Node* filterPoints(Node* start, Node* end = nullptr);
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);
67  Node* findHoleBridge(Node* hole, Node* outerNode);
68  void indexCurve(Node* start);
69  Node* sortLinked(Node* list);
70  int32_t zOrder(const double x_, const double y_);
71  Node* getLeftmost(Node* start);
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;
75  bool equals(const Node* p1, const Node* p2);
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);
80  Node* splitPolygon(Node* a, Node* b);
81  template <typename Point> Node* insertNode(std::size_t i, const Point& p, Node* last);
82  void removeNode(Node* p);
83 
84  bool hashing;
85  double minX, maxX;
86  double minY, maxY;
87  double inv_size = 0;
88 
89  template <typename T, typename Alloc = std::allocator<T>>
90  class ObjectPool {
91  public:
92  ObjectPool() { }
93  ObjectPool(std::size_t blockSize_) {
94  reset(blockSize_);
95  }
97  clear();
98  }
99  template <typename... Args>
100  T* construct(Args&&... args) {
101  if (currentIndex >= blockSize) {
102  currentBlock = alloc_traits::allocate(alloc, blockSize);
103  allocations.emplace_back(currentBlock);
104  currentIndex = 0;
105  }
106  T* object = &currentBlock[currentIndex++];
107  alloc_traits::construct(alloc, object, std::forward<Args>(args)...);
108  return object;
109  }
110  void reset(std::size_t newBlockSize) {
111  for (auto allocation : allocations) {
112  alloc_traits::deallocate(alloc, allocation, blockSize);
113  }
114  allocations.clear();
115  blockSize = std::max<std::size_t>(1, newBlockSize);
116  currentBlock = nullptr;
117  currentIndex = blockSize;
118  }
119  void clear() { reset(blockSize); }
120  private:
121  T* currentBlock = nullptr;
122  std::size_t currentIndex = 1;
123  std::size_t blockSize = 1;
124  std::vector<T*> allocations;
125  Alloc alloc;
126  typedef typename std::allocator_traits<Alloc> alloc_traits;
127  };
129 };
130 
131 template <typename N> template <typename Polygon>
132 void Earcut<N>::operator()(const Polygon& points) {
133  // reset
134  indices.clear();
135  vertices = 0;
136 
137  if (points.empty()) return;
138 
139  double x;
140  double y;
141  int threshold = 80;
142  std::size_t len = 0;
143 
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();
147  }
148 
149  //estimate size of nodes and indices
150  nodes.reset(len * 3 / 2);
151  indices.reserve(len + points[0].size());
152 
153  Node* outerNode = linkedList(points[0], true);
154  if (!outerNode || outerNode->prev == outerNode->next) return;
155 
156  if (points.size() > 1) outerNode = eliminateHoles(points, outerNode);
157 
158  // if the shape is not too simple, we'll use z-order curve hash later; calculate polygon bbox
159  hashing = threshold < 0;
160  if (hashing) {
161  Node* p = outerNode->next;
162  minX = maxX = outerNode->x;
163  minY = maxY = outerNode->y;
164  do {
165  x = p->x;
166  y = p->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);
171  p = p->next;
172  } while (p != outerNode);
173 
174  // minX, minY and size are later used to transform coords into integers for z-order calculation
175  inv_size = std::max<double>(maxX - minX, maxY - minY);
176  inv_size = inv_size != .0 ? (1. / inv_size) : .0;
177  }
178 
179  earcutLinked(outerNode);
180 
181  nodes.clear();
182 }
183 
184 // create a circular doubly linked list from polygon points in the specified winding order
185 template <typename N> template <typename Ring>
186 typename Earcut<N>::Node*
187 Earcut<N>::linkedList(const Ring& points, const bool clockwise) {
188  using Point = typename Ring::value_type;
189  double sum = 0;
190  const std::size_t len = points.size();
191  std::size_t i, j;
192  Node* last = nullptr;
193 
194  // calculate original winding order of a polygon ring
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];
198  const double p20 = util::nth<0, Point>::get(p2);
199  const double p10 = util::nth<0, Point>::get(p1);
200  const double p11 = util::nth<1, Point>::get(p1);
201  const double p21 = util::nth<1, Point>::get(p2);
202  sum += (p20 - p10) * (p11 + p21);
203  }
204 
205  // link points into circular doubly-linked list in the specified winding order
206  if (clockwise == (sum > 0)) {
207  for (i = 0; i < len; i++) last = insertNode(vertices + i, points[i], last);
208  } else {
209  for (i = len; i-- > 0;) last = insertNode(vertices + i, points[i], last);
210  }
211 
212  if (last && equals(last, last->next)) {
213  removeNode(last);
214  last = last->next;
215  }
216 
217  vertices += len;
218 
219  return last;
220 }
221 
222 // eliminate colinear or duplicate points
223 template <typename N>
224 typename Earcut<N>::Node*
226  if (!end) end = start;
227 
228  Node* p = start;
229  bool again;
230  do {
231  again = false;
232 
233  if (!p->steiner && (equals(p, p->next) || area(p->prev, p, p->next) == 0)) {
234  removeNode(p);
235  p = end = p->prev;
236 
237  if (p == p->next) break;
238  again = true;
239 
240  } else {
241  p = p->next;
242  }
243  } while (again || p != end);
244 
245  return end;
246 }
247 
248 // main ear slicing loop which triangulates a polygon (given as a linked list)
249 template <typename N>
250 void Earcut<N>::earcutLinked(Node* ear, int pass) {
251  if (!ear) return;
252 
253  // interlink polygon nodes in z-order
254  if (!pass && hashing) indexCurve(ear);
255 
256  Node* stop = ear;
257  Node* prev;
258  Node* next;
259 
260  int iterations = 0;
261 
262  // iterate through ears, slicing them one by one
263  while (ear->prev != ear->next) {
264  iterations++;
265  prev = ear->prev;
266  next = ear->next;
267 
268  if (hashing ? isEarHashed(ear) : isEar(ear)) {
269  // cut off the triangle
270  indices.emplace_back(prev->i);
271  indices.emplace_back(ear->i);
272  indices.emplace_back(next->i);
273 
274  removeNode(ear);
275 
276  // skipping the next vertice leads to less sliver triangles
277  ear = next->next;
278  stop = next->next;
279 
280  continue;
281  }
282 
283  ear = next;
284 
285  // if we looped through the whole remaining polygon and can't find any more ears
286  if (ear == stop) {
287  // try filtering points and slicing again
288  if (!pass) earcutLinked(filterPoints(ear), 1);
289 
290  // if this didn't work, try curing all small self-intersections locally
291  else if (pass == 1) {
292  ear = cureLocalIntersections(ear);
293  earcutLinked(ear, 2);
294 
295  // as a last resort, try splitting the remaining polygon into two
296  } else if (pass == 2) splitEarcut(ear);
297 
298  break;
299  }
300  }
301 }
302 
303 // check whether a polygon node forms a valid ear with adjacent nodes
304 template <typename N>
305 bool Earcut<N>::isEar(Node* ear) {
306  const Node* a = ear->prev;
307  const Node* b = ear;
308  const Node* c = ear->next;
309 
310  if (area(a, b, c) >= 0) return false; // reflex, can't be an ear
311 
312  // now make sure we don't have other points inside the potential ear
313  Node* p = ear->next->next;
314 
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;
318  p = p->next;
319  }
320 
321  return true;
322 }
323 
324 template <typename N>
326  const Node* a = ear->prev;
327  const Node* b = ear;
328  const Node* c = ear->next;
329 
330  if (area(a, b, c) >= 0) return false; // reflex, can't be an ear
331 
332  // triangle bbox; min & max are calculated like this for speed
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));
337 
338  // z-order range for the current triangle bbox;
339  const int32_t minZ = zOrder(minTX, minTY);
340  const int32_t maxZ = zOrder(maxTX, maxTY);
341 
342  // first look for points inside the triangle in increasing z-order
343  Node* p = ear->nextZ;
344 
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;
349  p = p->nextZ;
350  }
351 
352  // then look for points in decreasing z-order
353  p = ear->prevZ;
354 
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;
359  p = p->prevZ;
360  }
361 
362  return true;
363 }
364 
365 // go through all polygon nodes and cure small local self-intersections
366 template <typename N>
367 typename Earcut<N>::Node*
369  Node* p = start;
370  do {
371  Node* a = p->prev;
372  Node* b = p->next->next;
373 
374  // a self-intersection where edge (v[i-1],v[i]) intersects (v[i+1],v[i+2])
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);
379 
380  // remove two nodes involved
381  removeNode(p);
382  removeNode(p->next);
383 
384  p = start = b;
385  }
386  p = p->next;
387  } while (p != start);
388 
389  return p;
390 }
391 
392 // try splitting polygon into two and triangulate them independently
393 template <typename N>
395  // look for a valid diagonal that divides the polygon into two
396  Node* a = start;
397  do {
398  Node* b = a->next->next;
399  while (b != a->prev) {
400  if (a->i != b->i && isValidDiagonal(a, b)) {
401  // split the polygon in two by the diagonal
402  Node* c = splitPolygon(a, b);
403 
404  // filter colinear points around the cuts
405  a = filterPoints(a, a->next);
406  c = filterPoints(c, c->next);
407 
408  // run earcut on each half
409  earcutLinked(a);
410  earcutLinked(c);
411  return;
412  }
413  b = b->next;
414  }
415  a = a->next;
416  } while (a != start);
417 }
418 
419 // link every hole into the outer loop, producing a single-ring polygon without holes
420 template <typename N> template <typename Polygon>
421 typename Earcut<N>::Node*
422 Earcut<N>::eliminateHoles(const Polygon& points, Node* outerNode) {
423  const size_t len = points.size();
424 
425  std::vector<Node*> queue;
426  for (size_t i = 1; i < len; i++) {
427  Node* list = linkedList(points[i], false);
428  if (list) {
429  if (list == list->next) list->steiner = true;
430  queue.push_back(getLeftmost(list));
431  }
432  }
433  std::sort(queue.begin(), queue.end(), [](const Node* a, const Node* b) {
434  return a->x < b->x;
435  });
436 
437  // process holes from left to right
438  for (size_t i = 0; i < queue.size(); i++) {
439  eliminateHole(queue[i], outerNode);
440  outerNode = filterPoints(outerNode, outerNode->next);
441  }
442 
443  return outerNode;
444 }
445 
446 // find a bridge between vertices that connects hole with an outer ring and and link it
447 template <typename N>
448 void Earcut<N>::eliminateHole(Node* hole, Node* outerNode) {
449  outerNode = findHoleBridge(hole, outerNode);
450  if (outerNode) {
451  Node* b = splitPolygon(outerNode, hole);
452  filterPoints(b, b->next);
453  }
454 }
455 
456 // David Eberly's algorithm for finding a bridge between hole and outer polygon
457 template <typename N>
458 typename Earcut<N>::Node*
459 Earcut<N>::findHoleBridge(Node* hole, Node* outerNode) {
460  Node* p = outerNode;
461  double hx = hole->x;
462  double hy = hole->y;
463  double qx = -std::numeric_limits<double>::infinity();
464  Node* m = nullptr;
465 
466  // find a segment intersected by a ray from the hole's leftmost Vertex to the left;
467  // segment's endpoint with lesser x will be potential connection Vertex
468  do {
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) {
472  qx = x;
473  if (x == hx) {
474  if (hy == p->y) return p;
475  if (hy == p->next->y) return p->next;
476  }
477  m = p->x < p->next->x ? p : p->next;
478  }
479  }
480  p = p->next;
481  } while (p != outerNode);
482 
483  if (!m) return 0;
484 
485  if (hx == qx) return m->prev;
486 
487  // look for points inside the triangle of hole Vertex, segment intersection and endpoint;
488  // if there are no points found, we have a valid connection;
489  // otherwise choose the Vertex of the minimum angle with the ray as connection Vertex
490 
491  const Node* stop = m;
492  double tanMin = std::numeric_limits<double>::infinity();
493  double tanCur = 0;
494 
495  p = m->next;
496  double mx = m->x;
497  double my = m->y;
498 
499  while (p != stop) {
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)) {
502 
503  tanCur = std::abs(hy - p->y) / (hx - p->x); // tangential
504 
505  if ((tanCur < tanMin || (tanCur == tanMin && p->x > m->x)) && locallyInside(p, hole)) {
506  m = p;
507  tanMin = tanCur;
508  }
509  }
510 
511  p = p->next;
512  }
513 
514  return m;
515 }
516 
517 // interlink polygon nodes in z-order
518 template <typename N>
520  assert(start);
521  Node* p = start;
522 
523  do {
524  p->z = p->z ? p->z : zOrder(p->x, p->y);
525  p->prevZ = p->prev;
526  p->nextZ = p->next;
527  p = p->next;
528  } while (p != start);
529 
530  p->prevZ->nextZ = nullptr;
531  p->prevZ = nullptr;
532 
533  sortLinked(p);
534 }
535 
536 // Simon Tatham's linked list merge sort algorithm
537 // http://www.chiark.greenend.org.uk/~sgtatham/algorithms/listsort.html
538 template <typename N>
539 typename Earcut<N>::Node*
541  assert(list);
542  Node* p;
543  Node* q;
544  Node* e;
545  Node* tail;
546  int i, numMerges, pSize, qSize;
547  int inSize = 1;
548 
549  for (;;) {
550  p = list;
551  list = nullptr;
552  tail = nullptr;
553  numMerges = 0;
554 
555  while (p) {
556  numMerges++;
557  q = p;
558  pSize = 0;
559  for (i = 0; i < inSize; i++) {
560  pSize++;
561  q = q->nextZ;
562  if (!q) break;
563  }
564 
565  qSize = inSize;
566 
567  while (pSize > 0 || (qSize > 0 && q)) {
568 
569  if (pSize == 0) {
570  e = q;
571  q = q->nextZ;
572  qSize--;
573  } else if (qSize == 0 || !q) {
574  e = p;
575  p = p->nextZ;
576  pSize--;
577  } else if (p->z <= q->z) {
578  e = p;
579  p = p->nextZ;
580  pSize--;
581  } else {
582  e = q;
583  q = q->nextZ;
584  qSize--;
585  }
586 
587  if (tail) tail->nextZ = e;
588  else list = e;
589 
590  e->prevZ = tail;
591  tail = e;
592  }
593 
594  p = q;
595  }
596 
597  tail->nextZ = nullptr;
598 
599  if (numMerges <= 1) return list;
600 
601  inSize *= 2;
602  }
603 }
604 
605 // z-order of a Vertex given coords and size of the data bounding box
606 template <typename N>
607 int32_t Earcut<N>::zOrder(const double x_, const double y_) {
608  // coords are transformed into non-negative 15-bit integer range
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);
611 
612  x = (x | (x << 8)) & 0x00FF00FF;
613  x = (x | (x << 4)) & 0x0F0F0F0F;
614  x = (x | (x << 2)) & 0x33333333;
615  x = (x | (x << 1)) & 0x55555555;
616 
617  y = (y | (y << 8)) & 0x00FF00FF;
618  y = (y | (y << 4)) & 0x0F0F0F0F;
619  y = (y | (y << 2)) & 0x33333333;
620  y = (y | (y << 1)) & 0x55555555;
621 
622  return x | (y << 1);
623 }
624 
625 // find the leftmost node of a polygon ring
626 template <typename N>
627 typename Earcut<N>::Node*
629  Node* p = start;
630  Node* leftmost = start;
631  do {
632  if (p->x < leftmost->x || (p->x == leftmost->x && p->y < leftmost->y))
633  leftmost = p;
634  p = p->next;
635  } while (p != start);
636 
637  return leftmost;
638 }
639 
640 // check if a point lies within a convex triangle
641 template <typename N>
642 bool Earcut<N>::pointInTriangle(double ax, double ay, double bx, double by, double cx, double cy, double px, double py) const {
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;
646 }
647 
648 // check if a diagonal between two polygon nodes is valid (lies in polygon interior)
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);
653 }
654 
655 // signed area of a triangle
656 template <typename N>
657 double Earcut<N>::area(const Node* p, const Node* q, const Node* r) const {
658  return (q->y - p->y) * (r->x - q->x) - (q->x - p->x) * (r->y - q->y);
659 }
660 
661 // check if two points are equal
662 template <typename N>
663 bool Earcut<N>::equals(const Node* p1, const Node* p2) {
664  return p1->x == p2->x && p1->y == p2->y;
665 }
666 
667 // check if two segments intersect
668 template <typename N>
669 bool Earcut<N>::intersects(const Node* p1, const Node* q1, const Node* p2, const Node* q2) {
670  if ((equals(p1, q1) && equals(p2, q2)) ||
671  (equals(p1, q2) && equals(p2, q1))) return true;
672  return (area(p1, q1, p2) > 0) != (area(p1, q1, q2) > 0) &&
673  (area(p2, q2, p1) > 0) != (area(p2, q2, q1) > 0);
674 }
675 
676 // check if a polygon diagonal intersects any polygon segments
677 template <typename N>
678 bool Earcut<N>::intersectsPolygon(const Node* a, const Node* b) {
679  const Node* p = a;
680  do {
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;
683  p = p->next;
684  } while (p != a);
685 
686  return false;
687 }
688 
689 // check if a polygon diagonal is locally inside the polygon
690 template <typename N>
691 bool Earcut<N>::locallyInside(const Node* a, const Node* b) {
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;
695 }
696 
697 // check if the middle Vertex of a polygon diagonal is inside the polygon
698 template <typename N>
699 bool Earcut<N>::middleInside(const Node* a, const Node* b) {
700  const Node* p = a;
701  bool inside = false;
702  double px = (a->x + b->x) / 2;
703  double py = (a->y + b->y) / 2;
704  do {
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))
707  inside = !inside;
708  p = p->next;
709  } while (p != a);
710 
711  return inside;
712 }
713 
714 // link two polygon vertices with a bridge; if the vertices belong to the same ring, it splits
715 // polygon into two; if one belongs to the outer ring and another to a hole, it merges it into a
716 // single ring
717 template <typename N>
718 typename Earcut<N>::Node*
720  Node* a2 = nodes.construct(a->i, a->x, a->y);
721  Node* b2 = nodes.construct(b->i, b->x, b->y);
722  Node* an = a->next;
723  Node* bp = b->prev;
724 
725  a->next = b;
726  b->prev = a;
727 
728  a2->next = an;
729  an->prev = a2;
730 
731  b2->next = a2;
732  a2->prev = b2;
733 
734  bp->next = b2;
735  b2->prev = bp;
736 
737  return b2;
738 }
739 
740 // create a node and util::optionally link it with previous one (in a circular doubly linked list)
741 template <typename N> template <typename Point>
742 typename Earcut<N>::Node*
743 Earcut<N>::insertNode(std::size_t i, const Point& pt, Node* last) {
744  Node* p = nodes.construct(static_cast<N>(i), util::nth<0, Point>::get(pt), util::nth<1, Point>::get(pt));
745 
746  if (!last) {
747  p->prev = p;
748  p->next = p;
749 
750  } else {
751  assert(last);
752  p->next = last->next;
753  p->prev = last;
754  last->next->prev = p;
755  last->next = p;
756  }
757  return p;
758 }
759 
760 template <typename N>
762  p->next->prev = p->prev;
763  p->prev->next = p->next;
764 
765  if (p->prevZ) p->prevZ->nextZ = p->nextZ;
766  if (p->nextZ) p->nextZ->prevZ = p->prevZ;
767 }
768 }
769 
770 template <typename N = uint32_t, typename Polygon>
771 std::vector<N> earcut(const Polygon& poly) {
773  earcut(poly);
774  return std::move(earcut.indices);
775 }
776 }
ObjectPool(std::size_t blockSize_)
Definition: earcut.hpp:93
std::vector< T * > allocations
Definition: earcut.hpp:124
bool equals(const nav_2d_msgs::Polygon2D &polygon0, const nav_2d_msgs::Polygon2D &polygon1)
check if two polygons are equal. Used in testing
Definition: polygons.cpp:350
TFSIMD_FORCE_INLINE const tfScalar & y() const
Node(N index, double x_, double y_)
Definition: earcut.hpp:33
std::allocator_traits< Alloc > alloc_traits
Definition: earcut.hpp:126
static std::tuple_element< I, T >::type get(const T &t)
Definition: earcut.hpp:15
TFSIMD_FORCE_INLINE const tfScalar & x() const
std::vector< N > earcut(const Polygon &poly)
Definition: earcut.hpp:771
TFSIMD_FORCE_INLINE const tfScalar & z() const
ObjectPool< Node > nodes
Definition: earcut.hpp:128
std::vector< N > indices
Definition: earcut.hpp:25
void reset(std::size_t newBlockSize)
Definition: earcut.hpp:110
Definition: earcut.hpp:9
T * construct(Args &&...args)
Definition: earcut.hpp:100


nav_2d_utils
Author(s):
autogenerated on Sun Jan 10 2021 04:08:32