apriltag_quad_thresh.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 // limitation: image size must be <32768 in width and height. This is
29 // because we use a fixed-point 16 bit integer representation with one
30 // fractional bit.
31 #include <math.h>
32 #include <assert.h>
33 #include <string.h>
34 #include <stdio.h>
35 #include <stdint.h>
36 
37 #include "apriltag.h"
38 #include "common/image_u8x3.h"
39 #include "common/zarray.h"
40 #include "common/unionfind.h"
41 #include "common/timeprofile.h"
42 #include "common/zmaxheap.h"
44 #include "common/math_util.h"
45 
46 #ifdef _WIN32
47 static inline long int random(void)
48 {
49  return rand();
50 }
51 #endif
52 
53 static inline uint32_t u64hash_2(uint64_t x) {
54  return (2654435761 * x) >> 32;
55 }
56 
58 {
59  uint64_t id;
61 
63 };
64 
65 #ifndef M_PI
66 # define M_PI 3.141592653589793238462643383279502884196
67 #endif
68 
69 struct pt
70 {
71  // Note: these represent 2*actual value.
72  uint16_t x, y;
73  int16_t gx, gy;
74 
75  float slope;
76 };
77 
79 {
80  int y0, y1;
81  int w, h, s;
84 };
85 
86 struct quad_task
87 {
89  int cidx0, cidx1; // [cidx0, cidx1)
92  int w, h;
93 
95  int tag_width;
98 };
99 
100 
102 {
103  int y0;
104  int y1;
105  int w;
106  int s;
111 };
112 
114 {
115  int i; // which vertex to remove?
116  int left, right; // left vertex, right vertex
117 
118  double err;
119 };
120 
121 struct segment
122 {
124 
125  // always greater than zero, but right can be > size, which denotes
126  // a wrap around back to the beginning of the points. and left < right.
127  int left, right;
128 };
129 
131 {
132  double Mx, My;
133  double Mxx, Myy, Mxy;
134  double W; // total weight
135 };
136 
138 {
139  uint32_t hash;
140  uint64_t id;
142 };
143 
144 
145 // lfps contains *cumulative* moments for N points, with
146 // index j reflecting points [0,j] (inclusive).
147 //
148 // fit a line to the points [i0, i1] (inclusive). i0, i1 are both [0,
149 // sz) if i1 < i0, we treat this as a wrap around.
150 void fit_line(struct line_fit_pt *lfps, int sz, int i0, int i1, double *lineparm, double *err, double *mse)
151 {
152  assert(i0 != i1);
153  assert(i0 >= 0 && i1 >= 0 && i0 < sz && i1 < sz);
154 
155  double Mx, My, Mxx, Myy, Mxy, W;
156  int N; // how many points are included in the set?
157 
158  if (i0 < i1) {
159  N = i1 - i0 + 1;
160 
161  Mx = lfps[i1].Mx;
162  My = lfps[i1].My;
163  Mxx = lfps[i1].Mxx;
164  Mxy = lfps[i1].Mxy;
165  Myy = lfps[i1].Myy;
166  W = lfps[i1].W;
167 
168  if (i0 > 0) {
169  Mx -= lfps[i0-1].Mx;
170  My -= lfps[i0-1].My;
171  Mxx -= lfps[i0-1].Mxx;
172  Mxy -= lfps[i0-1].Mxy;
173  Myy -= lfps[i0-1].Myy;
174  W -= lfps[i0-1].W;
175  }
176 
177  } else {
178  // i0 > i1, e.g. [15, 2]. Wrap around.
179  assert(i0 > 0);
180 
181  Mx = lfps[sz-1].Mx - lfps[i0-1].Mx;
182  My = lfps[sz-1].My - lfps[i0-1].My;
183  Mxx = lfps[sz-1].Mxx - lfps[i0-1].Mxx;
184  Mxy = lfps[sz-1].Mxy - lfps[i0-1].Mxy;
185  Myy = lfps[sz-1].Myy - lfps[i0-1].Myy;
186  W = lfps[sz-1].W - lfps[i0-1].W;
187 
188  Mx += lfps[i1].Mx;
189  My += lfps[i1].My;
190  Mxx += lfps[i1].Mxx;
191  Mxy += lfps[i1].Mxy;
192  Myy += lfps[i1].Myy;
193  W += lfps[i1].W;
194 
195  N = sz - i0 + i1 + 1;
196  }
197 
198  assert(N >= 2);
199 
200  double Ex = Mx / W;
201  double Ey = My / W;
202  double Cxx = Mxx / W - Ex*Ex;
203  double Cxy = Mxy / W - Ex*Ey;
204  double Cyy = Myy / W - Ey*Ey;
205 
206  //if (1) {
207  // // on iOS about 5% of total CPU spent in these trig functions.
208  // // 85 ms per frame on 5S, example.pnm
209  // //
210  // // XXX this was using the double-precision atan2. Was there a case where
211  // // we needed that precision? Seems doubtful.
212  // double normal_theta = .5 * atan2f(-2*Cxy, (Cyy - Cxx));
213  // nx_old = cosf(normal_theta);
214  // ny_old = sinf(normal_theta);
215  //}
216 
217  // Instead of using the above cos/sin method, pose it as an eigenvalue problem.
218  double eig_small = 0.5*(Cxx + Cyy - sqrtf((Cxx - Cyy)*(Cxx - Cyy) + 4*Cxy*Cxy));
219 
220  if (lineparm) {
221  lineparm[0] = Ex;
222  lineparm[1] = Ey;
223 
224  double eig = 0.5*(Cxx + Cyy + sqrtf((Cxx - Cyy)*(Cxx - Cyy) + 4*Cxy*Cxy));
225  double nx1 = Cxx - eig;
226  double ny1 = Cxy;
227  double M1 = nx1*nx1 + ny1*ny1;
228  double nx2 = Cxy;
229  double ny2 = Cyy - eig;
230  double M2 = nx2*nx2 + ny2*ny2;
231 
232  double nx, ny, M;
233  if (M1 > M2) {
234  nx = nx1;
235  ny = ny1;
236  M = M1;
237  } else {
238  nx = nx2;
239  ny = ny2;
240  M = M2;
241  }
242 
243  double length = sqrtf(M);
244  lineparm[2] = nx/length;
245  lineparm[3] = ny/length;
246  }
247 
248  // sum of squared errors =
249  //
250  // SUM_i ((p_x - ux)*nx + (p_y - uy)*ny)^2
251  // SUM_i nx*nx*(p_x - ux)^2 + 2nx*ny(p_x -ux)(p_y-uy) + ny*ny*(p_y-uy)*(p_y-uy)
252  // nx*nx*SUM_i((p_x -ux)^2) + 2nx*ny*SUM_i((p_x-ux)(p_y-uy)) + ny*ny*SUM_i((p_y-uy)^2)
253  //
254  // nx*nx*N*Cxx + 2nx*ny*N*Cxy + ny*ny*N*Cyy
255 
256  // sum of squared errors
257  if (err)
258  *err = N*eig_small;
259 
260  // mean squared error
261  if (mse)
262  *mse = eig_small;
263 }
264 
265 float pt_compare_angle(struct pt *a, struct pt *b) {
266  return a->slope - b->slope;
267 }
268 
269 int err_compare_descending(const void *_a, const void *_b)
270 {
271  const double *a = _a;
272  const double *b = _b;
273 
274  return ((*a) < (*b)) ? 1 : -1;
275 }
276 
277 /*
278 
279  1. Identify A) white points near a black point and B) black points near a white point.
280 
281  2. Find the connected components within each of the classes above,
282  yielding clusters of "white-near-black" and
283  "black-near-white". (These two classes are kept separate). Each
284  segment has a unique id.
285 
286  3. For every pair of "white-near-black" and "black-near-white"
287  clusters, find the set of points that are in one and adjacent to the
288  other. In other words, a "boundary" layer between the two
289  clusters. (This is actually performed by iterating over the pixels,
290  rather than pairs of clusters.) Critically, this helps keep nearby
291  edges from becoming connected.
292 */
293 int quad_segment_maxima(apriltag_detector_t *td, zarray_t *cluster, struct line_fit_pt *lfps, int indices[4])
294 {
295  int sz = zarray_size(cluster);
296 
297  // ksz: when fitting points, how many points on either side do we consider?
298  // (actual "kernel" width is 2ksz).
299  //
300  // This value should be about: 0.5 * (points along shortest edge).
301  //
302  // If all edges were equally-sized, that would give a value of
303  // sz/8. We make it somewhat smaller to account for tags at high
304  // aspects.
305 
306  // XXX Tunable. Maybe make a multiple of JPEG block size to increase robustness
307  // to JPEG compression artifacts?
308  int ksz = imin(20, sz / 12);
309 
310  // can't fit a quad if there are too few points.
311  if (ksz < 2)
312  return 0;
313 
314  double *errs = malloc(sizeof(double)*sz);
315 
316  for (int i = 0; i < sz; i++) {
317  fit_line(lfps, sz, (i + sz - ksz) % sz, (i + ksz) % sz, NULL, &errs[i], NULL);
318  }
319 
320  // apply a low-pass filter to errs
321  if (1) {
322  double *y = malloc(sizeof(double)*sz);
323 
324  // how much filter to apply?
325 
326  // XXX Tunable
327  double sigma = 1; // was 3
328 
329  // cutoff = exp(-j*j/(2*sigma*sigma));
330  // log(cutoff) = -j*j / (2*sigma*sigma)
331  // log(cutoff)*2*sigma*sigma = -j*j;
332 
333  // how big a filter should we use? We make our kernel big
334  // enough such that we represent any values larger than
335  // 'cutoff'.
336 
337  // XXX Tunable (though not super useful to change)
338  double cutoff = 0.05;
339  int fsz = sqrt(-log(cutoff)*2*sigma*sigma) + 1;
340  fsz = 2*fsz + 1;
341 
342  // For default values of cutoff = 0.05, sigma = 3,
343  // we have fsz = 17.
344  float *f = malloc(sizeof(float)*fsz);
345 
346  for (int i = 0; i < fsz; i++) {
347  int j = i - fsz / 2;
348  f[i] = exp(-j*j/(2*sigma*sigma));
349  }
350 
351  for (int iy = 0; iy < sz; iy++) {
352  double acc = 0;
353 
354  for (int i = 0; i < fsz; i++) {
355  acc += errs[(iy + i - fsz / 2 + sz) % sz] * f[i];
356  }
357  y[iy] = acc;
358  }
359 
360  memcpy(errs, y, sizeof(double)*sz);
361  free(y);
362  free(f);
363  }
364 
365  int *maxima = malloc(sizeof(int)*sz);
366  double *maxima_errs = malloc(sizeof(double)*sz);
367  int nmaxima = 0;
368 
369  for (int i = 0; i < sz; i++) {
370  if (errs[i] > errs[(i+1)%sz] && errs[i] > errs[(i+sz-1)%sz]) {
371  maxima[nmaxima] = i;
372  maxima_errs[nmaxima] = errs[i];
373  nmaxima++;
374  }
375  }
376  free(errs);
377 
378  // if we didn't get at least 4 maxima, we can't fit a quad.
379  if (nmaxima < 4){
380  free(maxima);
381  free(maxima_errs);
382  return 0;
383  }
384 
385  // select only the best maxima if we have too many
386  int max_nmaxima = td->qtp.max_nmaxima;
387 
388  if (nmaxima > max_nmaxima) {
389  double *maxima_errs_copy = malloc(sizeof(double)*nmaxima);
390  memcpy(maxima_errs_copy, maxima_errs, sizeof(double)*nmaxima);
391 
392  // throw out all but the best handful of maxima. Sorts descending.
393  qsort(maxima_errs_copy, nmaxima, sizeof(double), err_compare_descending);
394 
395  double maxima_thresh = maxima_errs_copy[max_nmaxima];
396  int out = 0;
397  for (int in = 0; in < nmaxima; in++) {
398  if (maxima_errs[in] <= maxima_thresh)
399  continue;
400  maxima[out++] = maxima[in];
401  }
402  nmaxima = out;
403  free(maxima_errs_copy);
404  }
405  free(maxima_errs);
406 
407  int best_indices[4];
408  double best_error = HUGE_VALF;
409 
410  double err01, err12, err23, err30;
411  double mse01, mse12, mse23, mse30;
412  double params01[4], params12[4], params23[4], params30[4];
413 
414  // disallow quads where the angle is less than a critical value.
415  double max_dot = td->qtp.cos_critical_rad; //25*M_PI/180);
416 
417  for (int m0 = 0; m0 < nmaxima - 3; m0++) {
418  int i0 = maxima[m0];
419 
420  for (int m1 = m0+1; m1 < nmaxima - 2; m1++) {
421  int i1 = maxima[m1];
422 
423  fit_line(lfps, sz, i0, i1, params01, &err01, &mse01);
424 
425  if (mse01 > td->qtp.max_line_fit_mse)
426  continue;
427 
428  for (int m2 = m1+1; m2 < nmaxima - 1; m2++) {
429  int i2 = maxima[m2];
430 
431  fit_line(lfps, sz, i1, i2, params12, &err12, &mse12);
432  if (mse12 > td->qtp.max_line_fit_mse)
433  continue;
434 
435  double dot = params01[2]*params12[2] + params01[3]*params12[3];
436  if (fabs(dot) > max_dot)
437  continue;
438 
439  for (int m3 = m2+1; m3 < nmaxima; m3++) {
440  int i3 = maxima[m3];
441 
442  fit_line(lfps, sz, i2, i3, params23, &err23, &mse23);
443  if (mse23 > td->qtp.max_line_fit_mse)
444  continue;
445 
446  fit_line(lfps, sz, i3, i0, params30, &err30, &mse30);
447  if (mse30 > td->qtp.max_line_fit_mse)
448  continue;
449 
450  double err = err01 + err12 + err23 + err30;
451  if (err < best_error) {
452  best_error = err;
453  best_indices[0] = i0;
454  best_indices[1] = i1;
455  best_indices[2] = i2;
456  best_indices[3] = i3;
457  }
458  }
459  }
460  }
461  }
462 
463  free(maxima);
464 
465  if (best_error == HUGE_VALF)
466  return 0;
467 
468  for (int i = 0; i < 4; i++)
469  indices[i] = best_indices[i];
470 
471  if (best_error / sz < td->qtp.max_line_fit_mse)
472  return 1;
473  return 0;
474 }
475 
476 // returns 0 if the cluster looks bad.
477 int quad_segment_agg(apriltag_detector_t *td, zarray_t *cluster, struct line_fit_pt *lfps, int indices[4])
478 {
479  int sz = zarray_size(cluster);
480 
481  zmaxheap_t *heap = zmaxheap_create(sizeof(struct remove_vertex*));
482 
483  // We will initially allocate sz rvs. We then have two types of
484  // iterations: some iterations that are no-ops in terms of
485  // allocations, and those that remove a vertex and allocate two
486  // more children. This will happen at most (sz-4) times. Thus we
487  // need: sz + 2*(sz-4) entries.
488 
489  int rvalloc_pos = 0;
490  int rvalloc_size = 3*sz;
491  struct remove_vertex *rvalloc = calloc(rvalloc_size, sizeof(struct remove_vertex));
492 
493  struct segment *segs = calloc(sz, sizeof(struct segment));
494 
495  // populate with initial entries
496  for (int i = 0; i < sz; i++) {
497  struct remove_vertex *rv = &rvalloc[rvalloc_pos++];
498  rv->i = i;
499  if (i == 0) {
500  rv->left = sz-1;
501  rv->right = 1;
502  } else {
503  rv->left = i-1;
504  rv->right = (i+1) % sz;
505  }
506 
507  fit_line(lfps, sz, rv->left, rv->right, NULL, NULL, &rv->err);
508 
509  zmaxheap_add(heap, &rv, -rv->err);
510 
511  segs[i].left = rv->left;
512  segs[i].right = rv->right;
513  segs[i].is_vertex = 1;
514  }
515 
516  int nvertices = sz;
517 
518  while (nvertices > 4) {
519  assert(rvalloc_pos < rvalloc_size);
520 
521  struct remove_vertex *rv;
522  float err;
523 
524  int res = zmaxheap_remove_max(heap, &rv, &err);
525  if (!res)
526  return 0;
527  assert(res);
528 
529  // is this remove_vertex valid? (Or has one of the left/right
530  // vertices changes since we last looked?)
531  if (!segs[rv->i].is_vertex ||
532  !segs[rv->left].is_vertex ||
533  !segs[rv->right].is_vertex) {
534  continue;
535  }
536 
537  // we now merge.
538  assert(segs[rv->i].is_vertex);
539 
540  segs[rv->i].is_vertex = 0;
541  segs[rv->left].right = rv->right;
542  segs[rv->right].left = rv->left;
543 
544  // create the join to the left
545  if (1) {
546  struct remove_vertex *child = &rvalloc[rvalloc_pos++];
547  child->i = rv->left;
548  child->left = segs[rv->left].left;
549  child->right = rv->right;
550 
551  fit_line(lfps, sz, child->left, child->right, NULL, NULL, &child->err);
552 
553  zmaxheap_add(heap, &child, -child->err);
554  }
555 
556  // create the join to the right
557  if (1) {
558  struct remove_vertex *child = &rvalloc[rvalloc_pos++];
559  child->i = rv->right;
560  child->left = rv->left;
561  child->right = segs[rv->right].right;
562 
563  fit_line(lfps, sz, child->left, child->right, NULL, NULL, &child->err);
564 
565  zmaxheap_add(heap, &child, -child->err);
566  }
567 
568  // we now have one less vertex
569  nvertices--;
570  }
571 
572  free(rvalloc);
573  zmaxheap_destroy(heap);
574 
575  int idx = 0;
576  for (int i = 0; i < sz; i++) {
577  if (segs[i].is_vertex) {
578  indices[idx++] = i;
579  }
580  }
581 
582  free(segs);
583 
584  return 1;
585 }
586 
592  struct line_fit_pt *lfps = calloc(sz, sizeof(struct line_fit_pt));
593 
594  for (int i = 0; i < sz; i++) {
595  struct pt *p;
596  zarray_get_volatile(cluster, i, &p);
597 
598  if (i > 0) {
599  memcpy(&lfps[i], &lfps[i-1], sizeof(struct line_fit_pt));
600  }
601 
602  {
603  // we now undo our fixed-point arithmetic.
604  double delta = 0.5; // adjust for pixel center bias
605  double x = p->x * .5 + delta;
606  double y = p->y * .5 + delta;
607  int ix = x, iy = y;
608  double W = 1;
609 
610  if (ix > 0 && ix+1 < im->width && iy > 0 && iy+1 < im->height) {
611  int grad_x = im->buf[iy * im->stride + ix + 1] -
612  im->buf[iy * im->stride + ix - 1];
613 
614  int grad_y = im->buf[(iy+1) * im->stride + ix] -
615  im->buf[(iy-1) * im->stride + ix];
616 
617  // XXX Tunable. How to shape the gradient magnitude?
618  W = sqrt(grad_x*grad_x + grad_y*grad_y) + 1;
619  }
620 
621  double fx = x, fy = y;
622  lfps[i].Mx += W * fx;
623  lfps[i].My += W * fy;
624  lfps[i].Mxx += W * fx * fx;
625  lfps[i].Mxy += W * fx * fy;
626  lfps[i].Myy += W * fy * fy;
627  lfps[i].W += W;
628  }
629  }
630  return lfps;
631 }
632 
633 static inline void ptsort(struct pt *pts, int sz)
634 {
635 #define MAYBE_SWAP(arr,apos,bpos) \
636  if (pt_compare_angle(&(arr[apos]), &(arr[bpos])) > 0) { \
637  tmp = arr[apos]; arr[apos] = arr[bpos]; arr[bpos] = tmp; \
638  };
639 
640  if (sz <= 1)
641  return;
642 
643  if (sz == 2) {
644  struct pt tmp;
645  MAYBE_SWAP(pts, 0, 1);
646  return;
647  }
648 
649  // NB: Using less-branch-intensive sorting networks here on the
650  // hunch that it's better for performance.
651  if (sz == 3) { // 3 element bubble sort is optimal
652  struct pt tmp;
653  MAYBE_SWAP(pts, 0, 1);
654  MAYBE_SWAP(pts, 1, 2);
655  MAYBE_SWAP(pts, 0, 1);
656  return;
657  }
658 
659  if (sz == 4) { // 4 element optimal sorting network.
660  struct pt tmp;
661  MAYBE_SWAP(pts, 0, 1); // sort each half, like a merge sort
662  MAYBE_SWAP(pts, 2, 3);
663  MAYBE_SWAP(pts, 0, 2); // minimum value is now at 0.
664  MAYBE_SWAP(pts, 1, 3); // maximum value is now at end.
665  MAYBE_SWAP(pts, 1, 2); // that only leaves the middle two.
666  return;
667  }
668  if (sz == 5) {
669  // this 9-step swap is optimal for a sorting network, but two
670  // steps slower than a generic sort.
671  struct pt tmp;
672  MAYBE_SWAP(pts, 0, 1); // sort each half (3+2), like a merge sort
673  MAYBE_SWAP(pts, 3, 4);
674  MAYBE_SWAP(pts, 1, 2);
675  MAYBE_SWAP(pts, 0, 1);
676  MAYBE_SWAP(pts, 0, 3); // minimum element now at 0
677  MAYBE_SWAP(pts, 2, 4); // maximum element now at end
678  MAYBE_SWAP(pts, 1, 2); // now resort the three elements 1-3.
679  MAYBE_SWAP(pts, 2, 3);
680  MAYBE_SWAP(pts, 1, 2);
681  return;
682  }
683 
684 #undef MAYBE_SWAP
685 
686  // a merge sort with temp storage.
687 
688  struct pt *tmp = malloc(sizeof(struct pt) * sz);
689 
690  memcpy(tmp, pts, sizeof(struct pt) * sz);
691 
692  int asz = sz/2;
693  int bsz = sz - asz;
694 
695  struct pt *as = &tmp[0];
696  struct pt *bs = &tmp[asz];
697 
698  ptsort(as, asz);
699  ptsort(bs, bsz);
700 
701  #define MERGE(apos,bpos) \
702  if (pt_compare_angle(&(as[apos]), &(bs[bpos])) < 0) \
703  pts[outpos++] = as[apos++]; \
704  else \
705  pts[outpos++] = bs[bpos++];
706 
707  int apos = 0, bpos = 0, outpos = 0;
708  while (apos + 8 < asz && bpos + 8 < bsz) {
709  MERGE(apos,bpos); MERGE(apos,bpos); MERGE(apos,bpos); MERGE(apos,bpos);
710  MERGE(apos,bpos); MERGE(apos,bpos); MERGE(apos,bpos); MERGE(apos,bpos);
711  }
712 
713  while (apos < asz && bpos < bsz) {
714  MERGE(apos,bpos);
715  }
716 
717  if (apos < asz)
718  memcpy(&pts[outpos], &as[apos], (asz-apos)*sizeof(struct pt));
719  if (bpos < bsz)
720  memcpy(&pts[outpos], &bs[bpos], (bsz-bpos)*sizeof(struct pt));
721 
722  free(tmp);
723 
724 #undef MERGE
725 }
726 
727 // return 1 if the quad looks okay, 0 if it should be discarded
730  image_u8_t *im,
731  zarray_t *cluster,
732  struct quad *quad,
733  int tag_width,
734  bool normal_border,
735  bool reversed_border) {
736  int res = 0;
737 
738  int sz = zarray_size(cluster);
739  if (sz < 24) // Synchronize with later check.
740  return 0;
741 
743  // Step 1. Sort points so they wrap around the center of the
744  // quad. We will constrain our quad fit to simply partition this
745  // ordered set into 4 groups.
746 
747  // compute a bounding box so that we can order the points
748  // according to their angle WRT the center.
749  struct pt *p1;
750  zarray_get_volatile(cluster, 0, &p1);
751  uint16_t xmax = p1->x;
752  uint16_t xmin = p1->x;
753  uint16_t ymax = p1->y;
754  uint16_t ymin = p1->y;
755  for (int pidx = 1; pidx < zarray_size(cluster); pidx++) {
756  struct pt *p;
757  zarray_get_volatile(cluster, pidx, &p);
758 
759  if (p->x > xmax) {
760  xmax = p->x;
761  } else if (p->x < xmin) {
762  xmin = p->x;
763  }
764 
765  if (p->y > ymax) {
766  ymax = p->y;
767  } else if (p->y < ymin) {
768  ymin = p->y;
769  }
770  }
771 
772  if ((xmax - xmin)*(ymax - ymin) < tag_width) {
773  return 0;
774  }
775 
776  // add some noise to (cx,cy) so that pixels get a more diverse set
777  // of theta estimates. This will help us remove more points.
778  // (Only helps a small amount. The actual noise values here don't
779  // matter much at all, but we want them [-1, 1]. (XXX with
780  // fixed-point, should range be bigger?)
781  float cx = (xmin + xmax) * 0.5 + 0.05118;
782  float cy = (ymin + ymax) * 0.5 + -0.028581;
783 
784  float dot = 0;
785 
786  float quadrants[2][2] = {{-1*(2 << 15), 0}, {2*(2 << 15), 2 << 15}};
787 
788  for (int pidx = 0; pidx < zarray_size(cluster); pidx++) {
789  struct pt *p;
790  zarray_get_volatile(cluster, pidx, &p);
791 
792  float dx = p->x - cx;
793  float dy = p->y - cy;
794 
795  dot += dx*p->gx + dy*p->gy;
796 
797  float quadrant = quadrants[dy > 0][dx > 0];
798  if (dy < 0) {
799  dy = -dy;
800  dx = -dx;
801  }
802 
803  if (dx < 0) {
804  float tmp = dx;
805  dx = dy;
806  dy = -tmp;
807  }
808  p->slope = quadrant + dy/dx;
809  }
810 
811  // Ensure that the black border is inside the white border.
812  quad->reversed_border = dot < 0;
813  if (!reversed_border && quad->reversed_border) {
814  return 0;
815  }
816  if (!normal_border && !quad->reversed_border) {
817  return 0;
818  }
819 
820  // we now sort the points according to theta. This is a prepatory
821  // step for segmenting them into four lines.
822  if (1) {
823  ptsort((struct pt*) cluster->data, zarray_size(cluster));
824 
825  // remove duplicate points. (A byproduct of our segmentation system.)
826  if (1) {
827  int outpos = 1;
828 
829  struct pt *last;
830  zarray_get_volatile(cluster, 0, &last);
831 
832  for (int i = 1; i < sz; i++) {
833 
834  struct pt *p;
835  zarray_get_volatile(cluster, i, &p);
836 
837  if (p->x != last->x || p->y != last->y) {
838 
839  if (i != outpos) {
840  struct pt *out;
841  zarray_get_volatile(cluster, outpos, &out);
842  memcpy(out, p, sizeof(struct pt));
843  }
844 
845  outpos++;
846  }
847 
848  last = p;
849  }
850 
851  cluster->size = outpos;
852  sz = outpos;
853  }
854 
855  }
856 
857  if (sz < 24)
858  return 0;
859 
860 
861  struct line_fit_pt *lfps = compute_lfps(sz, cluster, im);
862 
863  int indices[4];
864  if (1) {
865  if (!quad_segment_maxima(td, cluster, lfps, indices))
866  goto finish;
867  } else {
868  if (!quad_segment_agg(td, cluster, lfps, indices))
869  goto finish;
870  }
871 
872 
873  double lines[4][4];
874 
875  for (int i = 0; i < 4; i++) {
876  int i0 = indices[i];
877  int i1 = indices[(i+1)&3];
878 
879  double err;
880  fit_line(lfps, sz, i0, i1, lines[i], NULL, &err);
881 
882  if (err > td->qtp.max_line_fit_mse) {
883  res = 0;
884  goto finish;
885  }
886  }
887 
888  for (int i = 0; i < 4; i++) {
889  // solve for the intersection of lines (i) and (i+1)&3.
890  // p0 + lambda0*u0 = p1 + lambda1*u1, where u0 and u1
891  // are the line directions.
892  //
893  // lambda0*u0 - lambda1*u1 = (p1 - p0)
894  //
895  // rearrange (solve for lambdas)
896  //
897  // [u0_x -u1_x ] [lambda0] = [ p1_x - p0_x ]
898  // [u0_y -u1_y ] [lambda1] [ p1_y - p0_y ]
899  //
900  // remember that lines[i][0,1] = p, lines[i][2,3] = NORMAL vector.
901  // We want the unit vector, so we need the perpendiculars. Thus, below
902  // we have swapped the x and y components and flipped the y components.
903 
904  double A00 = lines[i][3], A01 = -lines[(i+1)&3][3];
905  double A10 = -lines[i][2], A11 = lines[(i+1)&3][2];
906  double B0 = -lines[i][0] + lines[(i+1)&3][0];
907  double B1 = -lines[i][1] + lines[(i+1)&3][1];
908 
909  double det = A00 * A11 - A10 * A01;
910 
911  // inverse.
912  double W00 = A11 / det, W01 = -A01 / det;
913  if (fabs(det) < 0.001) {
914  res = 0;
915  goto finish;
916  }
917 
918  // solve
919  double L0 = W00*B0 + W01*B1;
920 
921  // compute intersection
922  quad->p[i][0] = lines[i][0] + L0*A00;
923  quad->p[i][1] = lines[i][1] + L0*A10;
924 
925  res = 1;
926  }
927 
928  // reject quads that are too small
929  if (1) {
930  double area = 0;
931 
932  // get area of triangle formed by points 0, 1, 2, 0
933  double length[3], p;
934  for (int i = 0; i < 3; i++) {
935  int idxa = i; // 0, 1, 2,
936  int idxb = (i+1) % 3; // 1, 2, 0
937  length[i] = sqrt(sq(quad->p[idxb][0] - quad->p[idxa][0]) +
938  sq(quad->p[idxb][1] - quad->p[idxa][1]));
939  }
940  p = (length[0] + length[1] + length[2]) / 2;
941 
942  area += sqrt(p*(p-length[0])*(p-length[1])*(p-length[2]));
943 
944  // get area of triangle formed by points 2, 3, 0, 2
945  for (int i = 0; i < 3; i++) {
946  int idxs[] = { 2, 3, 0, 2 };
947  int idxa = idxs[i];
948  int idxb = idxs[i+1];
949  length[i] = sqrt(sq(quad->p[idxb][0] - quad->p[idxa][0]) +
950  sq(quad->p[idxb][1] - quad->p[idxa][1]));
951  }
952  p = (length[0] + length[1] + length[2]) / 2;
953 
954  area += sqrt(p*(p-length[0])*(p-length[1])*(p-length[2]));
955 
956  if (area < 0.95*tag_width*tag_width) {
957  res = 0;
958  goto finish;
959  }
960  }
961 
962  // reject quads whose cumulative angle change isn't equal to 2PI
963  if (1) {
964  for (int i = 0; i < 4; i++) {
965  int i0 = i, i1 = (i+1)&3, i2 = (i+2)&3;
966 
967  double dx1 = quad->p[i1][0] - quad->p[i0][0];
968  double dy1 = quad->p[i1][1] - quad->p[i0][1];
969  double dx2 = quad->p[i2][0] - quad->p[i1][0];
970  double dy2 = quad->p[i2][1] - quad->p[i1][1];
971  double cos_dtheta = (dx1*dx2 + dy1*dy2)/sqrt((dx1*dx1 + dy1*dy1)*(dx2*dx2 + dy2*dy2));
972 
973  if ((cos_dtheta > td->qtp.cos_critical_rad || cos_dtheta < -td->qtp.cos_critical_rad) || dx1*dy2 < dy1*dx2) {
974  res = 0;
975  goto finish;
976  }
977  }
978  }
979 
980  finish:
981 
982  free(lfps);
983 
984  return res;
985 }
986 
987 #define DO_UNIONFIND2(dx, dy) if (im->buf[(y + dy)*s + x + dx] == v) unionfind_connect(uf, y*w + x, (y + dy)*w + x + dx);
988 
989 static void do_unionfind_first_line(unionfind_t *uf, image_u8_t *im, int h, int w, int s)
990 {
991  int y = 0;
992  uint8_t v;
993 
994  for (int x = 1; x < w - 1; x++) {
995  v = im->buf[y*s + x];
996 
997  if (v == 127)
998  continue;
999 
1000  DO_UNIONFIND2(-1, 0);
1001  }
1002 }
1003 
1004 static void do_unionfind_line2(unionfind_t *uf, image_u8_t *im, int h, int w, int s, int y)
1005 {
1006  assert(y > 0);
1007 
1008  uint8_t v_m1_m1;
1009  uint8_t v_0_m1 = im->buf[(y - 1)*s];
1010  uint8_t v_1_m1 = im->buf[(y - 1)*s + 1];
1011  uint8_t v_m1_0;
1012  uint8_t v = im->buf[y*s];
1013 
1014  for (int x = 1; x < w - 1; x++) {
1015  v_m1_m1 = v_0_m1;
1016  v_0_m1 = v_1_m1;
1017  v_1_m1 = im->buf[(y - 1)*s + x + 1];
1018  v_m1_0 = v;
1019  v = im->buf[y*s + x];
1020 
1021  if (v == 127)
1022  continue;
1023 
1024  // (dx,dy) pairs for 8 connectivity:
1025  // (-1, -1) (0, -1) (1, -1)
1026  // (-1, 0) (REFERENCE)
1027  DO_UNIONFIND2(-1, 0);
1028 
1029  if (x == 1 || !((v_m1_0 == v_m1_m1) && (v_m1_m1 == v_0_m1))) {
1030  DO_UNIONFIND2(0, -1);
1031  }
1032 
1033  if (v == 255) {
1034  if (x == 1 || !(v_m1_0 == v_m1_m1 || v_0_m1 == v_m1_m1) ) {
1035  DO_UNIONFIND2(-1, -1);
1036  }
1037  if (!(v_0_m1 == v_1_m1)) {
1038  DO_UNIONFIND2(1, -1);
1039  }
1040  }
1041  }
1042 }
1043 #undef DO_UNIONFIND2
1044 
1045 static void do_unionfind_task2(void *p)
1046 {
1047  struct unionfind_task *task = (struct unionfind_task*) p;
1048 
1049  for (int y = task->y0; y < task->y1; y++) {
1050  do_unionfind_line2(task->uf, task->im, task->h, task->w, task->s, y);
1051  }
1052 }
1053 
1054 static void do_quad_task(void *p)
1055 {
1056  struct quad_task *task = (struct quad_task*) p;
1057 
1058  zarray_t *clusters = task->clusters;
1059  zarray_t *quads = task->quads;
1060  apriltag_detector_t *td = task->td;
1061  int w = task->w, h = task->h;
1062 
1063  for (int cidx = task->cidx0; cidx < task->cidx1; cidx++) {
1064 
1065  zarray_t **cluster;
1066  zarray_get_volatile(clusters, cidx, &cluster);
1067 
1068  if (zarray_size(*cluster) < td->qtp.min_cluster_pixels)
1069  continue;
1070 
1071  // a cluster should contain only boundary points around the
1072  // tag. it cannot be bigger than the whole screen. (Reject
1073  // large connected blobs that will be prohibitively slow to
1074  // fit quads to.) A typical point along an edge is added three
1075  // times (because it has 3 neighbors). The maximum perimeter
1076  // is 2w+2h.
1077  if (zarray_size(*cluster) > 3*(2*w+2*h)) {
1078  continue;
1079  }
1080 
1081  struct quad quad;
1082  memset(&quad, 0, sizeof(struct quad));
1083 
1084  if (fit_quad(td, task->im, *cluster, &quad, task->tag_width, task->normal_border, task->reversed_border)) {
1085  pthread_mutex_lock(&td->mutex);
1086  zarray_add(quads, &quad);
1087  pthread_mutex_unlock(&td->mutex);
1088  }
1089  }
1090 }
1091 
1093 {
1094  int w = im->width, h = im->height, s = im->stride;
1095  assert(w < 32768);
1096  assert(h < 32768);
1097 
1098  image_u8_t *threshim = image_u8_create_alignment(w, h, s);
1099  assert(threshim->stride == s);
1100 
1101  // The idea is to find the maximum and minimum values in a
1102  // window around each pixel. If it's a contrast-free region
1103  // (max-min is small), don't try to binarize. Otherwise,
1104  // threshold according to (max+min)/2.
1105  //
1106  // Mark low-contrast regions with value 127 so that we can skip
1107  // future work on these areas too.
1108 
1109  // however, computing max/min around every pixel is needlessly
1110  // expensive. We compute max/min for tiles. To avoid artifacts
1111  // that arise when high-contrast features appear near a tile
1112  // edge (and thus moving from one tile to another results in a
1113  // large change in max/min value), the max/min values used for
1114  // any pixel are computed from all 3x3 surrounding tiles. Thus,
1115  // the max/min sampling area for nearby pixels overlap by at least
1116  // one tile.
1117  //
1118  // The important thing is that the windows be large enough to
1119  // capture edge transitions; the tag does not need to fit into
1120  // a tile.
1121 
1122  // XXX Tunable. Generally, small tile sizes--- so long as they're
1123  // large enough to span a single tag edge--- seem to be a winner.
1124  const int tilesz = 4;
1125 
1126  // the last (possibly partial) tiles along each row and column will
1127  // just use the min/max value from the last full tile.
1128  int tw = w / tilesz;
1129  int th = h / tilesz;
1130 
1131  uint8_t *im_max = calloc(tw*th, sizeof(uint8_t));
1132  uint8_t *im_min = calloc(tw*th, sizeof(uint8_t));
1133 
1134  // first, collect min/max statistics for each tile
1135  for (int ty = 0; ty < th; ty++) {
1136  for (int tx = 0; tx < tw; tx++) {
1137  uint8_t max = 0, min = 255;
1138 
1139  for (int dy = 0; dy < tilesz; dy++) {
1140 
1141  for (int dx = 0; dx < tilesz; dx++) {
1142 
1143  uint8_t v = im->buf[(ty*tilesz+dy)*s + tx*tilesz + dx];
1144  if (v < min)
1145  min = v;
1146  if (v > max)
1147  max = v;
1148  }
1149  }
1150 
1151  im_max[ty*tw+tx] = max;
1152  im_min[ty*tw+tx] = min;
1153  }
1154  }
1155 
1156  // second, apply 3x3 max/min convolution to "blur" these values
1157  // over larger areas. This reduces artifacts due to abrupt changes
1158  // in the threshold value.
1159  if (1) {
1160  uint8_t *im_max_tmp = calloc(tw*th, sizeof(uint8_t));
1161  uint8_t *im_min_tmp = calloc(tw*th, sizeof(uint8_t));
1162 
1163  for (int ty = 0; ty < th; ty++) {
1164  for (int tx = 0; tx < tw; tx++) {
1165  uint8_t max = 0, min = 255;
1166 
1167  for (int dy = -1; dy <= 1; dy++) {
1168  if (ty+dy < 0 || ty+dy >= th)
1169  continue;
1170  for (int dx = -1; dx <= 1; dx++) {
1171  if (tx+dx < 0 || tx+dx >= tw)
1172  continue;
1173 
1174  uint8_t m = im_max[(ty+dy)*tw+tx+dx];
1175  if (m > max)
1176  max = m;
1177  m = im_min[(ty+dy)*tw+tx+dx];
1178  if (m < min)
1179  min = m;
1180  }
1181  }
1182 
1183  im_max_tmp[ty*tw + tx] = max;
1184  im_min_tmp[ty*tw + tx] = min;
1185  }
1186  }
1187  free(im_max);
1188  free(im_min);
1189  im_max = im_max_tmp;
1190  im_min = im_min_tmp;
1191  }
1192 
1193  for (int ty = 0; ty < th; ty++) {
1194  for (int tx = 0; tx < tw; tx++) {
1195 
1196  int min = im_min[ty*tw + tx];
1197  int max = im_max[ty*tw + tx];
1198 
1199  // low contrast region? (no edges)
1200  if (max - min < td->qtp.min_white_black_diff) {
1201  for (int dy = 0; dy < tilesz; dy++) {
1202  int y = ty*tilesz + dy;
1203 
1204  for (int dx = 0; dx < tilesz; dx++) {
1205  int x = tx*tilesz + dx;
1206 
1207  threshim->buf[y*s+x] = 127;
1208  }
1209  }
1210  continue;
1211  }
1212 
1213  // otherwise, actually threshold this tile.
1214 
1215  // argument for biasing towards dark; specular highlights
1216  // can be substantially brighter than white tag parts
1217  uint8_t thresh = min + (max - min) / 2;
1218 
1219  for (int dy = 0; dy < tilesz; dy++) {
1220  int y = ty*tilesz + dy;
1221 
1222  for (int dx = 0; dx < tilesz; dx++) {
1223  int x = tx*tilesz + dx;
1224 
1225  uint8_t v = im->buf[y*s+x];
1226  if (v > thresh)
1227  threshim->buf[y*s+x] = 255;
1228  else
1229  threshim->buf[y*s+x] = 0;
1230  }
1231  }
1232  }
1233  }
1234 
1235  // we skipped over the non-full-sized tiles above. Fix those now.
1236  if (1) {
1237  for (int y = 0; y < h; y++) {
1238 
1239  // what is the first x coordinate we need to process in this row?
1240 
1241  int x0;
1242 
1243  if (y >= th*tilesz) {
1244  x0 = 0; // we're at the bottom; do the whole row.
1245  } else {
1246  x0 = tw*tilesz; // we only need to do the right most part.
1247  }
1248 
1249  // compute tile coordinates and clamp.
1250  int ty = y / tilesz;
1251  if (ty >= th)
1252  ty = th - 1;
1253 
1254  for (int x = x0; x < w; x++) {
1255  int tx = x / tilesz;
1256  if (tx >= tw)
1257  tx = tw - 1;
1258 
1259  int max = im_max[ty*tw + tx];
1260  int min = im_min[ty*tw + tx];
1261  int thresh = min + (max - min) / 2;
1262 
1263  uint8_t v = im->buf[y*s+x];
1264  if (v > thresh)
1265  threshim->buf[y*s+x] = 255;
1266  else
1267  threshim->buf[y*s+x] = 0;
1268  }
1269  }
1270  }
1271 
1272  free(im_min);
1273  free(im_max);
1274 
1275  // this is a dilate/erode deglitching scheme that does not improve
1276  // anything as far as I can tell.
1277  if (td->qtp.deglitch) {
1278  image_u8_t *tmp = image_u8_create(w, h);
1279 
1280  for (int y = 1; y + 1 < h; y++) {
1281  for (int x = 1; x + 1 < w; x++) {
1282  uint8_t max = 0;
1283  for (int dy = -1; dy <= 1; dy++) {
1284  for (int dx = -1; dx <= 1; dx++) {
1285  uint8_t v = threshim->buf[(y+dy)*s + x + dx];
1286  if (v > max)
1287  max = v;
1288  }
1289  }
1290  tmp->buf[y*s+x] = max;
1291  }
1292  }
1293 
1294  for (int y = 1; y + 1 < h; y++) {
1295  for (int x = 1; x + 1 < w; x++) {
1296  uint8_t min = 255;
1297  for (int dy = -1; dy <= 1; dy++) {
1298  for (int dx = -1; dx <= 1; dx++) {
1299  uint8_t v = tmp->buf[(y+dy)*s + x + dx];
1300  if (v < min)
1301  min = v;
1302  }
1303  }
1304  threshim->buf[y*s+x] = min;
1305  }
1306  }
1307 
1308  image_u8_destroy(tmp);
1309  }
1310 
1311  timeprofile_stamp(td->tp, "threshold");
1312 
1313  return threshim;
1314 }
1315 
1316 // basically the same as threshold(), but assumes the input image is a
1317 // bayer image. It collects statistics separately for each 2x2 block
1318 // of pixels. NOT WELL TESTED.
1320 {
1321  int w = im->width, h = im->height, s = im->stride;
1322 
1323  image_u8_t *threshim = image_u8_create_alignment(w, h, s);
1324  assert(threshim->stride == s);
1325 
1326  int tilesz = 32;
1327  assert((tilesz & 1) == 0); // must be multiple of 2
1328 
1329  int tw = w/tilesz + 1;
1330  int th = h/tilesz + 1;
1331 
1332  uint8_t *im_max[4], *im_min[4];
1333  for (int i = 0; i < 4; i++) {
1334  im_max[i] = calloc(tw*th, sizeof(uint8_t));
1335  im_min[i] = calloc(tw*th, sizeof(uint8_t));
1336  }
1337 
1338  for (int ty = 0; ty < th; ty++) {
1339  for (int tx = 0; tx < tw; tx++) {
1340 
1341  uint8_t max[4] = { 0, 0, 0, 0};
1342  uint8_t min[4] = { 255, 255, 255, 255 };
1343 
1344  for (int dy = 0; dy < tilesz; dy++) {
1345  if (ty*tilesz+dy >= h)
1346  continue;
1347 
1348  for (int dx = 0; dx < tilesz; dx++) {
1349  if (tx*tilesz+dx >= w)
1350  continue;
1351 
1352  // which bayer element is this pixel?
1353  int idx = (2*(dy&1) + (dx&1));
1354 
1355  uint8_t v = im->buf[(ty*tilesz+dy)*s + tx*tilesz + dx];
1356  if (v < min[idx])
1357  min[idx] = v;
1358  if (v > max[idx])
1359  max[idx] = v;
1360  }
1361  }
1362 
1363  for (int i = 0; i < 4; i++) {
1364  im_max[i][ty*tw+tx] = max[i];
1365  im_min[i][ty*tw+tx] = min[i];
1366  }
1367  }
1368  }
1369 
1370  for (int ty = 0; ty < th; ty++) {
1371  for (int tx = 0; tx < tw; tx++) {
1372 
1373  uint8_t max[4] = { 0, 0, 0, 0};
1374  uint8_t min[4] = { 255, 255, 255, 255 };
1375 
1376  for (int dy = -1; dy <= 1; dy++) {
1377  if (ty+dy < 0 || ty+dy >= th)
1378  continue;
1379  for (int dx = -1; dx <= 1; dx++) {
1380  if (tx+dx < 0 || tx+dx >= tw)
1381  continue;
1382 
1383  for (int i = 0; i < 4; i++) {
1384  uint8_t m = im_max[i][(ty+dy)*tw+tx+dx];
1385  if (m > max[i])
1386  max[i] = m;
1387  m = im_min[i][(ty+dy)*tw+tx+dx];
1388  if (m < min[i])
1389  min[i] = m;
1390  }
1391  }
1392  }
1393 
1394  // XXX CONSTANT
1395 // if (max - min < 30)
1396 // continue;
1397 
1398  // argument for biasing towards dark: specular highlights
1399  // can be substantially brighter than white tag parts
1400  uint8_t thresh[4];
1401  for (int i = 0; i < 4; i++) {
1402  thresh[i] = min[i] + (max[i] - min[i]) / 2;
1403  }
1404 
1405  for (int dy = 0; dy < tilesz; dy++) {
1406  int y = ty*tilesz + dy;
1407  if (y >= h)
1408  continue;
1409 
1410  for (int dx = 0; dx < tilesz; dx++) {
1411  int x = tx*tilesz + dx;
1412  if (x >= w)
1413  continue;
1414 
1415  // which bayer element is this pixel?
1416  int idx = (2*(y&1) + (x&1));
1417 
1418  uint8_t v = im->buf[y*s+x];
1419  threshim->buf[y*s+x] = v > thresh[idx];
1420  }
1421  }
1422  }
1423  }
1424 
1425  for (int i = 0; i < 4; i++) {
1426  free(im_min[i]);
1427  free(im_max[i]);
1428  }
1429 
1430  timeprofile_stamp(td->tp, "threshold");
1431 
1432  return threshim;
1433 }
1434 
1435 unionfind_t* connected_components(apriltag_detector_t *td, image_u8_t* threshim, int w, int h, int ts) {
1436  unionfind_t *uf = unionfind_create(w * h);
1437 
1438  if (td->nthreads <= 1) {
1439  do_unionfind_first_line(uf, threshim, h, w, ts);
1440  for (int y = 1; y < h; y++) {
1441  do_unionfind_line2(uf, threshim, h, w, ts, y);
1442  }
1443  } else {
1444  do_unionfind_first_line(uf, threshim, h, w, ts);
1445 
1446  int sz = h;
1447  int chunksize = 1 + sz / (APRILTAG_TASKS_PER_THREAD_TARGET * td->nthreads);
1448  struct unionfind_task *tasks = malloc(sizeof(struct unionfind_task)*(sz / chunksize + 1));
1449 
1450  int ntasks = 0;
1451 
1452  for (int i = 1; i < sz; i += chunksize) {
1453  // each task will process [y0, y1). Note that this attaches
1454  // each cell to the right and down, so row y1 *is* potentially modified.
1455  //
1456  // for parallelization, make sure that each task doesn't touch rows
1457  // used by another thread.
1458  tasks[ntasks].y0 = i;
1459  tasks[ntasks].y1 = imin(sz, i + chunksize - 1);
1460  tasks[ntasks].h = h;
1461  tasks[ntasks].w = w;
1462  tasks[ntasks].s = ts;
1463  tasks[ntasks].uf = uf;
1464  tasks[ntasks].im = threshim;
1465 
1466  workerpool_add_task(td->wp, do_unionfind_task2, &tasks[ntasks]);
1467  ntasks++;
1468  }
1469 
1470  workerpool_run(td->wp);
1471 
1472  // XXX stitch together the different chunks.
1473  for (int i = 1; i < ntasks; i++) {
1474  do_unionfind_line2(uf, threshim, h, w, ts, tasks[i].y0 - 1);
1475  }
1476 
1477  free(tasks);
1478  }
1479  return uf;
1480 }
1481 
1482 zarray_t* do_gradient_clusters(image_u8_t* threshim, int ts, int y0, int y1, int w, int nclustermap, unionfind_t* uf, zarray_t* clusters) {
1483  struct uint64_zarray_entry **clustermap = calloc(nclustermap, sizeof(struct uint64_zarray_entry*));
1484 
1485  int mem_chunk_size = 2048;
1486  struct uint64_zarray_entry** mem_pools = malloc(sizeof(struct uint64_zarray_entry *)*(1 + 2 * nclustermap / mem_chunk_size)); // SmodeTech: avoid memory corruption when nclustermap < mem_chunk_size
1487  int mem_pool_idx = 0;
1488  int mem_pool_loc = 0;
1489  mem_pools[mem_pool_idx] = calloc(mem_chunk_size, sizeof(struct uint64_zarray_entry));
1490 
1491  for (int y = y0; y < y1; y++) {
1492  for (int x = 1; x < w-1; x++) {
1493 
1494  uint8_t v0 = threshim->buf[y*ts + x];
1495  if (v0 == 127)
1496  continue;
1497 
1498  // XXX don't query this until we know we need it?
1499  uint64_t rep0 = unionfind_get_representative(uf, y*w + x);
1500  if (unionfind_get_set_size(uf, rep0) < 25) {
1501  continue;
1502  }
1503 
1504  // whenever we find two adjacent pixels such that one is
1505  // white and the other black, we add the point half-way
1506  // between them to a cluster associated with the unique
1507  // ids of the white and black regions.
1508  //
1509  // We additionally compute the gradient direction (i.e., which
1510  // direction was the white pixel?) Note: if (v1-v0) == 255, then
1511  // (dx,dy) points towards the white pixel. if (v1-v0) == -255, then
1512  // (dx,dy) points towards the black pixel. p.gx and p.gy will thus
1513  // be -255, 0, or 255.
1514  //
1515  // Note that any given pixel might be added to multiple
1516  // different clusters. But in the common case, a given
1517  // pixel will be added multiple times to the same cluster,
1518  // which increases the size of the cluster and thus the
1519  // computational costs.
1520  //
1521  // A possible optimization would be to combine entries
1522  // within the same cluster.
1523 
1524 #define DO_CONN(dx, dy) \
1525  if (1) { \
1526  uint8_t v1 = threshim->buf[(y + dy)*ts + x + dx]; \
1527  \
1528  if (v0 + v1 == 255) { \
1529  uint64_t rep1 = unionfind_get_representative(uf, (y + dy)*w + x + dx); \
1530  if (unionfind_get_set_size(uf, rep1) > 24) { \
1531  uint64_t clusterid; \
1532  if (rep0 < rep1) \
1533  clusterid = (rep1 << 32) + rep0; \
1534  else \
1535  clusterid = (rep0 << 32) + rep1; \
1536  \
1537  /* XXX lousy hash function */ \
1538  uint32_t clustermap_bucket = u64hash_2(clusterid) % nclustermap; \
1539  struct uint64_zarray_entry *entry = clustermap[clustermap_bucket]; \
1540  while (entry && entry->id != clusterid) { \
1541  entry = entry->next; \
1542  } \
1543  \
1544  if (!entry) { \
1545  if (mem_pool_loc == mem_chunk_size) { \
1546  mem_pool_loc = 0; \
1547  mem_pool_idx++; \
1548  mem_pools[mem_pool_idx] = calloc(mem_chunk_size, sizeof(struct uint64_zarray_entry)); \
1549  } \
1550  entry = mem_pools[mem_pool_idx] + mem_pool_loc; \
1551  mem_pool_loc++; \
1552  \
1553  entry->id = clusterid; \
1554  entry->cluster = zarray_create(sizeof(struct pt)); \
1555  entry->next = clustermap[clustermap_bucket]; \
1556  clustermap[clustermap_bucket] = entry; \
1557  } \
1558  \
1559  struct pt p = { .x = 2*x + dx, .y = 2*y + dy, .gx = dx*((int) v1-v0), .gy = dy*((int) v1-v0)}; \
1560  zarray_add(entry->cluster, &p); \
1561  } \
1562  } \
1563  }
1564 
1565  // do 4 connectivity. NB: Arguments must be [-1, 1] or we'll overflow .gx, .gy
1566  DO_CONN(1, 0);
1567  DO_CONN(0, 1);
1568 
1569  // do 8 connectivity
1570  DO_CONN(-1, 1);
1571  DO_CONN(1, 1);
1572  }
1573  }
1574 #undef DO_CONN
1575 
1576  for (int i = 0; i < nclustermap; i++) {
1577  int start = zarray_size(clusters);
1578  for (struct uint64_zarray_entry *entry = clustermap[i]; entry; entry = entry->next) {
1579  struct cluster_hash* cluster_hash = malloc(sizeof(struct cluster_hash));
1580  cluster_hash->hash = u64hash_2(entry->id) % nclustermap;
1581  cluster_hash->id = entry->id;
1582  cluster_hash->data = entry->cluster;
1583  zarray_add(clusters, &cluster_hash);
1584  }
1585  int end = zarray_size(clusters);
1586 
1587  // Do a quick bubblesort on the secondary key.
1588  int n = end - start;
1589  for (int j = 0; j < n - 1; j++) {
1590  for (int k = 0; k < n - j - 1; k++) {
1591  struct cluster_hash** hash1;
1592  struct cluster_hash** hash2;
1593  zarray_get_volatile(clusters, start + k, &hash1);
1594  zarray_get_volatile(clusters, start + k + 1, &hash2);
1595  if ((*hash1)->id > (*hash2)->id) {
1596  struct cluster_hash tmp = **hash2;
1597  **hash2 = **hash1;
1598  **hash1 = tmp;
1599  }
1600  }
1601  }
1602  }
1603  for (int i = 0; i <= mem_pool_idx; i++) {
1604  free(mem_pools[i]);
1605  }
1606  free(mem_pools);
1607  free(clustermap);
1608 
1609  return clusters;
1610 }
1611 
1612 static void do_cluster_task(void *p)
1613 {
1614  struct cluster_task *task = (struct cluster_task*) p;
1615 
1616  do_gradient_clusters(task->im, task->s, task->y0, task->y1, task->w, task->nclustermap, task->uf, task->clusters);
1617 }
1618 
1620  zarray_t* ret = zarray_create(sizeof(struct cluster_hash*));
1622 
1623  int i1 = 0;
1624  int i2 = 0;
1625  int l1 = zarray_size(c1);
1626  int l2 = zarray_size(c2);
1627 
1628  while (i1 < l1 && i2 < l2) {
1629  struct cluster_hash** h1;
1630  struct cluster_hash** h2;
1631  zarray_get_volatile(c1, i1, &h1);
1632  zarray_get_volatile(c2, i2, &h2);
1633 
1634  if ((*h1)->hash == (*h2)->hash && (*h1)->id == (*h2)->id) {
1635  zarray_add_range((*h1)->data, (*h2)->data, 0, zarray_size((*h2)->data));
1636  zarray_add(ret, h1);
1637  i1++;
1638  i2++;
1639  zarray_destroy((*h2)->data);
1640  free(*h2);
1641  } else if ((*h2)->hash < (*h1)->hash || ((*h2)->hash == (*h1)->hash && (*h2)->id < (*h1)->id)) {
1642  zarray_add(ret, h2);
1643  i2++;
1644  } else {
1645  zarray_add(ret, h1);
1646  i1++;
1647  }
1648  }
1649 
1650  zarray_add_range(ret, c1, i1, l1);
1651  zarray_add_range(ret, c2, i2, l2);
1652 
1653  zarray_destroy(c1);
1654  zarray_destroy(c2);
1655 
1656  return ret;
1657 }
1658 
1659 zarray_t* gradient_clusters(apriltag_detector_t *td, image_u8_t* threshim, int w, int h, int ts, unionfind_t* uf) {
1660  zarray_t* clusters;
1661  int nclustermap = 0.2*w*h;
1662 
1663  int sz = h - 1;
1664  int chunksize = 1 + sz / (APRILTAG_TASKS_PER_THREAD_TARGET * td->nthreads);
1665  struct cluster_task *tasks = malloc(sizeof(struct cluster_task)*(sz / chunksize + 1));
1666 
1667  int ntasks = 0;
1668 
1669  for (int i = 1; i < sz; i += chunksize) {
1670  // each task will process [y0, y1). Note that this processes
1671  // each cell to the right and down.
1672  tasks[ntasks].y0 = i;
1673  tasks[ntasks].y1 = imin(sz, i + chunksize);
1674  tasks[ntasks].w = w;
1675  tasks[ntasks].s = ts;
1676  tasks[ntasks].uf = uf;
1677  tasks[ntasks].im = threshim;
1678  tasks[ntasks].nclustermap = nclustermap/(sz / chunksize + 1);
1679  tasks[ntasks].clusters = zarray_create(sizeof(struct cluster_hash*));
1680 
1681  workerpool_add_task(td->wp, do_cluster_task, &tasks[ntasks]);
1682  ntasks++;
1683  }
1684 
1685  workerpool_run(td->wp);
1686 
1687  zarray_t** clusters_list = malloc(sizeof(zarray_t *)*ntasks);
1688  for (int i = 0; i < ntasks; i++) {
1689  clusters_list[i] = tasks[i].clusters;
1690  }
1691 
1692  int length = ntasks;
1693  while (length > 1) {
1694  int write = 0;
1695  for (int i = 0; i < length - 1; i += 2) {
1696  clusters_list[write] = merge_clusters(clusters_list[i], clusters_list[i + 1]);
1697  write++;
1698  }
1699 
1700  if (length % 2) {
1701  clusters_list[write] = clusters_list[length - 1];
1702  }
1703 
1704  length = (length >> 1) + length % 2;
1705  }
1706 
1707  clusters = zarray_create(sizeof(zarray_t*));
1708  zarray_ensure_capacity(clusters, zarray_size(clusters_list[0]));
1709  for (int i = 0; i < zarray_size(clusters_list[0]); i++) {
1710  struct cluster_hash** hash;
1711  zarray_get_volatile(clusters_list[0], i, &hash);
1712  zarray_add(clusters, &(*hash)->data);
1713  free(*hash);
1714  }
1715  zarray_destroy(clusters_list[0]);
1716  free(clusters_list);
1717  free(tasks);
1718  return clusters;
1719 }
1720 
1721 zarray_t* fit_quads(apriltag_detector_t *td, int w, int h, zarray_t* clusters, image_u8_t* im) {
1722  zarray_t *quads = zarray_create(sizeof(struct quad));
1723 
1724  bool normal_border = false;
1725  bool reversed_border = false;
1726  int min_tag_width = 1000000;
1727  for (int i = 0; i < zarray_size(td->tag_families); i++) {
1728  apriltag_family_t* family;
1729  zarray_get(td->tag_families, i, &family);
1730  if (family->width_at_border < min_tag_width) {
1731  min_tag_width = family->width_at_border;
1732  }
1733  normal_border |= !family->reversed_border;
1734  reversed_border |= family->reversed_border;
1735  }
1736  min_tag_width /= td->quad_decimate;
1737  if (min_tag_width < 3) {
1738  min_tag_width = 3;
1739  }
1740 
1741  int sz = zarray_size(clusters);
1742  int chunksize = 1 + sz / (APRILTAG_TASKS_PER_THREAD_TARGET * td->nthreads);
1743  struct quad_task *tasks = malloc(sizeof(struct quad_task)*(sz / chunksize + 1));
1744 
1745  int ntasks = 0;
1746  for (int i = 0; i < sz; i += chunksize) {
1747  tasks[ntasks].td = td;
1748  tasks[ntasks].cidx0 = i;
1749  tasks[ntasks].cidx1 = imin(sz, i + chunksize);
1750  tasks[ntasks].h = h;
1751  tasks[ntasks].w = w;
1752  tasks[ntasks].quads = quads;
1753  tasks[ntasks].clusters = clusters;
1754  tasks[ntasks].im = im;
1755  tasks[ntasks].tag_width = min_tag_width;
1756  tasks[ntasks].normal_border = normal_border;
1757  tasks[ntasks].reversed_border = reversed_border;
1758 
1759  workerpool_add_task(td->wp, do_quad_task, &tasks[ntasks]);
1760  ntasks++;
1761  }
1762 
1763  workerpool_run(td->wp);
1764 
1765  free(tasks);
1766 
1767  return quads;
1768 }
1769 
1771 {
1773  // step 1. threshold the image, creating the edge image.
1774 
1775  int w = im->width, h = im->height;
1776 
1777  image_u8_t *threshim = threshold(td, im);
1778  int ts = threshim->stride;
1779 
1780  if (td->debug)
1781  image_u8_write_pnm(threshim, "debug_threshold.pnm");
1782 
1783 
1785  // step 2. find connected components.
1786  unionfind_t* uf = connected_components(td, threshim, w, h, ts);
1787 
1788  // make segmentation image.
1789  if (td->debug) {
1790  image_u8x3_t *d = image_u8x3_create(w, h);
1791 
1792  uint32_t *colors = (uint32_t*) calloc(w*h, sizeof(*colors));
1793 
1794  for (int y = 0; y < h; y++) {
1795  for (int x = 0; x < w; x++) {
1796  uint32_t v = unionfind_get_representative(uf, y*w+x);
1797 
1799  continue;
1800 
1801  uint32_t color = colors[v];
1802  uint8_t r = color >> 16,
1803  g = color >> 8,
1804  b = color;
1805 
1806  if (color == 0) {
1807  const int bias = 50;
1808  r = bias + (random() % (200-bias));
1809  g = bias + (random() % (200-bias));
1810  b = bias + (random() % (200-bias));
1811  colors[v] = (r << 16) | (g << 8) | b;
1812  }
1813 
1814  d->buf[y*d->stride + 3*x + 0] = r;
1815  d->buf[y*d->stride + 3*x + 1] = g;
1816  d->buf[y*d->stride + 3*x + 2] = b;
1817  }
1818  }
1819 
1820  free(colors);
1821 
1822  image_u8x3_write_pnm(d, "debug_segmentation.pnm");
1823  image_u8x3_destroy(d);
1824  }
1825 
1826 
1827  timeprofile_stamp(td->tp, "unionfind");
1828 
1829  zarray_t* clusters = gradient_clusters(td, threshim, w, h, ts, uf);
1830 
1831  if (td->debug) {
1832  image_u8x3_t *d = image_u8x3_create(w, h);
1833 
1834  for (int i = 0; i < zarray_size(clusters); i++) {
1835  zarray_t *cluster;
1836  zarray_get(clusters, i, &cluster);
1837 
1838  uint32_t r, g, b;
1839 
1840  if (1) {
1841  const int bias = 50;
1842  r = bias + (random() % (200-bias));
1843  g = bias + (random() % (200-bias));
1844  b = bias + (random() % (200-bias));
1845  }
1846 
1847  for (int j = 0; j < zarray_size(cluster); j++) {
1848  struct pt *p;
1849  zarray_get_volatile(cluster, j, &p);
1850 
1851  int x = p->x / 2;
1852  int y = p->y / 2;
1853  d->buf[y*d->stride + 3*x + 0] = r;
1854  d->buf[y*d->stride + 3*x + 1] = g;
1855  d->buf[y*d->stride + 3*x + 2] = b;
1856  }
1857  }
1858 
1859  image_u8x3_write_pnm(d, "debug_clusters.pnm");
1860  image_u8x3_destroy(d);
1861  }
1862 
1863 
1864  image_u8_destroy(threshim);
1865  timeprofile_stamp(td->tp, "make clusters");
1866 
1868  // step 3. process each connected component.
1869 
1870  zarray_t* quads = fit_quads(td, w, h, clusters, im);
1871 
1872  if (td->debug) {
1873  FILE *f = fopen("debug_lines.ps", "w");
1874  fprintf(f, "%%!PS\n\n");
1875 
1876  image_u8_t *im2 = image_u8_copy(im);
1877  image_u8_darken(im2);
1878  image_u8_darken(im2);
1879 
1880  // assume letter, which is 612x792 points.
1881  double scale = fmin(612.0/im->width, 792.0/im2->height);
1882  fprintf(f, "%.15f %.15f scale\n", scale, scale);
1883  fprintf(f, "0 %d translate\n", im2->height);
1884  fprintf(f, "1 -1 scale\n");
1885 
1886  postscript_image(f, im2);
1887 
1888  image_u8_destroy(im2);
1889 
1890  for (int i = 0; i < zarray_size(quads); i++) {
1891  struct quad *q;
1892  zarray_get_volatile(quads, i, &q);
1893 
1894  float rgb[3];
1895  int bias = 100;
1896 
1897  for (int j = 0; j < 3; j++)
1898  rgb[j] = bias + (random() % (255-bias));
1899 
1900  fprintf(f, "%f %f %f setrgbcolor\n", rgb[0]/255.0f, rgb[1]/255.0f, rgb[2]/255.0f);
1901  fprintf(f, "%.15f %.15f moveto %.15f %.15f lineto %.15f %.15f lineto %.15f %.15f lineto %.15f %.15f lineto stroke\n",
1902  q->p[0][0], q->p[0][1],
1903  q->p[1][0], q->p[1][1],
1904  q->p[2][0], q->p[2][1],
1905  q->p[3][0], q->p[3][1],
1906  q->p[0][0], q->p[0][1]);
1907  }
1908 
1909  fclose(f);
1910  }
1911 
1912  timeprofile_stamp(td->tp, "fit quads to clusters");
1913 
1914  unionfind_destroy(uf);
1915 
1916  for (int i = 0; i < zarray_size(clusters); i++) {
1917  zarray_t *cluster;
1918  zarray_get(clusters, i, &cluster);
1919  zarray_destroy(cluster);
1920  }
1921  zarray_destroy(clusters);
1922 
1923  return quads;
1924 }
static unionfind_t * unionfind_create(uint32_t maxid)
Definition: unionfind.h:52
void workerpool_add_task(workerpool_t *wp, void(*f)(void *p), void *p)
Definition: workerpool.c:161
#define APRILTAG_TASKS_PER_THREAD_TARGET
Definition: apriltag.h:43
static void do_unionfind_task2(void *p)
image_u8_t * im
static void zarray_get_volatile(const zarray_t *za, int idx, void *p)
Definition: zarray.h:212
int quad_segment_agg(apriltag_detector_t *td, zarray_t *cluster, struct line_fit_pt *lfps, int indices[4])
void image_u8_darken(image_u8_t *im)
Definition: image_u8.c:288
bool reversed_border
Definition: apriltag.h:49
static void timeprofile_stamp(timeprofile_t *tp, const char *name)
Definition: timeprofile.h:76
void zmaxheap_destroy(zmaxheap_t *heap)
Definition: zmaxheap.c:109
zarray_t * clusters
static void do_unionfind_first_line(unionfind_t *uf, image_u8_t *im, int h, int w, int s)
struct line_fit_pt * compute_lfps(int sz, zarray_t *cluster, image_u8_t *im)
int fit_quad(apriltag_detector_t *td, image_u8_t *im, zarray_t *cluster, struct quad *quad, int tag_width, bool normal_border, bool reversed_border)
pthread_mutex_t mutex
Definition: apriltag.h:190
zarray_t * tag_families
Definition: apriltag.h:184
static void do_unionfind_line2(unionfind_t *uf, image_u8_t *im, int h, int w, int s, int y)
bool reversed_border
Definition: apriltag.h:71
static int zarray_size(const zarray_t *za)
Definition: zarray.h:130
static uint32_t unionfind_get_representative(unionfind_t *uf, uint32_t id)
Definition: unionfind.h:89
static void zarray_ensure_capacity(zarray_t *za, int capacity)
Definition: zarray.h:158
int image_u8x3_write_pnm(const image_u8x3_t *im, const char *path)
Definition: image_u8x3.c:138
static void zarray_destroy(zarray_t *za)
Definition: zarray.h:70
apriltag_detector_t * td
zarray_t * quads
image_u8_t * threshold_bayer(apriltag_detector_t *td, image_u8_t *im)
static void ptsort(struct pt *pts, int sz)
#define MAYBE_SWAP(arr, apos, bpos)
struct uint64_zarray_entry * next
timeprofile_t * tp
Definition: apriltag.h:172
image_u8_t * image_u8_copy(const image_u8_t *in)
Definition: image_u8.c:69
static void zarray_add_range(zarray_t *dest, const zarray_t *source, int start, int end)
Definition: zarray.h:444
const int32_t height
Definition: image_types.h:40
static uint32_t unionfind_get_set_size(unionfind_t *uf, uint32_t id)
Definition: unionfind.h:108
image_u8_t * image_u8_create_alignment(unsigned int width, unsigned int height, unsigned int alignment)
Definition: image_u8.c:59
static zarray_t * zarray_create(size_t el_sz)
Definition: zarray.h:57
const int32_t width
Definition: image_types.h:39
float p[4][2]
Definition: apriltag.h:47
int16_t gy
char * data
Definition: zarray.h:49
uint8_t * buf
Definition: image_types.h:53
#define MERGE(apos, bpos)
const int32_t stride
Definition: image_types.h:41
struct apriltag_quad_thresh_params qtp
Definition: apriltag.h:168
zarray_t * apriltag_quad_thresh(apriltag_detector_t *td, image_u8_t *im)
image_u8x3_t * image_u8x3_create(unsigned int width, unsigned int height)
Definition: image_u8x3.c:43
#define DO_CONN(dx, dy)
int16_t gx
void workerpool_run(workerpool_t *wp)
Definition: workerpool.c:182
uint16_t x
int image_u8_write_pnm(const image_u8_t *im, const char *path)
Definition: image_u8.c:200
static double sq(double v)
Definition: math_util.h:78
zmaxheap_t * zmaxheap_create(size_t el_sz)
Definition: zmaxheap.c:96
static void do_quad_task(void *p)
static void unionfind_destroy(unionfind_t *uf)
Definition: unionfind.h:64
const int32_t stride
Definition: image_types.h:51
static int imin(int a, int b)
Definition: math_util.h:158
float slope
uint16_t y
#define DO_UNIONFIND2(dx, dy)
uint8_t * buf
Definition: image_types.h:43
static void zarray_get(const zarray_t *za, int idx, void *p)
Definition: zarray.h:195
Definition: zarray.h:43
image_u8_t * image_u8_create(unsigned int width, unsigned int height)
Definition: image_u8.c:54
static void do_cluster_task(void *p)
void image_u8_destroy(image_u8_t *im)
Definition: image_u8.c:82
#define min(A, B)
Definition: math_util.h:53
int size
Definition: zarray.h:47
int quad_segment_maxima(apriltag_detector_t *td, zarray_t *cluster, struct line_fit_pt *lfps, int indices[4])
zarray_t * gradient_clusters(apriltag_detector_t *td, image_u8_t *threshim, int w, int h, int ts, unionfind_t *uf)
workerpool_t * wp
Definition: apriltag.h:187
Definition: apriltag.h:45
unionfind_t * connected_components(apriltag_detector_t *td, image_u8_t *threshim, int w, int h, int ts)
void zmaxheap_add(zmaxheap_t *heap, void *p, float v)
Definition: zmaxheap.c:143
float quad_decimate
Definition: apriltag.h:139
int err_compare_descending(const void *_a, const void *_b)
image_u8_t * threshold(apriltag_detector_t *td, image_u8_t *im)
void fit_line(struct line_fit_pt *lfps, int sz, int i0, int i1, double *lineparm, double *err, double *mse)
static void postscript_image(FILE *f, image_u8_t *im)
uint64_t id
static uint32_t u64hash_2(uint64_t x)
zarray_t * cluster
unionfind_t * uf
int zmaxheap_remove_max(zmaxheap_t *heap, void *p, float *v)
Definition: zmaxheap.c:251
int width_at_border
Definition: apriltag.h:69
zarray_t * do_gradient_clusters(image_u8_t *threshim, int ts, int y0, int y1, int w, int nclustermap, unionfind_t *uf, zarray_t *clusters)
zarray_t * merge_clusters(zarray_t *c1, zarray_t *c2)
void image_u8x3_destroy(image_u8x3_t *im)
Definition: image_u8x3.c:78
#define max(A, B)
Definition: math_util.h:52
float pt_compare_angle(struct pt *a, struct pt *b)
static void zarray_add(zarray_t *za, const void *p)
Definition: zarray.h:179
zarray_t * fit_quads(apriltag_detector_t *td, int w, int h, zarray_t *clusters, image_u8_t *im)


apriltag
Author(s): Edwin Olson , Max Krogius
autogenerated on Mon Jun 26 2023 02:26:12