AprilTagConfig
This message is used to configure the AprilTag node. It allows selecting the AprilTag family to detect, adjusting decoding thresholds, and fine-tuning quad detection parameters.Examples of functionality
Reference
class
dai::AprilTagConfig
variable
variable
std::int32_t quadDecimate
Detection of quads can be done on a lower-resolution image, improving speed at a cost of pose accuracy and a slight decrease in detection rate. Decoding the binary payload is still done at full resolution.
variable
float quadSigma
What Gaussian blur should be applied to the segmented image. Parameter is the standard deviation in pixels. Very noisy images benefit from non-zero values (e.g. 0.8).
variable
bool refineEdges
When non-zero, the edges of the each quad are adjusted to "snap
to" strong gradients nearby. This is useful when decimation is employed, as it can increase the quality of the initial quad estimate substantially. Generally recommended to be on. Very computationally inexpensive. Option is ignored if quadDecimate = 1.
variable
float decodeSharpening
How much sharpening should be done to decoded images? This can help decode small tags but may or may not help in odd lighting conditions or low light conditions. The default value is 0.25.
variable
std::int32_t maxHammingDistance
Max number of error bits that should be corrected. Accepting large numbers of corrected errors leads to greatly increased false positive rates. As of this implementation, the detector cannot detect tags with a hamming distance greater than 2.
variable
QuadThresholds quadThresholds
AprilTag quad threshold parameters.
function
AprilTagConfig()
function
~AprilTagConfig()
inline function
void serialize(std::vector< std::uint8_t > & metadata, DatatypeEnum & datatype)
function
AprilTagConfig & setFamily(Family family)
Parameters
- family: AprilTag family
function
DEPTHAI_SERIALIZE(AprilTagConfig, Buffer::sequenceNum, Buffer::ts, Buffer::tsDevice, family, quadDecimate, quadSigma, refineEdges, decodeSharpening, maxHammingDistance, quadThresholds)
struct
dai::AprilTagConfig::QuadThresholds
variable
std::int32_t minClusterPixels
Reject quads containing too few pixels.
variable
std::int32_t maxNmaxima
How many corner candidates to consider when segmenting a group of pixels into a quad.
variable
float criticalDegree
Reject quads where pairs of edges have angles that are close to straight or close to 180 degrees. Zero means that no quads are rejected. (In degrees).
variable
float maxLineFitMse
When fitting lines to the contours, what is the maximum mean squared error allowed? This is useful in rejecting contours that are far from being quad shaped; rejecting these quads "early" saves expensive decoding processing.
variable
std::int32_t minWhiteBlackDiff
When we build our model of black & white pixels, we add an extra check that the white model must be (overall) brighter than the black model. How much brighter? (in pixel values: [0,255]).
variable
bool deglitch
Should the thresholded image be deglitched? Only useful for very noisy images
function
DEPTHAI_SERIALIZE(QuadThresholds, minClusterPixels, maxNmaxima, criticalDegree, maxLineFitMse, minWhiteBlackDiff, deglitch)
enum
std::int32_t Family
enumerator
TAG_36H11
enumerator
TAG_36H10
enumerator
TAG_25H9
enumerator
TAG_16H5
enumerator
TAG_CIR21H7
enumerator
TAG_STAND41H12
Need assistance?
Head over to Discussion Forum for technical support or any other questions you might have.