std::vector<TagMatch> detectTags(image_u8_t *im) { const int hamm_hist_max = 10; int hamm_hist[hamm_hist_max]; memset(hamm_hist, 0, sizeof(hamm_hist)); zarray_t *detections = apriltag_detector_detect(td, im); std::vector<TagMatch> tag_matches; for (int i = 0; i < zarray_size(detections); i++) { apriltag_detection_t *det; zarray_get(detections, i, &det); if (!quiet) { printf("detection %3d: id (%2dx%2d)-%-4d, hamming %d, goodness %8.3f, margin %8.3f\n", i, det->family->d*det->family->d, det->family->h, det->id, det->hamming, det->goodness, det->decision_margin); // image_u8_draw_line(im, det->p[x][0], det->p[x][1], det->p[x+1][0], det->p[x+1][1], 255, 10); } if (tag_id == -1 || det->id == tag_id) { TagMatch tag_match; tag_match.id = det->family->d*det->family->d; tag_match.p0 = cv::Point2d(det->p[0][0], det->p[0][1]); tag_match.p1 = cv::Point2d(det->p[1][0], det->p[1][1]); tag_match.p2 = cv::Point2d(det->p[2][0], det->p[2][1]); tag_match.p3 = cv::Point2d(det->p[3][0], det->p[3][1]); Eigen::Map<Eigen::Matrix3d> H_map(det->H->data); tag_match.H = H_map.transpose(); tag_matches.push_back(tag_match); } hamm_hist[det->hamming]++; } apriltag_detections_destroy(detections); if (!quiet) { timeprofile_display(td->tp); printf("nedges: %d, nsegments: %d, nquads: %d\n", td->nedges, td->nsegments, td->nquads); printf("Hamming histogram: "); for (int i = 0; i < hamm_hist_max; i++) printf("%5d", hamm_hist[i]); printf("%12.3f", timeprofile_total_utime(td->tp) / 1.0E3); printf("\n"); } return tag_matches; }
int main(int argc, char *argv[]) { getopt_t *getopt = getopt_create(); getopt_add_bool(getopt, 'h', "help", 0, "Show this help"); getopt_add_bool(getopt, 'd', "debug", 0, "Enable debugging output (slow)"); getopt_add_bool(getopt, 'q', "quiet", 0, "Reduce output"); getopt_add_string(getopt, 'f', "family", "tag36h11", "Tag family to use"); getopt_add_int(getopt, '\0', "border", "1", "Set tag family border size"); getopt_add_int(getopt, 'i', "iters", "1", "Repeat processing on input set this many times"); getopt_add_int(getopt, 't', "threads", "4", "Use this many CPU threads"); getopt_add_double(getopt, 'x', "decimate", "1.0", "Decimate input image by this factor"); getopt_add_double(getopt, 'b', "blur", "0.0", "Apply low-pass blur to input"); getopt_add_bool(getopt, '1', "refine-decode", 0, "Spend more time trying to decode tags"); getopt_add_bool(getopt, '2', "refine-pose", 0, "Spend more time trying to precisely localize tags"); if (!getopt_parse(getopt, argc, argv, 1) || getopt_get_bool(getopt, "help")) { printf("Usage: %s [options] <input files>\n", argv[0]); getopt_do_usage(getopt); exit(0); } const zarray_t *inputs = getopt_get_extra_args(getopt); apriltag_family_t *tf = NULL; const char *famname = getopt_get_string(getopt, "family"); if (!strcmp(famname, "tag36h11")) tf = tag36h11_create(); else if (!strcmp(famname, "tag36h10")) tf = tag36h10_create(); else if (!strcmp(famname, "tag36artoolkit")) tf = tag36artoolkit_create(); else if (!strcmp(famname, "tag25h9")) tf = tag25h9_create(); else if (!strcmp(famname, "tag25h7")) tf = tag25h7_create(); else { printf("Unrecognized tag family name. Use e.g. \"tag36h11\".\n"); exit(-1); } tf->black_border = getopt_get_int(getopt, "border"); apriltag_detector_t *td = apriltag_detector_create(); apriltag_detector_add_family(td, tf); td->quad_decimate = getopt_get_double(getopt, "decimate"); td->quad_sigma = getopt_get_double(getopt, "blur"); td->nthreads = getopt_get_int(getopt, "threads"); td->debug = getopt_get_bool(getopt, "debug"); td->refine_decode = getopt_get_bool(getopt, "refine-decode"); td->refine_pose = getopt_get_bool(getopt, "refine-pose"); int quiet = getopt_get_bool(getopt, "quiet"); int maxiters = getopt_get_int(getopt, "iters"); const int hamm_hist_max = 10; for (int iter = 0; iter < maxiters; iter++) { if (maxiters > 1) printf("iter %d / %d\n", iter + 1, maxiters); for (int input = 0; input < zarray_size(inputs); input++) { int hamm_hist[hamm_hist_max]; memset(hamm_hist, 0, sizeof(hamm_hist)); char *path; zarray_get(inputs, input, &path); if (!quiet) printf("loading %s\n", path); image_u8_t *im = image_u8_create_from_pnm(path); if (im == NULL) { printf("couldn't find %s\n", path); continue; } zarray_t *detections = apriltag_detector_detect(td, im); for (int i = 0; i < zarray_size(detections); i++) { apriltag_detection_t *det; zarray_get(detections, i, &det); if (!quiet) printf("detection %3d: id (%2dx%2d)-%-4d, hamming %d, goodness %8.3f, margin %8.3f\n", i, det->family->d*det->family->d, det->family->h, det->id, det->hamming, det->goodness, det->decision_margin); hamm_hist[det->hamming]++; apriltag_detection_destroy(det); } zarray_destroy(detections); if (!quiet) { timeprofile_display(td->tp); printf("nedges: %d, nsegments: %d, nquads: %d\n", td->nedges, td->nsegments, td->nquads); } if (!quiet) printf("Hamming histogram: "); for (int i = 0; i < hamm_hist_max; i++) printf("%5d", hamm_hist[i]); if (quiet) { printf("%12.3f", timeprofile_total_utime(td->tp) / 1.0E3); } printf("\n"); image_u8_destroy(im); } } // don't deallocate contents of inputs; those are the argv apriltag_detector_destroy(td); tag36h11_destroy(tf); return 0; }
int main(int argc, char *argv[]) { april_tag_family_t *tf = tag36h11_create(); april_tag_detector_t *td = april_tag_detector_create(tf); td->small_tag_refinement = 0; int maxiters = 1; zarray_t *inputs = zarray_create(sizeof(char*)); int waitsec = 0; for (int i = 1; i < argc; i++) { if (!strcmp(argv[i], "-d")) td->debug = 1; else if (!strcmp(argv[i], "-t")) td->nthreads = atoi(argv[++i]); else if (!strcmp(argv[i], "-f")) td->seg_decimate = (i+1 < argc && isdigit(argv[i+1][0])) ? atoi(argv[++i]) : 2; else if (!strcmp(argv[i], "-i")) maxiters = atoi(argv[++i]); else if (!strcmp(argv[i], "-r")) td->small_tag_refinement = 1; else if (!strcmp(argv[i], "-w")) waitsec = atoi(argv[++i]); else if (!strcmp(argv[i], "-b")) td->seg_sigma = atof(argv[++i]); /* else if (!strcmp(argv[i], "--family")) { char *fam = argv[++i]; if (!strcmp(fam, "36h11")) td->tag_family = tag36h11_create(); else if (!strcmp(fam, "36h10")) td->tag_family = tag36h10_create(); } */ else zarray_add(inputs, &argv[i]); } for (int iter = 0; iter < maxiters; iter++) { if (maxiters > 1) printf("iter %d / %d\n", iter + 1, maxiters); for (int input = 0; input < zarray_size(inputs); input++) { char *path; zarray_get(inputs, input, &path); printf("loading %s\n", path); image_u8_t *im = image_u8_create_from_pnm(path); if (im == NULL) { printf("couldn't find %s\n", path); continue; } zarray_t *detections = april_tag_detector_detect(td, im); for (int i = 0; i < zarray_size(detections); i++) { april_tag_detection_t *det; zarray_get(detections, i, &det); printf("detection %3d: id %4d, hamming %d, goodness %f\n", i, det->id, det->hamming, det->goodness); april_tag_detection_destroy(det); } zarray_destroy(detections); timeprofile_display(td->tp); printf("nedges: %d, nsegments: %d, nquads: %d\n", td->nedges, td->nsegments, td->nquads); image_u8_destroy(im); if (zarray_size(inputs) > 1 || iter > 0) sleep(waitsec); } } april_tag_detector_destroy(td); tag36h11_destroy(tf); return 0; }