Austin Schuh | 3333ec7 | 2022-12-29 16:21:06 -0800 | [diff] [blame^] | 1 | /* Copyright (C) 2013-2016, The Regents of The University of Michigan. |
| 2 | All rights reserved. |
| 3 | This software was developed in the APRIL Robotics Lab under the |
| 4 | direction of Edwin Olson, ebolson@umich.edu. This software may be |
| 5 | available under alternative licensing terms; contact the address above. |
| 6 | Redistribution and use in source and binary forms, with or without |
| 7 | modification, are permitted provided that the following conditions are met: |
| 8 | 1. Redistributions of source code must retain the above copyright notice, this |
| 9 | list of conditions and the following disclaimer. |
| 10 | 2. Redistributions in binary form must reproduce the above copyright notice, |
| 11 | this list of conditions and the following disclaimer in the documentation |
| 12 | and/or other materials provided with the distribution. |
| 13 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND |
| 14 | ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED |
| 15 | WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE |
| 16 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR |
| 17 | ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES |
| 18 | (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; |
| 19 | LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND |
| 20 | ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT |
| 21 | (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS |
| 22 | SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. |
| 23 | The views and conclusions contained in the software and documentation are those |
| 24 | of the authors and should not be interpreted as representing official policies, |
| 25 | either expressed or implied, of the Regents of The University of Michigan. |
| 26 | */ |
| 27 | |
| 28 | #include <iostream> |
| 29 | #include <iomanip> |
| 30 | |
| 31 | #include "opencv2/opencv.hpp" |
| 32 | |
| 33 | extern "C" { |
| 34 | #include "apriltag.h" |
| 35 | #include "tag36h11.h" |
| 36 | #include "tag25h9.h" |
| 37 | #include "tag16h5.h" |
| 38 | #include "tagCircle21h7.h" |
| 39 | #include "tagCircle49h12.h" |
| 40 | #include "tagCustom48h12.h" |
| 41 | #include "tagStandard41h12.h" |
| 42 | #include "tagStandard52h13.h" |
| 43 | #include "common/getopt.h" |
| 44 | } |
| 45 | |
| 46 | using namespace std; |
| 47 | using namespace cv; |
| 48 | |
| 49 | |
| 50 | int main(int argc, char *argv[]) |
| 51 | { |
| 52 | getopt_t *getopt = getopt_create(); |
| 53 | |
| 54 | getopt_add_bool(getopt, 'h', "help", 0, "Show this help"); |
| 55 | getopt_add_int(getopt, 'c', "camera", "0", "camera ID"); |
| 56 | getopt_add_bool(getopt, 'd', "debug", 0, "Enable debugging output (slow)"); |
| 57 | getopt_add_bool(getopt, 'q', "quiet", 0, "Reduce output"); |
| 58 | getopt_add_string(getopt, 'f', "family", "tag36h11", "Tag family to use"); |
| 59 | getopt_add_int(getopt, 't', "threads", "1", "Use this many CPU threads"); |
| 60 | getopt_add_double(getopt, 'x', "decimate", "2.0", "Decimate input image by this factor"); |
| 61 | getopt_add_double(getopt, 'b', "blur", "0.0", "Apply low-pass blur to input"); |
| 62 | getopt_add_bool(getopt, '0', "refine-edges", 1, "Spend more time trying to align edges of tags"); |
| 63 | |
| 64 | if (!getopt_parse(getopt, argc, argv, 1) || |
| 65 | getopt_get_bool(getopt, "help")) { |
| 66 | printf("Usage: %s [options]\n", argv[0]); |
| 67 | getopt_do_usage(getopt); |
| 68 | exit(0); |
| 69 | } |
| 70 | |
| 71 | cout << "Enabling video capture" << endl; |
| 72 | |
| 73 | TickMeter meter; |
| 74 | meter.start(); |
| 75 | |
| 76 | // Initialize camera |
| 77 | VideoCapture cap(getopt_get_int(getopt, "camera")); |
| 78 | if (!cap.isOpened()) { |
| 79 | cerr << "Couldn't open video capture device" << endl; |
| 80 | return -1; |
| 81 | } |
| 82 | |
| 83 | // Initialize tag detector with options |
| 84 | apriltag_family_t *tf = NULL; |
| 85 | const char *famname = getopt_get_string(getopt, "family"); |
| 86 | if (!strcmp(famname, "tag36h11")) { |
| 87 | tf = tag36h11_create(); |
| 88 | } else if (!strcmp(famname, "tag25h9")) { |
| 89 | tf = tag25h9_create(); |
| 90 | } else if (!strcmp(famname, "tag16h5")) { |
| 91 | tf = tag16h5_create(); |
| 92 | } else if (!strcmp(famname, "tagCircle21h7")) { |
| 93 | tf = tagCircle21h7_create(); |
| 94 | } else if (!strcmp(famname, "tagCircle49h12")) { |
| 95 | tf = tagCircle49h12_create(); |
| 96 | } else if (!strcmp(famname, "tagStandard41h12")) { |
| 97 | tf = tagStandard41h12_create(); |
| 98 | } else if (!strcmp(famname, "tagStandard52h13")) { |
| 99 | tf = tagStandard52h13_create(); |
| 100 | } else if (!strcmp(famname, "tagCustom48h12")) { |
| 101 | tf = tagCustom48h12_create(); |
| 102 | } else { |
| 103 | printf("Unrecognized tag family name. Use e.g. \"tag36h11\".\n"); |
| 104 | exit(-1); |
| 105 | } |
| 106 | |
| 107 | |
| 108 | apriltag_detector_t *td = apriltag_detector_create(); |
| 109 | apriltag_detector_add_family(td, tf); |
| 110 | |
| 111 | if (errno == ENOMEM) { |
| 112 | printf("Unable to add family to detector due to insufficient memory to allocate the tag-family decoder with the default maximum hamming value of 2. Try choosing an alternative tag family.\n"); |
| 113 | exit(-1); |
| 114 | } |
| 115 | |
| 116 | td->quad_decimate = getopt_get_double(getopt, "decimate"); |
| 117 | td->quad_sigma = getopt_get_double(getopt, "blur"); |
| 118 | td->nthreads = getopt_get_int(getopt, "threads"); |
| 119 | td->debug = getopt_get_bool(getopt, "debug"); |
| 120 | td->refine_edges = getopt_get_bool(getopt, "refine-edges"); |
| 121 | |
| 122 | float frame_counter = 0.0f; |
| 123 | meter.stop(); |
| 124 | cout << "Detector " << famname << " initialized in " |
| 125 | << std::fixed << std::setprecision(3) << meter.getTimeSec() << " seconds" << endl; |
| 126 | #if CV_MAJOR_VERSION > 3 |
| 127 | cout << " " << cap.get(CAP_PROP_FRAME_WIDTH ) << "x" << |
| 128 | cap.get(CAP_PROP_FRAME_HEIGHT ) << " @" << |
| 129 | cap.get(CAP_PROP_FPS) << "FPS" << endl; |
| 130 | #else |
| 131 | cout << " " << cap.get(CV_CAP_PROP_FRAME_WIDTH ) << "x" << |
| 132 | cap.get(CV_CAP_PROP_FRAME_HEIGHT ) << " @" << |
| 133 | cap.get(CV_CAP_PROP_FPS) << "FPS" << endl; |
| 134 | #endif |
| 135 | meter.reset(); |
| 136 | |
| 137 | Mat frame, gray; |
| 138 | while (true) { |
| 139 | errno = 0; |
| 140 | cap >> frame; |
| 141 | cvtColor(frame, gray, COLOR_BGR2GRAY); |
| 142 | |
| 143 | // Make an image_u8_t header for the Mat data |
| 144 | image_u8_t im = { .width = gray.cols, |
| 145 | .height = gray.rows, |
| 146 | .stride = gray.cols, |
| 147 | .buf = gray.data |
| 148 | }; |
| 149 | |
| 150 | zarray_t *detections = apriltag_detector_detect(td, &im); |
| 151 | |
| 152 | if (errno == EAGAIN) { |
| 153 | printf("Unable to create the %d threads requested.\n",td->nthreads); |
| 154 | exit(-1); |
| 155 | } |
| 156 | |
| 157 | // Draw detection outlines |
| 158 | for (int i = 0; i < zarray_size(detections); i++) { |
| 159 | apriltag_detection_t *det; |
| 160 | zarray_get(detections, i, &det); |
| 161 | line(frame, Point(det->p[0][0], det->p[0][1]), |
| 162 | Point(det->p[1][0], det->p[1][1]), |
| 163 | Scalar(0, 0xff, 0), 2); |
| 164 | line(frame, Point(det->p[0][0], det->p[0][1]), |
| 165 | Point(det->p[3][0], det->p[3][1]), |
| 166 | Scalar(0, 0, 0xff), 2); |
| 167 | line(frame, Point(det->p[1][0], det->p[1][1]), |
| 168 | Point(det->p[2][0], det->p[2][1]), |
| 169 | Scalar(0xff, 0, 0), 2); |
| 170 | line(frame, Point(det->p[2][0], det->p[2][1]), |
| 171 | Point(det->p[3][0], det->p[3][1]), |
| 172 | Scalar(0xff, 0, 0), 2); |
| 173 | |
| 174 | stringstream ss; |
| 175 | ss << det->id; |
| 176 | String text = ss.str(); |
| 177 | int fontface = FONT_HERSHEY_SCRIPT_SIMPLEX; |
| 178 | double fontscale = 1.0; |
| 179 | int baseline; |
| 180 | Size textsize = getTextSize(text, fontface, fontscale, 2, |
| 181 | &baseline); |
| 182 | putText(frame, text, Point(det->c[0]-textsize.width/2, |
| 183 | det->c[1]+textsize.height/2), |
| 184 | fontface, fontscale, Scalar(0xff, 0x99, 0), 2); |
| 185 | } |
| 186 | apriltag_detections_destroy(detections); |
| 187 | |
| 188 | imshow("Tag Detections", frame); |
| 189 | if (waitKey(30) >= 0) |
| 190 | break; |
| 191 | } |
| 192 | |
| 193 | apriltag_detector_destroy(td); |
| 194 | |
| 195 | if (!strcmp(famname, "tag36h11")) { |
| 196 | tag36h11_destroy(tf); |
| 197 | } else if (!strcmp(famname, "tag25h9")) { |
| 198 | tag25h9_destroy(tf); |
| 199 | } else if (!strcmp(famname, "tag16h5")) { |
| 200 | tag16h5_destroy(tf); |
| 201 | } else if (!strcmp(famname, "tagCircle21h7")) { |
| 202 | tagCircle21h7_destroy(tf); |
| 203 | } else if (!strcmp(famname, "tagCircle49h12")) { |
| 204 | tagCircle49h12_destroy(tf); |
| 205 | } else if (!strcmp(famname, "tagStandard41h12")) { |
| 206 | tagStandard41h12_destroy(tf); |
| 207 | } else if (!strcmp(famname, "tagStandard52h13")) { |
| 208 | tagStandard52h13_destroy(tf); |
| 209 | } else if (!strcmp(famname, "tagCustom48h12")) { |
| 210 | tagCustom48h12_destroy(tf); |
| 211 | } |
| 212 | |
| 213 | |
| 214 | getopt_destroy(getopt); |
| 215 | |
| 216 | return 0; |
| 217 | } |