g2d.c
Go to the documentation of this file.
1 /* Copyright (C) 2013-2016, The Regents of The University of Michigan.
2 All rights reserved.
3 This software was developed in the APRIL Robotics Lab under the
4 direction of Edwin Olson, ebolson@umich.edu. This software may be
5 available under alternative licensing terms; contact the address above.
6 Redistribution and use in source and binary forms, with or without
7 modification, are permitted provided that the following conditions are met:
8 1. Redistributions of source code must retain the above copyright notice, this
9  list of conditions and the following disclaimer.
10 2. Redistributions in binary form must reproduce the above copyright notice,
11  this list of conditions and the following disclaimer in the documentation
12  and/or other materials provided with the distribution.
13 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
14 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
15 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
16 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR
17 ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
18 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
19 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
20 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
21 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
22 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
23 The views and conclusions contained in the software and documentation are those
24 of the authors and should not be interpreted as representing official policies,
25 either expressed or implied, of the Regents of The University of Michigan.
26 */
27 
28 #include <assert.h>
29 #include <math.h>
30 #include <stdio.h>
31 #include <string.h>
32 
33 #include "g2d.h"
34 #include "common/math_util.h"
35 
36 double g2d_distance(const double a[2], const double b[2])
37 {
38  return sqrtf(sq(a[0]-b[0]) + sq(a[1]-b[1]));
39 }
40 
42 {
43  return zarray_create(sizeof(double[2]));
44 }
45 
46 void g2d_polygon_add(zarray_t *poly, double v[2])
47 {
48  zarray_add(poly, v);
49 }
50 
51 zarray_t *g2d_polygon_create_data(double v[][2], int sz)
52 {
54 
55  for (int i = 0; i < sz; i++)
56  g2d_polygon_add(points, v[i]);
57 
58  return points;
59 }
60 
62 {
63  zarray_t *points = zarray_create(sizeof(double[2]));
64 
65  double z[2] = { 0, 0 };
66 
67  for (int i = 0; i < sz; i++)
68  zarray_add(points, z);
69 
70  return points;
71 }
72 
74 {
75  // Step one: we want the points in counter-clockwise order.
76  // If the points are in clockwise order, we'll reverse them.
77  double total_theta = 0;
78  double last_theta = 0;
79 
80  // Count the angle accumulated going around the polygon. If
81  // the sum is +2pi, it's CCW. Otherwise, we'll get -2pi.
82  int sz = zarray_size(poly);
83 
84  for (int i = 0; i <= sz; i++) {
85  double p0[2], p1[2];
86  zarray_get(poly, i % sz, &p0);
87  zarray_get(poly, (i+1) % sz, &p1);
88 
89  double this_theta = atan2(p1[1]-p0[1], p1[0]-p0[0]);
90 
91  if (i > 0) {
92  double dtheta = mod2pi(this_theta-last_theta);
93  total_theta += dtheta;
94  }
95 
96  last_theta = this_theta;
97  }
98 
99  int ccw = (total_theta > 0);
100 
101  // reverse order if necessary.
102  if (!ccw) {
103  for (int i = 0; i < sz / 2; i++) {
104  double a[2], b[2];
105 
106  zarray_get(poly, i, a);
107  zarray_get(poly, sz-1-i, b);
108  zarray_set(poly, i, b, NULL);
109  zarray_set(poly, sz-1-i, a, NULL);
110  }
111  }
112 }
113 
114 int g2d_polygon_contains_point_ref(const zarray_t *poly, double q[2])
115 {
116  // use winding. If the point is inside the polygon, we'll wrap
117  // around it (accumulating 6.28 radians). If we're outside the
118  // polygon, we'll accumulate zero.
119  int psz = zarray_size(poly);
120 
121  double acc_theta = 0;
122 
123  double last_theta = 0;
124 
125  for (int i = 0; i <= psz; i++) {
126  double p[2];
127 
128  zarray_get(poly, i % psz, &p);
129 
130  double this_theta = atan2(q[1]-p[1], q[0]-p[0]);
131 
132  if (i != 0)
133  acc_theta += mod2pi(this_theta - last_theta);
134 
135  last_theta = this_theta;
136  }
137 
138  return acc_theta > M_PI;
139 }
140 
141 /*
142 // sort by x coordinate, ascending
143 static int g2d_convex_hull_sort(const void *_a, const void *_b)
144 {
145  double *a = (double*) _a;
146  double *b = (double*) _b;
147 
148  if (a[0] < b[0])
149  return -1;
150  if (a[0] == b[0])
151  return 0;
152  return 1;
153 }
154 */
155 
156 /*
157 zarray_t *g2d_convex_hull2(const zarray_t *points)
158 {
159  zarray_t *hull = zarray_copy(points);
160 
161  zarray_sort(hull, g2d_convex_hull_sort);
162 
163  int hsz = zarray_size(hull);
164  int hout = 0;
165 
166  for (int hin = 1; hin < hsz; hin++) {
167  double *p;
168  zarray_get_volatile(hull, i, &p);
169 
170  // Everything to the right of hin is already convex. We now
171  // add one point, p, which begins "connected" by two
172  // (coincident) edges from the last right-most point to p.
173  double *last;
174  zarray_get_volatile(hull, hout, &last);
175 
176  // We now remove points from the convex hull by moving
177  }
178 
179  return hull;
180 }
181 */
182 
183 // creates and returns a zarray(double[2]). The resulting polygon is
184 // CCW and implicitly closed. Unnecessary colinear points are omitted.
186 {
187  zarray_t *hull = zarray_create(sizeof(double[2]));
188 
189  // gift-wrap algorithm.
190 
191  // step 1: find left most point.
192  int insz = zarray_size(points);
193 
194  // must have at least 2 points. (XXX need 3?)
195  assert(insz >= 2);
196 
197  double *pleft = NULL;
198  for (int i = 0; i < insz; i++) {
199  double *p;
200  zarray_get_volatile(points, i, &p);
201 
202  if (pleft == NULL || p[0] < pleft[0])
203  pleft = p;
204  }
205 
206  // cannot be NULL since there must be at least one point.
207  assert(pleft != NULL);
208 
209  zarray_add(hull, pleft);
210 
211  // step 2. gift wrap. Keep searching for points that make the
212  // smallest-angle left-hand turn. This implementation is carefully
213  // written to use only addition/subtraction/multiply. No division
214  // or sqrts. This guarantees exact results for integer-coordinate
215  // polygons (no rounding/precision problems).
216  double *p = pleft;
217 
218  while (1) {
219  assert(p != NULL);
220 
221  double *q = NULL;
222  double n0 = 0, n1 = 0; // the normal to the line (p, q) (not
223  // necessarily unit length).
224 
225  // Search for the point q for which the line (p,q) is most "to
226  // the right of" the other points. (i.e., every time we find a
227  // point that is to the right of our current line, we change
228  // lines.)
229  for (int i = 0; i < insz; i++) {
230  double *thisq;
231  zarray_get_volatile(points, i, &thisq);
232 
233  if (thisq == p)
234  continue;
235 
236  // the first time we find another point, we initialize our
237  // value of q, forming the line (p,q)
238  if (q == NULL) {
239  q = thisq;
240  n0 = q[1] - p[1];
241  n1 = -q[0] + p[0];
242  } else {
243  // we already have a line (p,q). is point thisq RIGHT OF line (p, q)?
244  double e0 = thisq[0] - p[0], e1 = thisq[1] - p[1];
245  double dot = e0*n0 + e1*n1;
246 
247  if (dot > 0) {
248  // it is. change our line.
249  q = thisq;
250  n0 = q[1] - p[1];
251  n1 = -q[0] + p[0];
252  }
253  }
254  }
255 
256  // we must have elected *some* line, so long as there are at
257  // least 2 points in the polygon.
258  assert(q != NULL);
259 
260  // loop completed?
261  if (q == pleft)
262  break;
263 
264  int colinear = 0;
265 
266  // is this new point colinear with the last two?
267  if (zarray_size(hull) > 1) {
268  double *o;
269  zarray_get_volatile(hull, zarray_size(hull) - 2, &o);
270 
271  double e0 = o[0] - p[0];
272  double e1 = o[1] - p[1];
273 
274  if (n0*e0 + n1*e1 == 0)
275  colinear = 1;
276  }
277 
278  // if it is colinear, overwrite the last one.
279  if (colinear)
280  zarray_set(hull, zarray_size(hull)-1, q, NULL);
281  else
282  zarray_add(hull, q);
283 
284  p = q;
285  }
286 
287  return hull;
288 }
289 
290 // Find point p on the boundary of poly that is closest to q.
291 void g2d_polygon_closest_boundary_point(const zarray_t *poly, const double q[2], double *p)
292 {
293  int psz = zarray_size(poly);
294  double min_dist = HUGE_VALF;
295 
296  for (int i = 0; i < psz; i++) {
297  double *p0, *p1;
298 
299  zarray_get_volatile(poly, i, &p0);
300  zarray_get_volatile(poly, (i+1) % psz, &p1);
301 
302  g2d_line_segment_t seg;
303  g2d_line_segment_init_from_points(&seg, p0, p1);
304 
305  double thisp[2];
306  g2d_line_segment_closest_point(&seg, q, thisp);
307 
308  double dist = g2d_distance(q, thisp);
309  if (dist < min_dist) {
310  memcpy(p, thisp, sizeof(double[2]));
311  min_dist = dist;
312  }
313  }
314 }
315 
316 int g2d_polygon_contains_point(const zarray_t *poly, double q[2])
317 {
318  // use winding. If the point is inside the polygon, we'll wrap
319  // around it (accumulating 6.28 radians). If we're outside the
320  // polygon, we'll accumulate zero.
321  int psz = zarray_size(poly);
322  assert(psz > 0);
323 
324  int last_quadrant = 0;
325  int quad_acc = 0;
326 
327  for (int i = 0; i <= psz; i++) {
328  double *p;
329 
330  zarray_get_volatile(poly, i % psz, &p);
331 
332  // p[0] < q[0] p[1] < q[1] quadrant
333  // 0 0 0
334  // 0 1 3
335  // 1 0 1
336  // 1 1 2
337 
338  // p[1] < q[1] p[0] < q[0] quadrant
339  // 0 0 0
340  // 0 1 1
341  // 1 0 3
342  // 1 1 2
343 
344  int quadrant;
345  if (p[0] < q[0])
346  quadrant = (p[1] < q[1]) ? 2 : 1;
347  else
348  quadrant = (p[1] < q[1]) ? 3 : 0;
349 
350  if (i > 0) {
351  int dquadrant = quadrant - last_quadrant;
352 
353  // encourage a jump table by mapping to small positive integers.
354  switch (dquadrant) {
355  case -3:
356  case 1:
357  quad_acc ++;
358  break;
359  case -1:
360  case 3:
361  quad_acc --;
362  break;
363  case 0:
364  break;
365  case -2:
366  case 2:
367  {
368  // get the previous point.
369  double *p0;
370  zarray_get_volatile(poly, i-1, &p0);
371 
372  // Consider the points p0 and p (the points around the
373  //polygon that we are tracing) and the query point q.
374  //
375  // If we've moved diagonally across quadrants, we want
376  // to measure whether we have rotated +PI radians or
377  // -PI radians. We can test this by computing the dot
378  // product of vector (p0-q) with the vector
379  // perpendicular to vector (p-q)
380  double nx = p[1] - q[1];
381  double ny = -p[0] + q[0];
382 
383  double dot = nx*(p0[0]-q[0]) + ny*(p0[1]-q[1]);
384  if (dot < 0)
385  quad_acc -= 2;
386  else
387  quad_acc += 2;
388 
389  break;
390  }
391  }
392  }
393 
394  last_quadrant = quadrant;
395  }
396 
397  int v = (quad_acc >= 2) || (quad_acc <= -2);
398 
399  #if 0
400  if (v != g2d_polygon_contains_point_ref(poly, q)) {
401  printf("FAILURE %d %d\n", v, quad_acc);
402  exit(-1);
403  }
404  #endif
405 
406  return v;
407 }
408 
409 void g2d_line_init_from_points(g2d_line_t *line, const double p0[2], const double p1[2])
410 {
411  line->p[0] = p0[0];
412  line->p[1] = p0[1];
413  line->u[0] = p1[0]-p0[0];
414  line->u[1] = p1[1]-p0[1];
415  double mag = sqrtf(sq(line->u[0]) + sq(line->u[1]));
416 
417  line->u[0] /= mag;
418  line->u[1] /= mag;
419 }
420 
421 double g2d_line_get_coordinate(const g2d_line_t *line, const double q[2])
422 {
423  return (q[0]-line->p[0])*line->u[0] + (q[1]-line->p[1])*line->u[1];
424 }
425 
426 // Compute intersection of two line segments. If they intersect,
427 // result is stored in p and 1 is returned. Otherwise, zero is
428 // returned. p may be NULL.
429 int g2d_line_intersect_line(const g2d_line_t *linea, const g2d_line_t *lineb, double *p)
430 {
431  // this implementation is many times faster than the original,
432  // mostly due to avoiding a general-purpose LU decomposition in
433  // Matrix.inverse().
434  double m00, m01, m10, m11;
435  double i00, i01;
436  double b00, b10;
437 
438  m00 = linea->u[0];
439  m01= -lineb->u[0];
440  m10 = linea->u[1];
441  m11= -lineb->u[1];
442 
443  // determinant of m
444  double det = m00*m11-m01*m10;
445 
446  // parallel lines?
447  if (fabs(det) < 0.00000001)
448  return 0;
449 
450  // inverse of m
451  i00 = m11/det;
452  i01 = -m01/det;
453 
454  b00 = lineb->p[0] - linea->p[0];
455  b10 = lineb->p[1] - linea->p[1];
456 
457  double x00; //, x10;
458  x00 = i00*b00+i01*b10;
459 
460  if (p != NULL) {
461  p[0] = linea->u[0]*x00 + linea->p[0];
462  p[1] = linea->u[1]*x00 + linea->p[1];
463  }
464 
465  return 1;
466 }
467 
468 
469 void g2d_line_segment_init_from_points(g2d_line_segment_t *seg, const double p0[2], const double p1[2])
470 {
471  g2d_line_init_from_points(&seg->line, p0, p1);
472  seg->p1[0] = p1[0];
473  seg->p1[1] = p1[1];
474 }
475 
476 // Find the point p on segment seg that is closest to point q.
477 void g2d_line_segment_closest_point(const g2d_line_segment_t *seg, const double *q, double *p)
478 {
479  double a = g2d_line_get_coordinate(&seg->line, seg->line.p);
480  double b = g2d_line_get_coordinate(&seg->line, seg->p1);
481  double c = g2d_line_get_coordinate(&seg->line, q);
482 
483  if (a < b)
484  c = dclamp(c, a, b);
485  else
486  c = dclamp(c, b, a);
487 
488  p[0] = seg->line.p[0] + c * seg->line.u[0];
489  p[1] = seg->line.p[1] + c * seg->line.u[1];
490 }
491 
492 // Compute intersection of two line segments. If they intersect,
493 // result is stored in p and 1 is returned. Otherwise, zero is
494 // returned. p may be NULL.
496 {
497  double tmp[2];
498 
499  if (!g2d_line_intersect_line(&sega->line, &segb->line, tmp))
500  return 0;
501 
502  double a = g2d_line_get_coordinate(&sega->line, sega->line.p);
503  double b = g2d_line_get_coordinate(&sega->line, sega->p1);
504  double c = g2d_line_get_coordinate(&sega->line, tmp);
505 
506  // does intersection lie on the first line?
507  if ((c<a && c<b) || (c>a && c>b))
508  return 0;
509 
510  a = g2d_line_get_coordinate(&segb->line, segb->line.p);
511  b = g2d_line_get_coordinate(&segb->line, segb->p1);
512  c = g2d_line_get_coordinate(&segb->line, tmp);
513 
514  // does intersection lie on second line?
515  if ((c<a && c<b) || (c>a && c>b))
516  return 0;
517 
518  if (p != NULL) {
519  p[0] = tmp[0];
520  p[1] = tmp[1];
521  }
522 
523  return 1;
524 }
525 
526 // Compute intersection of a line segment and a line. If they
527 // intersect, result is stored in p and 1 is returned. Otherwise, zero
528 // is returned. p may be NULL.
529 int g2d_line_segment_intersect_line(const g2d_line_segment_t *seg, const g2d_line_t *line, double *p)
530 {
531  double tmp[2];
532 
533  if (!g2d_line_intersect_line(&seg->line, line, tmp))
534  return 0;
535 
536  double a = g2d_line_get_coordinate(&seg->line, seg->line.p);
537  double b = g2d_line_get_coordinate(&seg->line, seg->p1);
538  double c = g2d_line_get_coordinate(&seg->line, tmp);
539 
540  // does intersection lie on the first line?
541  if ((c<a && c<b) || (c>a && c>b))
542  return 0;
543 
544  if (p != NULL) {
545  p[0] = tmp[0];
546  p[1] = tmp[1];
547  }
548 
549  return 1;
550 }
551 
552 // do the edges of polya and polyb collide? (Does NOT test for containment).
553 int g2d_polygon_intersects_polygon(const zarray_t *polya, const zarray_t *polyb)
554 {
555  // do any of the line segments collide? If so, the answer is no.
556 
557  // dumb N^2 method.
558  for (int ia = 0; ia < zarray_size(polya); ia++) {
559  double pa0[2], pa1[2];
560  zarray_get(polya, ia, pa0);
561  zarray_get(polya, (ia+1)%zarray_size(polya), pa1);
562 
563  g2d_line_segment_t sega;
564  g2d_line_segment_init_from_points(&sega, pa0, pa1);
565 
566  for (int ib = 0; ib < zarray_size(polyb); ib++) {
567  double pb0[2], pb1[2];
568  zarray_get(polyb, ib, pb0);
569  zarray_get(polyb, (ib+1)%zarray_size(polyb), pb1);
570 
571  g2d_line_segment_t segb;
572  g2d_line_segment_init_from_points(&segb, pb0, pb1);
573 
574  if (g2d_line_segment_intersect_segment(&sega, &segb, NULL))
575  return 1;
576  }
577  }
578 
579  return 0;
580 }
581 
582 // does polya completely contain polyb?
583 int g2d_polygon_contains_polygon(const zarray_t *polya, const zarray_t *polyb)
584 {
585  // do any of the line segments collide? If so, the answer is no.
586  if (g2d_polygon_intersects_polygon(polya, polyb))
587  return 0;
588 
589  // if none of the edges cross, then the polygon is either fully
590  // contained or fully outside.
591  double p[2];
592  zarray_get(polyb, 0, p);
593 
594  return g2d_polygon_contains_point(polya, p);
595 }
596 
597 // compute a point that is inside the polygon. (It may not be *far* inside though)
598 void g2d_polygon_get_interior_point(const zarray_t *poly, double *p)
599 {
600  // take the first three points, which form a triangle. Find the middle point
601  double a[2], b[2], c[2];
602 
603  zarray_get(poly, 0, a);
604  zarray_get(poly, 1, b);
605  zarray_get(poly, 2, c);
606 
607  p[0] = (a[0]+b[0]+c[0])/3;
608  p[1] = (a[1]+b[1]+c[1])/3;
609 }
610 
611 int g2d_polygon_overlaps_polygon(const zarray_t *polya, const zarray_t *polyb)
612 {
613  // do any of the line segments collide? If so, the answer is yes.
614  if (g2d_polygon_intersects_polygon(polya, polyb))
615  return 1;
616 
617  // if none of the edges cross, then the polygon is either fully
618  // contained or fully outside.
619  double p[2];
621 
622  if (g2d_polygon_contains_point(polya, p))
623  return 1;
624 
626 
627  if (g2d_polygon_contains_point(polyb, p))
628  return 1;
629 
630  return 0;
631 }
632 
633 static int double_sort_up(const void *_a, const void *_b)
634 {
635  double a = *((double*) _a);
636  double b = *((double*) _b);
637 
638  if (a < b)
639  return -1;
640 
641  if (a == b)
642  return 0;
643 
644  return 1;
645 }
646 
647 // Compute the crossings of the polygon along line y, storing them in
648 // the array x. X must be allocated to be at least as long as
649 // zarray_size(poly). X will be sorted, ready for
650 // rasterization. Returns the number of intersections (and elements
651 // written to x).
652 /*
653  To rasterize, do something like this:
654 
655  double res = 0.099;
656  for (double y = y0; y < y1; y += res) {
657  double xs[zarray_size(poly)];
658 
659  int xsz = g2d_polygon_rasterize(poly, y, xs);
660  int xpos = 0;
661  int inout = 0; // start off "out"
662 
663  for (double x = x0; x < x1; x += res) {
664  while (x > xs[xpos] && xpos < xsz) {
665  xpos++;
666  inout ^= 1;
667  }
668 
669  if (inout)
670  printf("y");
671  else
672  printf(" ");
673  }
674  printf("\n");
675 */
676 
677 // returns the number of x intercepts
678 int g2d_polygon_rasterize(const zarray_t *poly, double y, double *x)
679 {
680  int sz = zarray_size(poly);
681 
682  g2d_line_t line;
683  if (1) {
684  double p0[2] = { 0, y };
685  double p1[2] = { 1, y };
686 
687  g2d_line_init_from_points(&line, p0, p1);
688  }
689 
690  int xpos = 0;
691 
692  for (int i = 0; i < sz; i++) {
693  g2d_line_segment_t seg;
694  double *p0, *p1;
695  zarray_get_volatile(poly, i, &p0);
696  zarray_get_volatile(poly, (i+1)%sz, &p1);
697 
698  g2d_line_segment_init_from_points(&seg, p0, p1);
699 
700  double q[2];
701  if (g2d_line_segment_intersect_line(&seg, &line, q))
702  x[xpos++] = q[0];
703  }
704 
705  qsort(x, xpos, sizeof(double), double_sort_up);
706 
707  return xpos;
708 }
709 
710 /*
711  /---(1,5)
712  (-2,4)-/ |
713  \ |
714  \ (1,2)--(2,2)\
715  \ \
716  \ \
717  (0,0)------------------(4,0)
718 */
719 #if 0
720 
721 #ifdef _WIN32
722 static inline long int random(void)
723 {
724  return rand();
725 }
726 #endif
727 
728 #include "timeprofile.h"
729 
730 int main(int argc, char *argv[])
731 {
733 
734  zarray_t *polya = g2d_polygon_create_data((double[][2]) {
735  { 0, 0},
736  { 4, 0},
737  { 2, 2},
738  { 1, 2},
739  { 1, 5},
740  { -2,4} }, 6);
741 
742  zarray_t *polyb = g2d_polygon_create_data((double[][2]) {
743  { .1, .1},
744  { .5, .1},
745  { .1, .5 } }, 3);
746 
747  zarray_t *polyc = g2d_polygon_create_data((double[][2]) {
748  { 3, 0},
749  { 5, 0},
750  { 5, 1} }, 3);
751 
752  zarray_t *polyd = g2d_polygon_create_data((double[][2]) {
753  { 5, 5},
754  { 6, 6},
755  { 5, 6} }, 3);
756 
757 /*
758  5 L---K
759  4 |I--J
760  3 |H-G
761  2 |E-F
762  1 |D--C
763  0 A---B
764  01234
765 */
766  zarray_t *polyE = g2d_polygon_create_data((double[][2]) {
767  {0,0}, {4,0}, {4, 1}, {1,1},
768  {1,2}, {3,2}, {3,3}, {1,3},
769  {1,4}, {4,4}, {4,5}, {0,5}}, 12);
770 
771  srand(0);
772 
773  timeprofile_stamp(tp, "begin");
774 
775  if (1) {
776  int niters = 100000;
777 
778  for (int i = 0; i < niters; i++) {
779  double q[2];
780  q[0] = 10.0f * random() / RAND_MAX - 2;
781  q[1] = 10.0f * random() / RAND_MAX - 2;
782 
783  g2d_polygon_contains_point(polyE, q);
784  }
785 
786  timeprofile_stamp(tp, "fast");
787 
788  for (int i = 0; i < niters; i++) {
789  double q[2];
790  q[0] = 10.0f * random() / RAND_MAX - 2;
791  q[1] = 10.0f * random() / RAND_MAX - 2;
792 
794  }
795 
796  timeprofile_stamp(tp, "slow");
797 
798  for (int i = 0; i < niters; i++) {
799  double q[2];
800  q[0] = 10.0f * random() / RAND_MAX - 2;
801  q[1] = 10.0f * random() / RAND_MAX - 2;
802 
803  int v0 = g2d_polygon_contains_point(polyE, q);
804  int v1 = g2d_polygon_contains_point_ref(polyE, q);
805  assert(v0 == v1);
806  }
807 
808  timeprofile_stamp(tp, "both");
810  }
811 
812  if (1) {
813  zarray_t *poly = polyE;
814 
815  double res = 0.399;
816  for (double y = 5.2; y >= -.5; y -= res) {
817  double xs[zarray_size(poly)];
818 
819  int xsz = g2d_polygon_rasterize(poly, y, xs);
820  int xpos = 0;
821  int inout = 0; // start off "out"
822  for (double x = -3; x < 6; x += res) {
823  while (x > xs[xpos] && xpos < xsz) {
824  xpos++;
825  inout ^= 1;
826  }
827 
828  if (inout)
829  printf("y");
830  else
831  printf(" ");
832  }
833  printf("\n");
834 
835  for (double x = -3; x < 6; x += res) {
836  double q[2] = {x, y};
837  if (g2d_polygon_contains_point(poly, q))
838  printf("X");
839  else
840  printf(" ");
841  }
842  printf("\n");
843  }
844  }
845 
846 
847 
848 /*
849 // CW order
850 double p[][2] = { { 0, 0},
851 { -2, 4},
852 {1, 5},
853 {1, 2},
854 {2, 2},
855 {4, 0} };
856 */
857 
858  double q[2] = { 10, 10 };
859  printf("0==%d\n", g2d_polygon_contains_point(polya, q));
860 
861  q[0] = 1; q[1] = 1;
862  printf("1==%d\n", g2d_polygon_contains_point(polya, q));
863 
864  q[0] = 3; q[1] = .5;
865  printf("1==%d\n", g2d_polygon_contains_point(polya, q));
866 
867  q[0] = 1.2; q[1] = 2.1;
868  printf("0==%d\n", g2d_polygon_contains_point(polya, q));
869 
870  printf("0==%d\n", g2d_polygon_contains_polygon(polya, polyb));
871 
872  printf("0==%d\n", g2d_polygon_contains_polygon(polya, polyc));
873 
874  printf("0==%d\n", g2d_polygon_contains_polygon(polya, polyd));
875 
877  // Test convex hull
878  if (1) {
879  zarray_t *hull = g2d_convex_hull(polyE);
880 
881  for (int k = 0; k < zarray_size(hull); k++) {
882  double *h;
883  zarray_get_volatile(hull, k, &h);
884 
885  printf("%15f, %15f\n", h[0], h[1]);
886  }
887  }
888 
889  for (int i = 0; i < 100000; i++) {
890  zarray_t *points = zarray_create(sizeof(double[2]));
891 
892  for (int j = 0; j < 100; j++) {
893  double q[2];
894  q[0] = 10.0f * random() / RAND_MAX - 2;
895  q[1] = 10.0f * random() / RAND_MAX - 2;
896 
897  zarray_add(points, q);
898  }
899 
900  zarray_t *hull = g2d_convex_hull(points);
901  for (int j = 0; j < zarray_size(points); j++) {
902  double *q;
903  zarray_get_volatile(points, j, &q);
904 
905  int on_edge;
906 
907  double p[2];
909  if (g2d_distance(q, p) < .00001)
910  on_edge = 1;
911 
912  assert(on_edge || g2d_polygon_contains_point(hull, q));
913  }
914 
915  zarray_destroy(hull);
916  zarray_destroy(points);
917  }
918 }
919 #endif
zarray_create
static zarray_t * zarray_create(size_t el_sz)
Definition: zarray.h:57
g2d_polygon_create_empty
zarray_t * g2d_polygon_create_empty()
Definition: g2d.c:41
g2d_line_init_from_points
void g2d_line_init_from_points(g2d_line_t *line, const double p0[2], const double p1[2])
Definition: g2d.c:409
g2d_line_segment_intersect_line
int g2d_line_segment_intersect_line(const g2d_line_segment_t *seg, const g2d_line_t *line, double *p)
Definition: g2d.c:529
zarray_destroy
static void zarray_destroy(zarray_t *za)
Definition: zarray.h:70
g2d.h
g2d_distance
double g2d_distance(const double a[2], const double b[2])
Definition: g2d.c:36
dclamp
static double dclamp(double a, double min, double max)
Definition: math_util.h:171
g2d_line_t::p
double p[2]
Definition: g2d.h:58
zarray
Definition: zarray.h:43
g2d_convex_hull
zarray_t * g2d_convex_hull(const zarray_t *points)
Definition: g2d.c:185
zarray_size
static int zarray_size(const zarray_t *za)
Definition: zarray.h:130
g2d_line_t::u
double u[2]
Definition: g2d.h:59
g2d_line_get_coordinate
double g2d_line_get_coordinate(const g2d_line_t *line, const double q[2])
Definition: g2d.c:421
g2d_polygon_add
void g2d_polygon_add(zarray_t *poly, double v[2])
Definition: g2d.c:46
g2d_polygon_get_interior_point
void g2d_polygon_get_interior_point(const zarray_t *poly, double *p)
Definition: g2d.c:598
g2d_line_segment_init_from_points
void g2d_line_segment_init_from_points(g2d_line_segment_t *seg, const double p0[2], const double p1[2])
Definition: g2d.c:469
quad::p
float p[4][2]
Definition: apriltag.h:47
g2d_polygon_create_data
zarray_t * g2d_polygon_create_data(double v[][2], int sz)
Definition: g2d.c:51
g2d_polygon_intersects_polygon
int g2d_polygon_intersects_polygon(const zarray_t *polya, const zarray_t *polyb)
Definition: g2d.c:553
timeprofile
Definition: timeprofile.h:48
g2d_line_segment_t
Definition: g2d.h:77
g2d_line_segment_closest_point
void g2d_line_segment_closest_point(const g2d_line_segment_t *seg, const double *q, double *p)
Definition: g2d.c:477
g2d_polygon_contains_point
int g2d_polygon_contains_point(const zarray_t *poly, double q[2])
Definition: g2d.c:316
g2d_polygon_create_zeros
zarray_t * g2d_polygon_create_zeros(int sz)
Definition: g2d.c:61
g2d_line_segment_intersect_segment
int g2d_line_segment_intersect_segment(const g2d_line_segment_t *sega, const g2d_line_segment_t *segb, double *p)
Definition: g2d.c:495
mod2pi
static double mod2pi(double vin)
Definition: math_util.h:106
sq
static double sq(double v)
Definition: math_util.h:66
main
int main(int argc, char *argv[])
Definition: apriltag_demo.c:61
timeprofile.h
g2d_line_intersect_line
int g2d_line_intersect_line(const g2d_line_t *linea, const g2d_line_t *lineb, double *p)
Definition: g2d.c:429
g2d_polygon_contains_polygon
int g2d_polygon_contains_polygon(const zarray_t *polya, const zarray_t *polyb)
Definition: g2d.c:583
g2d_polygon_contains_point_ref
int g2d_polygon_contains_point_ref(const zarray_t *poly, double q[2])
Definition: g2d.c:114
g2d_polygon_make_ccw
void g2d_polygon_make_ccw(zarray_t *poly)
Definition: g2d.c:73
zarray_add
static void zarray_add(zarray_t *za, const void *p)
Definition: zarray.h:179
timeprofile_stamp
static void timeprofile_stamp(timeprofile_t *tp, const char *name)
Definition: timeprofile.h:76
timeprofile_create
static timeprofile_t * timeprofile_create()
Definition: timeprofile.h:54
math_util.h
g2d_line_t
Definition: g2d.h:54
zarray_get_volatile
static void zarray_get_volatile(const zarray_t *za, int idx, void *p)
Definition: zarray.h:212
zarray_get
static void zarray_get(const zarray_t *za, int idx, void *p)
Definition: zarray.h:195
g2d_polygon_overlaps_polygon
int g2d_polygon_overlaps_polygon(const zarray_t *polya, const zarray_t *polyb)
Definition: g2d.c:611
g2d_polygon_rasterize
int g2d_polygon_rasterize(const zarray_t *poly, double y, double *x)
Definition: g2d.c:678
timeprofile_display
static void timeprofile_display(timeprofile_t *tp)
Definition: timeprofile.h:87
zarray_set
static void zarray_set(zarray_t *za, int idx, const void *p, void *outp)
Definition: zarray.h:319
double_sort_up
static int double_sort_up(const void *_a, const void *_b)
Definition: g2d.c:633
g2d_polygon_closest_boundary_point
void g2d_polygon_closest_boundary_point(const zarray_t *poly, const double q[2], double *p)
Definition: g2d.c:291
g2d_line_segment_t::line
g2d_line_t line
Definition: g2d.h:79
g2d_line_segment_t::p1
double p1[2]
Definition: g2d.h:80


apriltag
Author(s): Edwin Olson , Max Krogius
autogenerated on Sun Apr 20 2025 02:08:19