apriltag.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 "apriltag.h"
34 
35 #include <math.h>
36 #include <assert.h>
37 #include <stdint.h>
38 #include <string.h>
39 #include <stdio.h>
40 #include <errno.h>
41 
42 #include "common/image_u8.h"
43 #include "common/image_u8x3.h"
44 #include "common/zarray.h"
45 #include "common/matd.h"
46 #include "common/homography.h"
47 #include "common/timeprofile.h"
48 #include "common/math_util.h"
49 #include "common/g2d.h"
50 #include "common/debug_print.h"
51 
52 #include "apriltag_math.h"
53 
55 
56 #ifndef M_PI
57 # define M_PI 3.141592653589793238462643383279502884196
58 #endif
59 
60 #ifdef _WIN32
61 static inline void srandom(unsigned int seed)
62 {
63  srand(seed);
64 }
65 
66 static inline long int random(void)
67 {
68  return rand();
69 }
70 #endif
71 
72 #define APRILTAG_U64_ONE ((uint64_t) 1)
73 
75 
76 // Regresses a model of the form:
77 // intensity(x,y) = C0*x + C1*y + CC2
78 // The J matrix is the:
79 // J = [ x1 y1 1 ]
80 // [ x2 y2 1 ]
81 // [ ... ]
82 // The A matrix is J'J
83 
84 struct graymodel
85 {
86  double A[3][3];
87  double B[3];
88  double C[3];
89 };
90 
91 static void graymodel_init(struct graymodel *gm)
92 {
93  memset(gm, 0, sizeof(struct graymodel));
94 }
95 
96 static void graymodel_add(struct graymodel *gm, double x, double y, double gray)
97 {
98  // update upper right entries of A = J'J
99  gm->A[0][0] += x*x;
100  gm->A[0][1] += x*y;
101  gm->A[0][2] += x;
102  gm->A[1][1] += y*y;
103  gm->A[1][2] += y;
104  gm->A[2][2] += 1;
105 
106  // update B = J'gray
107  gm->B[0] += x * gray;
108  gm->B[1] += y * gray;
109  gm->B[2] += gray;
110 }
111 
112 static void graymodel_solve(struct graymodel *gm)
113 {
114  mat33_sym_solve((double*) gm->A, gm->B, gm->C);
115 }
116 
117 static double graymodel_interpolate(struct graymodel *gm, double x, double y)
118 {
119  return gm->C[0]*x + gm->C[1]*y + gm->C[2];
120 }
121 
123 {
124  uint64_t rcode; // the queried code
125  uint16_t id; // the tag ID (a small integer)
126  uint8_t hamming; // how many errors corrected?
127  uint8_t rotation; // number of rotations [0, 3]
128 };
129 
131 {
132  int nentries;
134 };
135 
140 static uint64_t rotate90(uint64_t w, int numBits)
141 {
142  int p = numBits;
143  uint64_t l = 0;
144  if (numBits % 4 == 1) {
145  p = numBits - 1;
146  l = 1;
147  }
148  w = ((w >> l) << (p/4 + l)) | (w >> (3 * p/ 4 + l) << l) | (w & l);
149  w &= ((APRILTAG_U64_ONE << numBits) - 1);
150  return w;
151 }
152 
153 static void quad_destroy(struct quad *quad)
154 {
155  if (!quad)
156  return;
157 
158  matd_destroy(quad->H);
159  matd_destroy(quad->Hinv);
160  free(quad);
161 }
162 
163 static struct quad *quad_copy(struct quad *quad)
164 {
165  struct quad *q = calloc(1, sizeof(struct quad));
166  memcpy(q, quad, sizeof(struct quad));
167  if (quad->H)
168  q->H = matd_copy(quad->H);
169  if (quad->Hinv)
170  q->Hinv = matd_copy(quad->Hinv);
171  return q;
172 }
173 
174 static void quick_decode_add(struct quick_decode *qd, uint64_t code, int id, int hamming)
175 {
176  uint32_t bucket = code % qd->nentries;
177 
178  while (qd->entries[bucket].rcode != UINT64_MAX) {
179  bucket = (bucket + 1) % qd->nentries;
180  }
181 
182  qd->entries[bucket].rcode = code;
183  qd->entries[bucket].id = id;
184  qd->entries[bucket].hamming = hamming;
185 }
186 
188 {
189  if (!fam->impl)
190  return;
191 
192  struct quick_decode *qd = (struct quick_decode*) fam->impl;
193  free(qd->entries);
194  free(qd);
195  fam->impl = NULL;
196 }
197 
198 static void quick_decode_init(apriltag_family_t *family, int maxhamming)
199 {
200  assert(family->impl == NULL);
201  assert(family->ncodes < 65536);
202 
203  struct quick_decode *qd = calloc(1, sizeof(struct quick_decode));
204  int capacity = family->ncodes;
205 
206  int nbits = family->nbits;
207 
208  if (maxhamming >= 1)
209  capacity += family->ncodes * nbits;
210 
211  if (maxhamming >= 2)
212  capacity += family->ncodes * nbits * (nbits-1);
213 
214  if (maxhamming >= 3)
215  capacity += family->ncodes * nbits * (nbits-1) * (nbits-2);
216 
217  qd->nentries = capacity * 3;
218 
219 // debug_print("capacity %d, size: %.0f kB\n",
220 // capacity, qd->nentries * sizeof(struct quick_decode_entry) / 1024.0);
221 
222  qd->entries = calloc(qd->nentries, sizeof(struct quick_decode_entry));
223  if (qd->entries == NULL) {
224  debug_print("Failed to allocate hamming decode table\n");
225  // errno already set to ENOMEM (Error No MEMory) by calloc() failure
226  return;
227  }
228 
229  for (int i = 0; i < qd->nentries; i++)
230  qd->entries[i].rcode = UINT64_MAX;
231 
232  errno = 0;
233 
234  for (int i = 0; i < family->ncodes; i++) {
235  uint64_t code = family->codes[i];
236 
237  // add exact code (hamming = 0)
238  quick_decode_add(qd, code, i, 0);
239 
240  if (maxhamming >= 1) {
241  // add hamming 1
242  for (int j = 0; j < nbits; j++)
243  quick_decode_add(qd, code ^ (APRILTAG_U64_ONE << j), i, 1);
244  }
245 
246  if (maxhamming >= 2) {
247  // add hamming 2
248  for (int j = 0; j < nbits; j++)
249  for (int k = 0; k < j; k++)
250  quick_decode_add(qd, code ^ (APRILTAG_U64_ONE << j) ^ (APRILTAG_U64_ONE << k), i, 2);
251  }
252 
253  if (maxhamming >= 3) {
254  // add hamming 3
255  for (int j = 0; j < nbits; j++)
256  for (int k = 0; k < j; k++)
257  for (int m = 0; m < k; m++)
258  quick_decode_add(qd, code ^ (APRILTAG_U64_ONE << j) ^ (APRILTAG_U64_ONE << k) ^ (APRILTAG_U64_ONE << m), i, 3);
259  }
260 
261  if (maxhamming > 3) {
262  debug_print("\"maxhamming\" beyond 3 not supported\n");
263  // set errno to Error INvalid VALue
264  errno = EINVAL;
265  return;
266  }
267  }
268 
269  family->impl = qd;
270 
271  #if 0
272  int longest_run = 0;
273  int run = 0;
274  int run_sum = 0;
275  int run_count = 0;
276 
277  // This accounting code doesn't check the last possible run that
278  // occurs at the wrap-around. That's pretty insignificant.
279  for (int i = 0; i < qd->nentries; i++) {
280  if (qd->entries[i].rcode == UINT64_MAX) {
281  if (run > 0) {
282  run_sum += run;
283  run_count ++;
284  }
285  run = 0;
286  } else {
287  run ++;
288  longest_run = imax(longest_run, run);
289  }
290  }
291 
292  printf("quick decode: longest run: %d, average run %.3f\n", longest_run, 1.0 * run_sum / run_count);
293  #endif
294 }
295 
296 // returns an entry with hamming set to 255 if no decode was found.
297 static void quick_decode_codeword(apriltag_family_t *tf, uint64_t rcode,
298  struct quick_decode_entry *entry)
299 {
300  struct quick_decode *qd = (struct quick_decode*) tf->impl;
301 
302  // qd might be null if detector_add_family_bits() failed
303  for (int ridx = 0; qd != NULL && ridx < 4; ridx++) {
304 
305  for (int bucket = rcode % qd->nentries;
306  qd->entries[bucket].rcode != UINT64_MAX;
307  bucket = (bucket + 1) % qd->nentries) {
308 
309  if (qd->entries[bucket].rcode == rcode) {
310  *entry = qd->entries[bucket];
311  entry->rotation = ridx;
312  return;
313  }
314  }
315 
316  rcode = rotate90(rcode, tf->nbits);
317  }
318 
319  entry->rcode = 0;
320  entry->id = 65535;
321  entry->hamming = 255;
322  entry->rotation = 0;
323 }
324 
325 static inline int detection_compare_function(const void *_a, const void *_b)
326 {
329 
330  return a->id - b->id;
331 }
332 
334 {
335  quick_decode_uninit(fam);
336  zarray_remove_value(td->tag_families, &fam, 0);
337 }
338 
340 {
341  zarray_add(td->tag_families, &fam);
342 
343  if (!fam->impl)
344  quick_decode_init(fam, bits_corrected);
345 }
346 
348 {
349  for (int i = 0; i < zarray_size(td->tag_families); i++) {
350  apriltag_family_t *fam;
351  zarray_get(td->tag_families, i, &fam);
352  quick_decode_uninit(fam);
353  }
355 }
356 
358 {
359  apriltag_detector_t *td = (apriltag_detector_t*) calloc(1, sizeof(apriltag_detector_t));
360 
361  td->nthreads = 1;
362  td->quad_decimate = 2.0;
363  td->quad_sigma = 0.0;
364 
365  td->qtp.max_nmaxima = 10;
366  td->qtp.min_cluster_pixels = 5;
367 
368  td->qtp.max_line_fit_mse = 10.0;
369  td->qtp.cos_critical_rad = cos(10 * M_PI / 180);
370  td->qtp.deglitch = false;
371  td->qtp.min_white_black_diff = 5;
372 
374 
375  pthread_mutex_init(&td->mutex, NULL);
376 
377  td->tp = timeprofile_create();
378 
379  td->refine_edges = true;
380  td->decode_sharpening = 0.25;
381 
382 
383  td->debug = false;
384 
385  // NB: defer initialization of td->wp so that the user can
386  // override td->nthreads.
387 
388  return td;
389 }
390 
392 {
393  timeprofile_destroy(td->tp);
394  workerpool_destroy(td->wp);
395 
397 
399  free(td);
400 }
401 
403 {
404  int i0, i1;
407 
410 
412 };
413 
415 {
416  int64_t rcode;
417  double score;
418  matd_t *H, *Hinv;
419 
422 };
423 
424 static matd_t* homography_compute2(double c[4][4]) {
425  double A[] = {
426  c[0][0], c[0][1], 1, 0, 0, 0, -c[0][0]*c[0][2], -c[0][1]*c[0][2], c[0][2],
427  0, 0, 0, c[0][0], c[0][1], 1, -c[0][0]*c[0][3], -c[0][1]*c[0][3], c[0][3],
428  c[1][0], c[1][1], 1, 0, 0, 0, -c[1][0]*c[1][2], -c[1][1]*c[1][2], c[1][2],
429  0, 0, 0, c[1][0], c[1][1], 1, -c[1][0]*c[1][3], -c[1][1]*c[1][3], c[1][3],
430  c[2][0], c[2][1], 1, 0, 0, 0, -c[2][0]*c[2][2], -c[2][1]*c[2][2], c[2][2],
431  0, 0, 0, c[2][0], c[2][1], 1, -c[2][0]*c[2][3], -c[2][1]*c[2][3], c[2][3],
432  c[3][0], c[3][1], 1, 0, 0, 0, -c[3][0]*c[3][2], -c[3][1]*c[3][2], c[3][2],
433  0, 0, 0, c[3][0], c[3][1], 1, -c[3][0]*c[3][3], -c[3][1]*c[3][3], c[3][3],
434  };
435 
436  double epsilon = 1e-10;
437 
438  // Eliminate.
439  for (int col = 0; col < 8; col++) {
440  // Find best row to swap with.
441  double max_val = 0;
442  int max_val_idx = -1;
443  for (int row = col; row < 8; row++) {
444  double val = fabs(A[row*9 + col]);
445  if (val > max_val) {
446  max_val = val;
447  max_val_idx = row;
448  }
449  }
450 
451  if (max_val < epsilon) {
452  debug_print("WRN: Matrix is singular.\n");
453  return NULL;
454  }
455 
456  // Swap to get best row.
457  if (max_val_idx != col) {
458  for (int i = col; i < 9; i++) {
459  double tmp = A[col*9 + i];
460  A[col*9 + i] = A[max_val_idx*9 + i];
461  A[max_val_idx*9 + i] = tmp;
462  }
463  }
464 
465  // Do eliminate.
466  for (int i = col + 1; i < 8; i++) {
467  double f = A[i*9 + col]/A[col*9 + col];
468  A[i*9 + col] = 0;
469  for (int j = col + 1; j < 9; j++) {
470  A[i*9 + j] -= f*A[col*9 + j];
471  }
472  }
473  }
474 
475  // Back solve.
476  for (int col = 7; col >=0; col--) {
477  double sum = 0;
478  for (int i = col + 1; i < 8; i++) {
479  sum += A[col*9 + i]*A[i*9 + 8];
480  }
481  A[col*9 + 8] = (A[col*9 + 8] - sum)/A[col*9 + col];
482  }
483  return matd_create_data(3, 3, (double[]) { A[8], A[17], A[26], A[35], A[44], A[53], A[62], A[71], 1 });
484 }
485 
486 // returns non-zero if an error occurs (i.e., H has no inverse)
487 static int quad_update_homographies(struct quad *quad)
488 {
489  //zarray_t *correspondences = zarray_create(sizeof(float[4]));
490 
491  double corr_arr[4][4];
492 
493  for (int i = 0; i < 4; i++) {
494  corr_arr[i][0] = (i==0 || i==3) ? -1 : 1;
495  corr_arr[i][1] = (i==0 || i==1) ? -1 : 1;
496  corr_arr[i][2] = quad->p[i][0];
497  corr_arr[i][3] = quad->p[i][1];
498  }
499 
500  if (quad->H)
501  matd_destroy(quad->H);
502  if (quad->Hinv)
503  matd_destroy(quad->Hinv);
504 
505  // XXX Tunable
506  quad->H = homography_compute2(corr_arr);
507  if (quad->H != NULL) {
508  quad->Hinv = matd_inverse(quad->H);
509  if (quad->Hinv != NULL) {
510  // Success!
511  return 0;
512  }
513  matd_destroy(quad->H);
514  quad->H = NULL;
515  }
516  return -1;
517 }
518 
519 static double value_for_pixel(image_u8_t *im, double px, double py) {
520  int x1 = floor(px - 0.5);
521  int x2 = ceil(px - 0.5);
522  double x = px - 0.5 - x1;
523  int y1 = floor(py - 0.5);
524  int y2 = ceil(py - 0.5);
525  double y = py - 0.5 - y1;
526  if (x1 < 0 || x2 >= im->width || y1 < 0 || y2 >= im->height) {
527  return -1;
528  }
529  return im->buf[y1*im->stride + x1]*(1-x)*(1-y) +
530  im->buf[y1*im->stride + x2]*x*(1-y) +
531  im->buf[y2*im->stride + x1]*(1-x)*y +
532  im->buf[y2*im->stride + x2]*x*y;
533 }
534 
535 static void sharpen(apriltag_detector_t* td, double* values, int size) {
536  double *sharpened = malloc(sizeof(double)*size*size);
537  double kernel[9] = {
538  0, -1, 0,
539  -1, 4, -1,
540  0, -1, 0
541  };
542 
543  for (int y = 0; y < size; y++) {
544  for (int x = 0; x < size; x++) {
545  sharpened[y*size + x] = 0;
546  for (int i = 0; i < 3; i++) {
547  for (int j = 0; j < 3; j++) {
548  if ((y + i - 1) < 0 || (y + i - 1) > size - 1 || (x + j - 1) < 0 || (x + j - 1) > size - 1) {
549  continue;
550  }
551  sharpened[y*size + x] += values[(y + i - 1)*size + (x + j - 1)]*kernel[i*3 + j];
552  }
553  }
554  }
555  }
556 
557 
558  for (int y = 0; y < size; y++) {
559  for (int x = 0; x < size; x++) {
560  values[y*size + x] = values[y*size + x] + td->decode_sharpening*sharpened[y*size + x];
561  }
562  }
563 
564  free(sharpened);
565 }
566 
567 // returns the decision margin. Return < 0 if the detection should be rejected.
568 static float quad_decode(apriltag_detector_t* td, apriltag_family_t *family, image_u8_t *im, struct quad *quad, struct quick_decode_entry *entry, image_u8_t *im_samples)
569 {
570  // decode the tag binary contents by sampling the pixel
571  // closest to the center of each bit cell.
572 
573  // We will compute a threshold by sampling known white/black cells around this tag.
574  // This sampling is achieved by considering a set of samples along lines.
575  //
576  // coordinates are given in bit coordinates. ([0, fam->border_width]).
577  //
578  // { initial x, initial y, delta x, delta y, WHITE=1 }
579  float patterns[] = {
580  // left white column
581  -0.5, 0.5,
582  0, 1,
583  1,
584 
585  // left black column
586  0.5, 0.5,
587  0, 1,
588  0,
589 
590  // right white column
591  family->width_at_border + 0.5, .5,
592  0, 1,
593  1,
594 
595  // right black column
596  family->width_at_border - 0.5, .5,
597  0, 1,
598  0,
599 
600  // top white row
601  0.5, -0.5,
602  1, 0,
603  1,
604 
605  // top black row
606  0.5, 0.5,
607  1, 0,
608  0,
609 
610  // bottom white row
611  0.5, family->width_at_border + 0.5,
612  1, 0,
613  1,
614 
615  // bottom black row
616  0.5, family->width_at_border - 0.5,
617  1, 0,
618  0
619 
620  // XXX double-counts the corners.
621  };
622 
623  struct graymodel whitemodel, blackmodel;
624  graymodel_init(&whitemodel);
625  graymodel_init(&blackmodel);
626 
627  for (int pattern_idx = 0; pattern_idx < sizeof(patterns)/(5*sizeof(float)); pattern_idx ++) {
628  float *pattern = &patterns[pattern_idx * 5];
629 
630  int is_white = pattern[4];
631 
632  for (int i = 0; i < family->width_at_border; i++) {
633  double tagx01 = (pattern[0] + i*pattern[2]) / (family->width_at_border);
634  double tagy01 = (pattern[1] + i*pattern[3]) / (family->width_at_border);
635 
636  double tagx = 2*(tagx01-0.5);
637  double tagy = 2*(tagy01-0.5);
638 
639  double px, py;
640  homography_project(quad->H, tagx, tagy, &px, &py);
641 
642  // don't round
643  int ix = px;
644  int iy = py;
645  if (ix < 0 || iy < 0 || ix >= im->width || iy >= im->height)
646  continue;
647 
648  int v = im->buf[iy*im->stride + ix];
649 
650  if (im_samples) {
651  im_samples->buf[iy*im_samples->stride + ix] = (1-is_white)*255;
652  }
653 
654  if (is_white)
655  graymodel_add(&whitemodel, tagx, tagy, v);
656  else
657  graymodel_add(&blackmodel, tagx, tagy, v);
658  }
659  }
660 
661  if (family->width_at_border > 1) {
662  graymodel_solve(&whitemodel);
663  graymodel_solve(&blackmodel);
664  } else {
665  graymodel_solve(&whitemodel);
666  blackmodel.C[0] = 0;
667  blackmodel.C[1] = 0;
668  blackmodel.C[2] = blackmodel.B[2]/4;
669  }
670 
671  // XXX Tunable
672  if ((graymodel_interpolate(&whitemodel, 0, 0) - graymodel_interpolate(&blackmodel, 0, 0) < 0) != family->reversed_border) {
673  return -1;
674  }
675 
676  // compute the average decision margin (how far was each bit from
677  // the decision boundary?
678  //
679  // we score this separately for white and black pixels and return
680  // the minimum average threshold for black/white pixels. This is
681  // to penalize thresholds that are too close to an extreme.
682  float black_score = 0, white_score = 0;
683  float black_score_count = 1, white_score_count = 1;
684 
685  double *values = calloc(family->total_width*family->total_width, sizeof(double));
686 
687  int min_coord = (family->width_at_border - family->total_width)/2;
688  for (int i = 0; i < family->nbits; i++) {
689  int bity = family->bit_y[i];
690  int bitx = family->bit_x[i];
691 
692  double tagx01 = (bitx + 0.5) / (family->width_at_border);
693  double tagy01 = (bity + 0.5) / (family->width_at_border);
694 
695  // scale to [-1, 1]
696  double tagx = 2*(tagx01-0.5);
697  double tagy = 2*(tagy01-0.5);
698 
699  double px, py;
700  homography_project(quad->H, tagx, tagy, &px, &py);
701 
702  double v = value_for_pixel(im, px, py);
703 
704  if (v == -1) {
705  continue;
706  }
707 
708  double thresh = (graymodel_interpolate(&blackmodel, tagx, tagy) + graymodel_interpolate(&whitemodel, tagx, tagy)) / 2.0;
709  values[family->total_width*(bity - min_coord) + bitx - min_coord] = v - thresh;
710 
711  if (im_samples) {
712  int ix = px;
713  int iy = py;
714  im_samples->buf[iy*im_samples->stride + ix] = (v < thresh) * 255;
715  }
716  }
717 
718  sharpen(td, values, family->total_width);
719 
720  uint64_t rcode = 0;
721  for (int i = 0; i < family->nbits; i++) {
722  int bity = family->bit_y[i];
723  int bitx = family->bit_x[i];
724  rcode = (rcode << 1);
725  double v = values[(bity - min_coord)*family->total_width + bitx - min_coord];
726 
727  if (v > 0) {
728  white_score += v;
729  white_score_count++;
730  rcode |= 1;
731  } else {
732  black_score -= v;
733  black_score_count++;
734  }
735  }
736 
737  quick_decode_codeword(family, rcode, entry);
738  free(values);
739  return fmin(white_score / white_score_count, black_score / black_score_count);
740 }
741 
742 static void refine_edges(apriltag_detector_t *td, image_u8_t *im_orig, struct quad *quad)
743 {
744  double lines[4][4]; // for each line, [Ex Ey nx ny]
745 
746  for (int edge = 0; edge < 4; edge++) {
747  int a = edge, b = (edge + 1) & 3; // indices of the end points.
748 
749  // compute the normal to the current line estimate
750  double nx = quad->p[b][1] - quad->p[a][1];
751  double ny = -quad->p[b][0] + quad->p[a][0];
752  double mag = sqrt(nx*nx + ny*ny);
753  nx /= mag;
754  ny /= mag;
755 
756  if (quad->reversed_border) {
757  nx = -nx;
758  ny = -ny;
759  }
760 
761  // we will now fit a NEW line by sampling points near
762  // our original line that have large gradients. On really big tags,
763  // we're willing to sample more to get an even better estimate.
764  int nsamples = imax(16, mag / 8); // XXX tunable
765 
766  // stats for fitting a line...
767  double Mx = 0, My = 0, Mxx = 0, Mxy = 0, Myy = 0, N = 0;
768 
769  for (int s = 0; s < nsamples; s++) {
770  // compute a point along the line... Note, we're avoiding
771  // sampling *right* at the corners, since those points are
772  // the least reliable.
773  double alpha = (1.0 + s) / (nsamples + 1);
774  double x0 = alpha*quad->p[a][0] + (1-alpha)*quad->p[b][0];
775  double y0 = alpha*quad->p[a][1] + (1-alpha)*quad->p[b][1];
776 
777  // search along the normal to this line, looking at the
778  // gradients along the way. We're looking for a strong
779  // response.
780  double Mn = 0;
781  double Mcount = 0;
782 
783  // XXX tunable: how far to search? We want to search far
784  // enough that we find the best edge, but not so far that
785  // we hit other edges that aren't part of the tag. We
786  // shouldn't ever have to search more than quad_decimate,
787  // since otherwise we would (ideally) have started our
788  // search on another pixel in the first place. Likewise,
789  // for very small tags, we don't want the range to be too
790  // big.
791  double range = td->quad_decimate + 1;
792 
793  // XXX tunable step size.
794  for (double n = -range; n <= range; n += 0.25) {
795  // Because of the guaranteed winding order of the
796  // points in the quad, we will start inside the white
797  // portion of the quad and work our way outward.
798  //
799  // sample to points (x1,y1) and (x2,y2) XXX tunable:
800  // how far +/- to look? Small values compute the
801  // gradient more precisely, but are more sensitive to
802  // noise.
803  double grange = 1;
804  int x1 = x0 + (n + grange)*nx;
805  int y1 = y0 + (n + grange)*ny;
806  if (x1 < 0 || x1 >= im_orig->width || y1 < 0 || y1 >= im_orig->height)
807  continue;
808 
809  int x2 = x0 + (n - grange)*nx;
810  int y2 = y0 + (n - grange)*ny;
811  if (x2 < 0 || x2 >= im_orig->width || y2 < 0 || y2 >= im_orig->height)
812  continue;
813 
814  int g1 = im_orig->buf[y1*im_orig->stride + x1];
815  int g2 = im_orig->buf[y2*im_orig->stride + x2];
816 
817  if (g1 < g2) // reject points whose gradient is "backwards". They can only hurt us.
818  continue;
819 
820  double weight = (g2 - g1)*(g2 - g1); // XXX tunable. What shape for weight=f(g2-g1)?
821 
822  // compute weighted average of the gradient at this point.
823  Mn += weight*n;
824  Mcount += weight;
825  }
826 
827  // what was the average point along the line?
828  if (Mcount == 0)
829  continue;
830 
831  double n0 = Mn / Mcount;
832 
833  // where is the point along the line?
834  double bestx = x0 + n0*nx;
835  double besty = y0 + n0*ny;
836 
837  // update our line fit statistics
838  Mx += bestx;
839  My += besty;
840  Mxx += bestx*bestx;
841  Mxy += bestx*besty;
842  Myy += besty*besty;
843  N++;
844  }
845 
846  // fit a line
847  double Ex = Mx / N, Ey = My / N;
848  double Cxx = Mxx / N - Ex*Ex;
849  double Cxy = Mxy / N - Ex*Ey;
850  double Cyy = Myy / N - Ey*Ey;
851 
852  // TODO: Can replace this with same code as in fit_line.
853  double normal_theta = .5 * atan2f(-2*Cxy, (Cyy - Cxx));
854  nx = cosf(normal_theta);
855  ny = sinf(normal_theta);
856  lines[edge][0] = Ex;
857  lines[edge][1] = Ey;
858  lines[edge][2] = nx;
859  lines[edge][3] = ny;
860  }
861 
862  // now refit the corners of the quad
863  for (int i = 0; i < 4; i++) {
864 
865  // solve for the intersection of lines (i) and (i+1)&3.
866  double A00 = lines[i][3], A01 = -lines[(i+1)&3][3];
867  double A10 = -lines[i][2], A11 = lines[(i+1)&3][2];
868  double B0 = -lines[i][0] + lines[(i+1)&3][0];
869  double B1 = -lines[i][1] + lines[(i+1)&3][1];
870 
871  double det = A00 * A11 - A10 * A01;
872 
873  // inverse.
874  if (fabs(det) > 0.001) {
875  // solve
876  double W00 = A11 / det, W01 = -A01 / det;
877 
878  double L0 = W00*B0 + W01*B1;
879 
880  // Compute intersection. Note that line i represents the line from corner i to (i+1)&3, so
881  // the intersection of line i with line (i+1)&3 represents corner (i+1)&3.
882  quad->p[(i+1)&3][0] = lines[i][0] + L0*A00;
883  quad->p[(i+1)&3][1] = lines[i][1] + L0*A10;
884  } else {
885  // this is a bad sign. We'll just keep the corner we had.
886 // debug_print("bad det: %15f %15f %15f %15f %15f\n", A00, A11, A10, A01, det);
887  }
888  }
889 }
890 
891 static void quad_decode_task(void *_u)
892 {
893  struct quad_decode_task *task = (struct quad_decode_task*) _u;
894  apriltag_detector_t *td = task->td;
895  image_u8_t *im = task->im;
896 
897  for (int quadidx = task->i0; quadidx < task->i1; quadidx++) {
898  struct quad *quad_original;
899  zarray_get_volatile(task->quads, quadidx, &quad_original);
900 
901  // refine edges is not dependent upon the tag family, thus
902  // apply this optimization BEFORE the other work.
903  //if (td->quad_decimate > 1 && td->refine_edges) {
904  if (td->refine_edges) {
905  refine_edges(td, im, quad_original);
906  }
907 
908  // make sure the homographies are computed...
909  if (quad_update_homographies(quad_original) != 0)
910  continue;
911 
912  for (int famidx = 0; famidx < zarray_size(td->tag_families); famidx++) {
913  apriltag_family_t *family;
914  zarray_get(td->tag_families, famidx, &family);
915 
916  if (family->reversed_border != quad_original->reversed_border) {
917  continue;
918  }
919 
920  // since the geometry of tag families can vary, start any
921  // optimization process over with the original quad.
922  struct quad *quad = quad_copy(quad_original);
923 
924  struct quick_decode_entry entry;
925 
926  float decision_margin = quad_decode(td, family, im, quad, &entry, task->im_samples);
927 
928  if (decision_margin >= 0 && entry.hamming < 255) {
929  apriltag_detection_t *det = calloc(1, sizeof(apriltag_detection_t));
930 
931  det->family = family;
932  det->id = entry.id;
933  det->hamming = entry.hamming;
934  det->decision_margin = decision_margin;
935 
936  double theta = entry.rotation * M_PI / 2.0;
937  double c = cos(theta), s = sin(theta);
938 
939  // Fix the rotation of our homography to properly orient the tag
940  matd_t *R = matd_create(3,3);
941  MATD_EL(R, 0, 0) = c;
942  MATD_EL(R, 0, 1) = -s;
943  MATD_EL(R, 1, 0) = s;
944  MATD_EL(R, 1, 1) = c;
945  MATD_EL(R, 2, 2) = 1;
946 
947  det->H = matd_op("M*M", quad->H, R);
948 
949  matd_destroy(R);
950 
951  homography_project(det->H, 0, 0, &det->c[0], &det->c[1]);
952 
953  // [-1, -1], [1, -1], [1, 1], [-1, 1], Desired points
954  // [-1, 1], [1, 1], [1, -1], [-1, -1], FLIP Y
955  // adjust the points in det->p so that they correspond to
956  // counter-clockwise around the quad, starting at -1,-1.
957  for (int i = 0; i < 4; i++) {
958  int tcx = (i == 1 || i == 2) ? 1 : -1;
959  int tcy = (i < 2) ? 1 : -1;
960 
961  double p[2];
962 
963  homography_project(det->H, tcx, tcy, &p[0], &p[1]);
964 
965  det->p[i][0] = p[0];
966  det->p[i][1] = p[1];
967  }
968 
969  pthread_mutex_lock(&td->mutex);
970  zarray_add(task->detections, &det);
971  pthread_mutex_unlock(&td->mutex);
972  }
973 
974  quad_destroy(quad);
975  }
976  }
977 }
978 
980 {
981  if (det == NULL)
982  return;
983 
984  matd_destroy(det->H);
985  free(det);
986 }
987 
988 static int prefer_smaller(int pref, double q0, double q1)
989 {
990  if (pref) // already prefer something? exit.
991  return pref;
992 
993  if (q0 < q1)
994  return -1; // we now prefer q0
995  if (q1 < q0)
996  return 1; // we now prefer q1
997 
998  // no preference
999  return 0;
1000 }
1001 
1003 {
1004  if (zarray_size(td->tag_families) == 0) {
1006  debug_print("No tag families enabled\n");
1007  return s;
1008  }
1009 
1010  if (td->wp == NULL || td->nthreads != workerpool_get_nthreads(td->wp)) {
1011  workerpool_destroy(td->wp);
1012  td->wp = workerpool_create(td->nthreads);
1013  if (td->wp == NULL) {
1014  // creating workerpool failed - return empty zarray
1015  return zarray_create(sizeof(apriltag_detection_t*));
1016  }
1017  }
1018 
1019  timeprofile_clear(td->tp);
1020  timeprofile_stamp(td->tp, "init");
1021 
1023  // Step 1. Detect quads according to requested image decimation
1024  // and blurring parameters.
1025  image_u8_t *quad_im = im_orig;
1026  if (td->quad_decimate > 1) {
1027  quad_im = image_u8_decimate(im_orig, td->quad_decimate);
1028 
1029  timeprofile_stamp(td->tp, "decimate");
1030  }
1031 
1032  if (td->quad_sigma != 0) {
1033  // compute a reasonable kernel width by figuring that the
1034  // kernel should go out 2 std devs.
1035  //
1036  // max sigma ksz
1037  // 0.499 1 (disabled)
1038  // 0.999 3
1039  // 1.499 5
1040  // 1.999 7
1041 
1042  float sigma = fabsf((float) td->quad_sigma);
1043 
1044  int ksz = 4 * sigma; // 2 std devs in each direction
1045  if ((ksz & 1) == 0)
1046  ksz++;
1047 
1048  if (ksz > 1) {
1049 
1050  if (td->quad_sigma > 0) {
1051  // Apply a blur
1052  image_u8_gaussian_blur(quad_im, sigma, ksz);
1053  } else {
1054  // SHARPEN the image by subtracting the low frequency components.
1055  image_u8_t *orig = image_u8_copy(quad_im);
1056  image_u8_gaussian_blur(quad_im, sigma, ksz);
1057 
1058  for (int y = 0; y < orig->height; y++) {
1059  for (int x = 0; x < orig->width; x++) {
1060  int vorig = orig->buf[y*orig->stride + x];
1061  int vblur = quad_im->buf[y*quad_im->stride + x];
1062 
1063  int v = 2*vorig - vblur;
1064  if (v < 0)
1065  v = 0;
1066  if (v > 255)
1067  v = 255;
1068 
1069  quad_im->buf[y*quad_im->stride + x] = (uint8_t) v;
1070  }
1071  }
1072  image_u8_destroy(orig);
1073  }
1074  }
1075  }
1076 
1077  timeprofile_stamp(td->tp, "blur/sharp");
1078 
1079  if (td->debug)
1080  image_u8_write_pnm(quad_im, "debug_preprocess.pnm");
1081 
1082  zarray_t *quads = apriltag_quad_thresh(td, quad_im);
1083 
1084  // adjust centers of pixels so that they correspond to the
1085  // original full-resolution image.
1086  if (td->quad_decimate > 1) {
1087  for (int i = 0; i < zarray_size(quads); i++) {
1088  struct quad *q;
1089  zarray_get_volatile(quads, i, &q);
1090 
1091  for (int j = 0; j < 4; j++) {
1092  if (td->quad_decimate == 1.5) {
1093  q->p[j][0] *= td->quad_decimate;
1094  q->p[j][1] *= td->quad_decimate;
1095  } else {
1096  q->p[j][0] = (q->p[j][0] - 0.5)*td->quad_decimate + 0.5;
1097  q->p[j][1] = (q->p[j][1] - 0.5)*td->quad_decimate + 0.5;
1098  }
1099  }
1100  }
1101  }
1102 
1103  if (quad_im != im_orig)
1104  image_u8_destroy(quad_im);
1105 
1106  zarray_t *detections = zarray_create(sizeof(apriltag_detection_t*));
1107 
1108  td->nquads = zarray_size(quads);
1109 
1110  timeprofile_stamp(td->tp, "quads");
1111 
1112  if (td->debug) {
1113  image_u8_t *im_quads = image_u8_copy(im_orig);
1114  image_u8_darken(im_quads);
1115  image_u8_darken(im_quads);
1116 
1117  srandom(0);
1118 
1119  for (int i = 0; i < zarray_size(quads); i++) {
1120  struct quad *quad;
1121  zarray_get_volatile(quads, i, &quad);
1122 
1123  const int bias = 100;
1124  int color = bias + (random() % (255-bias));
1125 
1126  image_u8_draw_line(im_quads, quad->p[0][0], quad->p[0][1], quad->p[1][0], quad->p[1][1], color, 1);
1127  image_u8_draw_line(im_quads, quad->p[1][0], quad->p[1][1], quad->p[2][0], quad->p[2][1], color, 1);
1128  image_u8_draw_line(im_quads, quad->p[2][0], quad->p[2][1], quad->p[3][0], quad->p[3][1], color, 1);
1129  image_u8_draw_line(im_quads, quad->p[3][0], quad->p[3][1], quad->p[0][0], quad->p[0][1], color, 1);
1130  }
1131 
1132  image_u8_write_pnm(im_quads, "debug_quads_raw.pnm");
1133  image_u8_destroy(im_quads);
1134  }
1135 
1137  // Step 2. Decode tags from each quad.
1138  if (1) {
1139  image_u8_t *im_samples = td->debug ? image_u8_copy(im_orig) : NULL;
1140 
1141  int chunksize = 1 + zarray_size(quads) / (APRILTAG_TASKS_PER_THREAD_TARGET * td->nthreads);
1142 
1143  struct quad_decode_task *tasks = malloc(sizeof(struct quad_decode_task)*(zarray_size(quads) / chunksize + 1));
1144 
1145  int ntasks = 0;
1146  for (int i = 0; i < zarray_size(quads); i+= chunksize) {
1147  tasks[ntasks].i0 = i;
1148  tasks[ntasks].i1 = imin(zarray_size(quads), i + chunksize);
1149  tasks[ntasks].quads = quads;
1150  tasks[ntasks].td = td;
1151  tasks[ntasks].im = im_orig;
1152  tasks[ntasks].detections = detections;
1153 
1154  tasks[ntasks].im_samples = im_samples;
1155 
1156  workerpool_add_task(td->wp, quad_decode_task, &tasks[ntasks]);
1157  ntasks++;
1158  }
1159 
1160  workerpool_run(td->wp);
1161 
1162  free(tasks);
1163 
1164  if (im_samples != NULL) {
1165  image_u8_write_pnm(im_samples, "debug_samples.pnm");
1166  image_u8_destroy(im_samples);
1167  }
1168  }
1169 
1170  if (td->debug) {
1171  image_u8_t *im_quads = image_u8_copy(im_orig);
1172  image_u8_darken(im_quads);
1173  image_u8_darken(im_quads);
1174 
1175  srandom(0);
1176 
1177  for (int i = 0; i < zarray_size(quads); i++) {
1178  struct quad *quad;
1179  zarray_get_volatile(quads, i, &quad);
1180 
1181  const int bias = 100;
1182  int color = bias + (random() % (255-bias));
1183 
1184  image_u8_draw_line(im_quads, quad->p[0][0], quad->p[0][1], quad->p[1][0], quad->p[1][1], color, 1);
1185  image_u8_draw_line(im_quads, quad->p[1][0], quad->p[1][1], quad->p[2][0], quad->p[2][1], color, 1);
1186  image_u8_draw_line(im_quads, quad->p[2][0], quad->p[2][1], quad->p[3][0], quad->p[3][1], color, 1);
1187  image_u8_draw_line(im_quads, quad->p[3][0], quad->p[3][1], quad->p[0][0], quad->p[0][1], color, 1);
1188 
1189  }
1190 
1191  image_u8_write_pnm(im_quads, "debug_quads_fixed.pnm");
1192  image_u8_destroy(im_quads);
1193  }
1194 
1195  timeprofile_stamp(td->tp, "decode+refinement");
1196 
1198  // Step 3. Reconcile detections--- don't report the same tag more
1199  // than once. (Allow non-overlapping duplicate detections.)
1200  if (1) {
1201  zarray_t *poly0 = g2d_polygon_create_zeros(4);
1202  zarray_t *poly1 = g2d_polygon_create_zeros(4);
1203 
1204  for (int i0 = 0; i0 < zarray_size(detections); i0++) {
1205 
1206  apriltag_detection_t *det0;
1207  zarray_get(detections, i0, &det0);
1208 
1209  for (int k = 0; k < 4; k++)
1210  zarray_set(poly0, k, det0->p[k], NULL);
1211 
1212  for (int i1 = i0+1; i1 < zarray_size(detections); i1++) {
1213 
1214  apriltag_detection_t *det1;
1215  zarray_get(detections, i1, &det1);
1216 
1217  if (det0->id != det1->id || det0->family != det1->family)
1218  continue;
1219 
1220  for (int k = 0; k < 4; k++)
1221  zarray_set(poly1, k, det1->p[k], NULL);
1222 
1223  if (g2d_polygon_overlaps_polygon(poly0, poly1)) {
1224  // the tags overlap. Delete one, keep the other.
1225 
1226  int pref = 0; // 0 means undecided which one we'll keep.
1227  pref = prefer_smaller(pref, det0->hamming, det1->hamming); // want small hamming
1228  pref = prefer_smaller(pref, -det0->decision_margin, -det1->decision_margin); // want bigger margins
1229 
1230  // if we STILL don't prefer one detection over the other, then pick
1231  // any deterministic criterion.
1232  for (int i = 0; i < 4; i++) {
1233  pref = prefer_smaller(pref, det0->p[i][0], det1->p[i][0]);
1234  pref = prefer_smaller(pref, det0->p[i][1], det1->p[i][1]);
1235  }
1236 
1237  if (pref == 0) {
1238  // at this point, we should only be undecided if the tag detections
1239  // are *exactly* the same. How would that happen?
1240  debug_print("uh oh, no preference for overlappingdetection\n");
1241  }
1242 
1243  if (pref < 0) {
1244  // keep det0, destroy det1
1246  zarray_remove_index(detections, i1, 1);
1247  i1--; // retry the same index
1248  goto retry1;
1249  } else {
1250  // keep det1, destroy det0
1252  zarray_remove_index(detections, i0, 1);
1253  i0--; // retry the same index.
1254  goto retry0;
1255  }
1256  }
1257 
1258  retry1: ;
1259  }
1260 
1261  retry0: ;
1262  }
1263 
1264  zarray_destroy(poly0);
1265  zarray_destroy(poly1);
1266  }
1267 
1268  timeprofile_stamp(td->tp, "reconcile");
1269 
1271  // Produce final debug output
1272  if (td->debug) {
1273 
1274  image_u8_t *darker = image_u8_copy(im_orig);
1275  image_u8_darken(darker);
1276  image_u8_darken(darker);
1277 
1278  // assume letter, which is 612x792 points.
1279  FILE *f = fopen("debug_output.ps", "w");
1280  fprintf(f, "%%!PS\n\n");
1281  double scale = fmin(612.0/darker->width, 792.0/darker->height);
1282  fprintf(f, "%f %f scale\n", scale, scale);
1283  fprintf(f, "0 %d translate\n", darker->height);
1284  fprintf(f, "1 -1 scale\n");
1285  postscript_image(f, darker);
1286 
1287  image_u8_destroy(darker);
1288 
1289  for (int i = 0; i < zarray_size(detections); i++) {
1290  apriltag_detection_t *det;
1291  zarray_get(detections, i, &det);
1292 
1293  float rgb[3];
1294  int bias = 100;
1295 
1296  for (int j = 0; j < 3; j++) {
1297  rgb[j] = bias + (random() % (255-bias));
1298  }
1299 
1300  fprintf(f, "%f %f %f setrgbcolor\n", rgb[0]/255.0f, rgb[1]/255.0f, rgb[2]/255.0f);
1301  fprintf(f, "%f %f moveto %f %f lineto %f %f lineto %f %f lineto %f %f lineto stroke\n",
1302  det->p[0][0], det->p[0][1],
1303  det->p[1][0], det->p[1][1],
1304  det->p[2][0], det->p[2][1],
1305  det->p[3][0], det->p[3][1],
1306  det->p[0][0], det->p[0][1]);
1307  }
1308 
1309  fprintf(f, "showpage\n");
1310  fclose(f);
1311  }
1312 
1313  if (td->debug) {
1314  image_u8_t *darker = image_u8_copy(im_orig);
1315  image_u8_darken(darker);
1316  image_u8_darken(darker);
1317 
1318  image_u8x3_t *out = image_u8x3_create(darker->width, darker->height);
1319  for (int y = 0; y < im_orig->height; y++) {
1320  for (int x = 0; x < im_orig->width; x++) {
1321  out->buf[y*out->stride + 3*x + 0] = darker->buf[y*darker->stride + x];
1322  out->buf[y*out->stride + 3*x + 1] = darker->buf[y*darker->stride + x];
1323  out->buf[y*out->stride + 3*x + 2] = darker->buf[y*darker->stride + x];
1324  }
1325  }
1326 
1327  image_u8_destroy(darker);
1328 
1329  for (int i = 0; i < zarray_size(detections); i++) {
1330  apriltag_detection_t *det;
1331  zarray_get(detections, i, &det);
1332 
1333  float rgb[3];
1334  int bias = 100;
1335 
1336  for (int j = 0; j < 3; j++) {
1337  rgb[j] = bias + (random() % (255-bias));
1338  }
1339 
1340  for (int j = 0; j < 4; j++) {
1341  int k = (j + 1) & 3;
1343  det->p[j][0], det->p[j][1], det->p[k][0], det->p[k][1],
1344  (uint8_t[]) { rgb[0], rgb[1], rgb[2] },
1345  1);
1346  }
1347  }
1348 
1349  image_u8x3_write_pnm(out, "debug_output.pnm");
1350  image_u8x3_destroy(out);
1351  }
1352 
1353  // deallocate
1354  if (td->debug) {
1355  FILE *f = fopen("debug_quads.ps", "w");
1356  fprintf(f, "%%!PS\n\n");
1357 
1358  image_u8_t *darker = image_u8_copy(im_orig);
1359  image_u8_darken(darker);
1360  image_u8_darken(darker);
1361 
1362  // assume letter, which is 612x792 points.
1363  double scale = fmin(612.0/darker->width, 792.0/darker->height);
1364  fprintf(f, "%f %f scale\n", scale, scale);
1365  fprintf(f, "0 %d translate\n", darker->height);
1366  fprintf(f, "1 -1 scale\n");
1367 
1368  postscript_image(f, darker);
1369 
1370  image_u8_destroy(darker);
1371 
1372  for (int i = 0; i < zarray_size(quads); i++) {
1373  struct quad *q;
1374  zarray_get_volatile(quads, i, &q);
1375 
1376  float rgb[3];
1377  int bias = 100;
1378 
1379  for (int j = 0; j < 3; j++) {
1380  rgb[j] = bias + (random() % (255-bias));
1381  }
1382 
1383  fprintf(f, "%f %f %f setrgbcolor\n", rgb[0]/255.0f, rgb[1]/255.0f, rgb[2]/255.0f);
1384  fprintf(f, "%f %f moveto %f %f lineto %f %f lineto %f %f lineto %f %f lineto stroke\n",
1385  q->p[0][0], q->p[0][1],
1386  q->p[1][0], q->p[1][1],
1387  q->p[2][0], q->p[2][1],
1388  q->p[3][0], q->p[3][1],
1389  q->p[0][0], q->p[0][1]);
1390  }
1391 
1392  fprintf(f, "showpage\n");
1393  fclose(f);
1394  }
1395 
1396  timeprofile_stamp(td->tp, "debug output");
1397 
1398  for (int i = 0; i < zarray_size(quads); i++) {
1399  struct quad *quad;
1400  zarray_get_volatile(quads, i, &quad);
1401  matd_destroy(quad->H);
1402  matd_destroy(quad->Hinv);
1403  }
1404 
1405  zarray_destroy(quads);
1406 
1408  timeprofile_stamp(td->tp, "cleanup");
1409 
1410  return detections;
1411 }
1412 
1413 
1414 // Call this method on each of the tags returned by apriltag_detector_detect
1416 {
1417  for (int i = 0; i < zarray_size(detections); i++) {
1418  apriltag_detection_t *det;
1419  zarray_get(detections, i, &det);
1420 
1422  }
1423 
1424  zarray_destroy(detections);
1425 }
1426 
1428 {
1429  assert(fam != NULL);
1430  assert(idx >= 0 && idx < fam->ncodes);
1431 
1432  uint64_t code = fam->codes[idx];
1433 
1435 
1436  int white_border_width = fam->width_at_border + (fam->reversed_border ? 0 : 2);
1437  int white_border_start = (fam->total_width - white_border_width)/2;
1438  // Make 1px white border
1439  for (int i = 0; i < white_border_width - 1; i += 1) {
1440  im->buf[white_border_start*im->stride + white_border_start + i] = 255;
1441  im->buf[(white_border_start + i)*im->stride + fam->total_width - 1 - white_border_start] = 255;
1442  im->buf[(fam->total_width - 1 - white_border_start)*im->stride + white_border_start + i + 1] = 255;
1443  im->buf[(white_border_start + 1 + i)*im->stride + white_border_start] = 255;
1444  }
1445 
1446  int border_start = (fam->total_width - fam->width_at_border)/2;
1447  for (int i = 0; i < fam->nbits; i++) {
1448  if (code & (APRILTAG_U64_ONE << (fam->nbits - i - 1))) {
1449  im->buf[(fam->bit_y[i] + border_start)*im->stride + fam->bit_x[i] + border_start] = 255;
1450  }
1451  }
1452  return im;
1453 }
static void graymodel_add(struct graymodel *gm, double x, double y, double gray)
Definition: apriltag.c:96
matd_t * H
Definition: apriltag.h:53
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 zarray_get_volatile(const zarray_t *za, int idx, void *p)
Definition: zarray.h:212
zarray_t * quads
Definition: apriltag.c:405
static double value_for_pixel(image_u8_t *im, double px, double py)
Definition: apriltag.c:519
static void zarray_sort(zarray_t *za, int(*compar)(const void *, const void *))
Definition: zarray.h:406
static int zarray_remove_value(zarray_t *za, const void *p, int shuffle)
Definition: zarray.h:273
void image_u8_darken(image_u8_t *im)
Definition: image_u8.c:288
bool reversed_border
Definition: apriltag.h:49
void workerpool_destroy(workerpool_t *wp)
Definition: workerpool.c:129
static void timeprofile_stamp(timeprofile_t *tp, const char *name)
Definition: timeprofile.h:76
uint32_t ncodes
Definition: apriltag.h:64
image_u8_t * image_u8_decimate(image_u8_t *im, float ffactor)
Definition: image_u8.c:436
apriltag_detector_t * td
Definition: apriltag.c:406
void * impl
Definition: apriltag.h:87
image_u8_t * im_samples
Definition: apriltag.c:411
#define debug_print(fmt,...)
Definition: debug_print.h:39
int nentries
Definition: apriltag.c:132
static void quad_decode_task(void *_u)
Definition: apriltag.c:891
double p[4][2]
Definition: apriltag.h:230
static void mat33_sym_solve(const double *A, const double *B, double *R)
Definition: apriltag_math.h:83
pthread_mutex_t mutex
Definition: apriltag.h:190
zarray_t * tag_families
Definition: apriltag.h:184
bool reversed_border
Definition: apriltag.h:71
static int zarray_size(const zarray_t *za)
Definition: zarray.h:130
workerpool_t * workerpool_create(int nthreads)
Definition: workerpool.c:101
static void homography_project(const matd_t *H, double x, double y, double *ox, double *oy)
Definition: homography.h:134
matd_t * Hinv
Definition: apriltag.h:53
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
static void zarray_set(zarray_t *za, int idx, const void *p, void *outp)
Definition: zarray.h:319
static void quick_decode_uninit(apriltag_family_t *fam)
Definition: apriltag.c:187
#define APRILTAG_U64_ONE
Definition: apriltag.c:72
static void sharpen(apriltag_detector_t *td, double *values, int size)
Definition: apriltag.c:535
apriltag_detector_t * apriltag_detector_create()
Definition: apriltag.c:357
static void zarray_remove_index(zarray_t *za, int idx, int shuffle)
Definition: zarray.h:234
static int imax(int a, int b)
Definition: math_util.h:163
static int detection_compare_function(const void *_a, const void *_b)
Definition: apriltag.c:325
#define MATD_EL(m, row, col)
Definition: matd.h:65
void apriltag_detections_destroy(zarray_t *detections)
Definition: apriltag.c:1415
timeprofile_t * tp
Definition: apriltag.h:172
image_u8_t * image_u8_copy(const image_u8_t *in)
Definition: image_u8.c:69
const int32_t height
Definition: image_types.h:40
Definition: apriltag.c:122
zarray_t * g2d_polygon_create_zeros(int sz)
Definition: g2d.c:68
uint64_t * codes
Definition: apriltag.h:67
uint8_t rotation
Definition: apriltag.c:127
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
matd_t * Hinv
Definition: apriltag.c:418
int g2d_polygon_overlaps_polygon(const zarray_t *polya, const zarray_t *polyb)
Definition: g2d.c:618
static uint64_t rotate90(uint64_t w, int numBits)
Definition: apriltag.c:140
static float quad_decode(apriltag_detector_t *td, apriltag_family_t *family, image_u8_t *im, struct quad *quad, struct quick_decode_entry *entry, image_u8_t *im_samples)
Definition: apriltag.c:568
uint8_t * buf
Definition: image_types.h:53
uint64_t rcode
Definition: apriltag.c:124
static void quick_decode_add(struct quick_decode *qd, uint64_t code, int id, int hamming)
Definition: apriltag.c:174
uint8_t hamming
Definition: apriltag.c:126
const int32_t stride
Definition: image_types.h:41
zarray_t * detections
Definition: apriltag.c:409
struct apriltag_quad_thresh_params qtp
Definition: apriltag.h:168
static void quad_destroy(struct quad *quad)
Definition: apriltag.c:153
image_u8x3_t * image_u8x3_create(unsigned int width, unsigned int height)
Definition: image_u8x3.c:43
void workerpool_run(workerpool_t *wp)
Definition: workerpool.c:182
double B[3]
Definition: apriltag.c:87
void apriltag_detector_remove_family(apriltag_detector_t *td, apriltag_family_t *fam)
Definition: apriltag.c:333
void apriltag_detection_destroy(apriltag_detection_t *det)
Definition: apriltag.c:979
int image_u8_write_pnm(const image_u8_t *im, const char *path)
Definition: image_u8.c:200
static timeprofile_t * timeprofile_create()
Definition: timeprofile.h:54
matd_t * matd_create_data(int rows, int cols, const TYPE *data)
Definition: matd.c:71
void image_u8_gaussian_blur(image_u8_t *im, double sigma, int ksz)
Definition: image_u8.c:346
const int32_t stride
Definition: image_types.h:51
static int imin(int a, int b)
Definition: math_util.h:158
static matd_t * homography_compute2(double c[4][4])
Definition: apriltag.c:424
zarray_t * apriltag_quad_thresh(apriltag_detector_t *td, image_u8_t *im)
uint8_t * buf
Definition: image_types.h:43
static void graymodel_init(struct graymodel *gm)
Definition: apriltag.c:91
uint32_t nquads
Definition: apriltag.h:176
Definition: matd.h:45
void matd_destroy(matd_t *m)
Definition: matd.c:222
static int quad_update_homographies(struct quad *quad)
Definition: apriltag.c:487
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
uint32_t nbits
Definition: apriltag.h:74
void image_u8_destroy(image_u8_t *im)
Definition: image_u8.c:82
image_u8_t * im
Definition: apriltag.c:408
double C[3]
Definition: apriltag.c:88
int workerpool_get_nthreads(workerpool_t *wp)
Definition: workerpool.c:156
workerpool_t * wp
Definition: apriltag.h:187
Definition: apriltag.h:45
uint16_t id
Definition: apriltag.c:125
void image_u8x3_draw_line(image_u8x3_t *im, float x0, float y0, float x1, float y1, uint8_t rgb[3], int width)
Definition: image_u8x3.c:166
matd_t * matd_create(int rows, int cols)
Definition: matd.c:46
static void refine_edges(apriltag_detector_t *td, image_u8_t *im_orig, struct quad *quad)
Definition: apriltag.c:742
matd_t * matd_inverse(const matd_t *x)
Definition: matd.c:481
double decode_sharpening
Definition: apriltag.h:161
float quad_decimate
Definition: apriltag.h:139
static double graymodel_interpolate(struct graymodel *gm, double x, double y)
Definition: apriltag.c:117
static int prefer_smaller(int pref, double q0, double q1)
Definition: apriltag.c:988
void apriltag_detector_destroy(apriltag_detector_t *td)
Definition: apriltag.c:391
static void postscript_image(FILE *f, image_u8_t *im)
static void zarray_clear(zarray_t *za)
Definition: zarray.h:365
image_u8_t * apriltag_to_image(apriltag_family_t *fam, int idx)
Definition: apriltag.c:1427
struct quick_decode_entry * entries
Definition: apriltag.c:133
uint32_t * bit_y
Definition: apriltag.h:76
float decision_margin
Definition: apriltag.h:217
void apriltag_detector_add_family_bits(apriltag_detector_t *td, apriltag_family_t *fam, int bits_corrected)
Definition: apriltag.c:339
static void timeprofile_clear(timeprofile_t *tp)
Definition: timeprofile.h:70
void apriltag_detector_clear_families(apriltag_detector_t *td)
Definition: apriltag.c:347
uint32_t * bit_x
Definition: apriltag.h:75
matd_t * matd_copy(const matd_t *m)
Definition: matd.c:154
matd_t * matd_op(const char *expr,...)
Definition: matd.c:794
double A[3][3]
Definition: apriltag.c:86
int width_at_border
Definition: apriltag.h:69
#define M_PI
Definition: math_util.h:46
static void quick_decode_init(apriltag_family_t *family, int maxhamming)
Definition: apriltag.c:198
static void timeprofile_destroy(timeprofile_t *tp)
Definition: timeprofile.h:64
void image_u8x3_destroy(image_u8x3_t *im)
Definition: image_u8x3.c:78
static void quick_decode_codeword(apriltag_family_t *tf, uint64_t rcode, struct quick_decode_entry *entry)
Definition: apriltag.c:297
void image_u8_draw_line(image_u8_t *im, float x0, float y0, float x1, float y1, int v, int width)
Definition: image_u8.c:265
static void zarray_add(zarray_t *za, const void *p)
Definition: zarray.h:179
zarray_t * apriltag_detector_detect(apriltag_detector_t *td, image_u8_t *im_orig)
Definition: apriltag.c:1002
static void graymodel_solve(struct graymodel *gm)
Definition: apriltag.c:112
apriltag_family_t * family
Definition: apriltag.h:199
static struct quad * quad_copy(struct quad *quad)
Definition: apriltag.c:163


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