WPILibC++ 2024.3.2
AprilTagDetector.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <stdint.h>
8
9#include <memory>
10#include <span>
11#include <string_view>
12#include <utility>
13
14#include <units/angle.h>
15#include <wpi/StringMap.h>
16#include <wpi/SymbolExports.h>
17
19
20namespace frc {
21
22/**
23 * An AprilTag detector engine. This is expensive to set up and tear down, so
24 * most use cases should only create one of these, add a family to it, set up
25 * any other configuration, and repeatedly call Detect().
26 */
28 public:
29 /** Detector configuration. */
30 struct Config {
31 bool operator==(const Config&) const = default;
32
33 /**
34 * How many threads should be used for computation. Default is
35 * single-threaded operation (1 thread).
36 */
37 int numThreads = 1;
38
39 /**
40 * Quad decimation. Detection of quads can be done on a lower-resolution
41 * image, improving speed at a cost of pose accuracy and a slight decrease
42 * in detection rate. Decoding the binary payload is still done at full
43 * resolution. Default is 2.0.
44 */
45 float quadDecimate = 2.0f;
46
47 /**
48 * What Gaussian blur should be applied to the segmented image (used for
49 * quad detection). Very noisy images benefit from non-zero values (e.g.
50 * 0.8). Default is 0.0.
51 */
52 float quadSigma = 0.0f;
53
54 /**
55 * When true, the edges of the each quad are adjusted to "snap to" strong
56 * gradients nearby. This is useful when decimation is employed, as it can
57 * increase the quality of the initial quad estimate substantially.
58 * Generally recommended to be on (true). Default is true.
59 *
60 * Very computationally inexpensive. Option is ignored if
61 * quad_decimate = 1.
62 */
63 bool refineEdges = true;
64
65 /**
66 * How much sharpening should be done to decoded images. This can help
67 * decode small tags but may or may not help in odd lighting conditions or
68 * low light conditions. Default is 0.25.
69 */
70 double decodeSharpening = 0.25;
71
72 /**
73 * Debug mode. When true, the decoder writes a variety of debugging images
74 * to the current working directory at various stages through the detection
75 * process. This is slow and should *not* be used on space-limited systems
76 * such as the RoboRIO. Default is disabled (false).
77 */
78 bool debug = false;
79 };
80
81 /** Quad threshold parameters. */
83 bool operator==(const QuadThresholdParameters&) const = default;
84
85 /**
86 * Threshold used to reject quads containing too few pixels. Default is 5
87 * pixels.
88 */
89 int minClusterPixels = 5;
90
91 /**
92 * How many corner candidates to consider when segmenting a group of pixels
93 * into a quad. Default is 10.
94 */
95 int maxNumMaxima = 10;
96
97 /**
98 * Critical angle. The detector will reject quads where pairs of edges have
99 * angles that are close to straight or close to 180 degrees. Zero means
100 * that no quads are rejected. Default is 10 degrees.
101 */
102 units::radian_t criticalAngle = 10_deg;
103
104 /**
105 * When fitting lines to the contours, the maximum mean squared error
106 * allowed. This is useful in rejecting contours that are far from being
107 * quad shaped; rejecting these quads "early" saves expensive decoding
108 * processing. Default is 10.0.
109 */
110 float maxLineFitMSE = 10.0f;
111
112 /**
113 * Minimum brightness offset. When we build our model of black & white
114 * pixels, we add an extra check that the white model must be (overall)
115 * brighter than the black model. How much brighter? (in pixel values,
116 * [0,255]). Default is 5.
117 */
118 int minWhiteBlackDiff = 5;
119
120 /**
121 * Whether the thresholded image be should be deglitched. Only useful for
122 * very noisy images. Default is disabled (false).
123 */
124 bool deglitch = false;
125 };
126
127 /**
128 * Array of detection results. Each array element is a pointer to an
129 * AprilTagDetection.
130 */
132 : public std::span<AprilTagDetection const* const> {
133 struct private_init {};
134 friend class AprilTagDetector;
135
136 public:
137 Results() = default;
138 Results(void* impl, const private_init&);
139 ~Results() { Destroy(); }
140 Results(const Results&) = delete;
141 Results& operator=(const Results&) = delete;
142 Results(Results&& rhs) : span{std::move(rhs)}, m_impl{rhs.m_impl} {
143 rhs.m_impl = nullptr;
144 }
146
147 private:
148 void Destroy();
149 void* m_impl = nullptr;
150 };
151
153 ~AprilTagDetector() { Destroy(); }
157 : m_impl{rhs.m_impl},
158 m_families{std::move(rhs.m_families)},
159 m_qtpCriticalAngle{rhs.m_qtpCriticalAngle} {
160 rhs.m_impl = nullptr;
161 }
163
164 /**
165 * @{
166 * @name Configuration functions
167 */
168
169 /**
170 * Sets detector configuration.
171 *
172 * @param config Configuration
173 */
174 void SetConfig(const Config& config);
175
176 /**
177 * Gets detector configuration.
178 *
179 * @return Configuration
180 */
182
183 /**
184 * Sets quad threshold parameters.
185 *
186 * @param params Parameters
187 */
189
190 /**
191 * Gets quad threshold parameters.
192 *
193 * @return Parameters
194 */
196
197 /** @} */
198
199 /**
200 * @{
201 * @name Tag family functions
202 */
203
204 /**
205 * Adds a family of tags to be detected.
206 *
207 * @param fam Family name, e.g. "tag16h5"
208 * @param bitsCorrected Maximum number of bits to correct
209 * @return False if family can't be found
210 */
211 bool AddFamily(std::string_view fam, int bitsCorrected = 2);
212
213 /**
214 * Removes a family of tags from the detector.
215 *
216 * @param fam Family name, e.g. "tag16h5"
217 */
219
220 /**
221 * Unregister all families.
222 */
224
225 /** @} */
226
227 /**
228 * Detect tags from an 8-bit image.
229 * The image must be grayscale.
230 *
231 * @param width width of the image
232 * @param height height of the image
233 * @param stride number of bytes between image rows (often the same as width)
234 * @param buf image buffer
235 * @return Results (array of AprilTagDetection pointers)
236 */
237 Results Detect(int width, int height, int stride, uint8_t* buf);
238
239 /**
240 * Detect tags from an 8-bit image.
241 * The image must be grayscale.
242 *
243 * @param width width of the image
244 * @param height height of the image
245 * @param buf image buffer
246 * @return Results (array of AprilTagDetection pointers)
247 */
248 Results Detect(int width, int height, uint8_t* buf) {
249 return Detect(width, height, width, buf);
250 }
251
252 private:
253 void Destroy();
254 void DestroyFamilies();
255 void DestroyFamily(std::string_view name, void* data);
256
257 void* m_impl;
258 wpi::StringMap<void*> m_families;
259 units::radian_t m_qtpCriticalAngle = 10_deg;
260};
261
262} // namespace frc
This file defines the StringMap class.
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Array of detection results.
Definition: AprilTagDetector.h:132
~Results()
Definition: AprilTagDetector.h:139
Results & operator=(Results &&rhs)
Results(const Results &)=delete
Results(void *impl, const private_init &)
Results(Results &&rhs)
Definition: AprilTagDetector.h:142
Results & operator=(const Results &)=delete
An AprilTag detector engine.
Definition: AprilTagDetector.h:27
Results Detect(int width, int height, int stride, uint8_t *buf)
Detect tags from an 8-bit image.
Config GetConfig() const
Gets detector configuration.
Results Detect(int width, int height, uint8_t *buf)
Detect tags from an 8-bit image.
Definition: AprilTagDetector.h:248
AprilTagDetector(AprilTagDetector &&rhs)
Definition: AprilTagDetector.h:156
bool AddFamily(std::string_view fam, int bitsCorrected=2)
Adds a family of tags to be detected.
void RemoveFamily(std::string_view fam)
Removes a family of tags from the detector.
AprilTagDetector & operator=(AprilTagDetector &&rhs)
AprilTagDetector(const AprilTagDetector &)=delete
AprilTagDetector & operator=(const AprilTagDetector &)=delete
~AprilTagDetector()
Definition: AprilTagDetector.h:153
void SetConfig(const Config &config)
Sets detector configuration.
void ClearFamilies()
Unregister all families.
void SetQuadThresholdParameters(const QuadThresholdParameters &params)
Sets quad threshold parameters.
QuadThresholdParameters GetQuadThresholdParameters() const
Gets quad threshold parameters.
basic_string_view< char > string_view
Definition: core.h:501
Definition: AprilTagPoseEstimator.h:15
Definition: array.h:89
constexpr const char * name(const T &)
Detector configuration.
Definition: AprilTagDetector.h:30
bool operator==(const Config &) const =default
Quad threshold parameters.
Definition: AprilTagDetector.h:82
bool operator==(const QuadThresholdParameters &) const =default