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


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