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


apriltags2
Author(s): Danylo Malyuta
autogenerated on Fri Oct 19 2018 04:02:32