# AprilTagConfig

This message is used to configure the
[AprilTag](https://docs.luxonis.com/software-v3/depthai/depthai-components/nodes/april_tag.md) node. It allows selecting the
AprilTag family to detect, adjusting decoding thresholds, and fine-tuning quad detection parameters.

## Examples of functionality

 * [AprilTags from camera 12MP](https://docs.luxonis.com/software-v3/depthai/examples/april_tags/april_tags_12mp.md)
 * [AprilTags on image replay](https://docs.luxonis.com/software-v3/depthai/examples/april_tags/april_tags_replay.md)

## Reference

### dai::AprilTagConfig

Kind: class

AprilTagConfig message.

#### dai::AprilTagConfig::QuadThresholds

Kind: struct

AprilTag quad threshold parameters.

##### std::int32_t minClusterPixels

Kind: variable

Reject quads containing too few pixels.

##### std::int32_t maxNmaxima

Kind: variable

How many corner candidates to consider when segmenting a group of pixels into a quad.

##### float criticalDegree

Kind: variable

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).

##### float maxLineFitMse

Kind: variable

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.

##### std::int32_t minWhiteBlackDiff

Kind: variable

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]).

##### bool deglitch

Kind: variable

Should the thresholded image be deglitched? Only useful for very noisy images

##### DEPTHAI_SERIALIZE(QuadThresholds, minClusterPixels, maxNmaxima, criticalDegree, maxLineFitMse, minWhiteBlackDiff, deglitch)

Kind: function

#### std::int32_t Family

Kind: enum

Supported AprilTag families.

##### TAG_36H11

Kind: enum_value

##### TAG_36H10

Kind: enum_value

##### TAG_25H9

Kind: enum_value

##### TAG_16H5

Kind: enum_value

##### TAG_CIR21H7

Kind: enum_value

##### TAG_STAND41H12

Kind: enum_value

#### Family family

Kind: variable

AprilTag family.

#### std::int32_t quadDecimate

Kind: variable

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.

#### float quadSigma

Kind: variable

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).

#### bool refineEdges

Kind: variable

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.

#### float decodeSharpening

Kind: variable

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.

#### std::int32_t maxHammingDistance

Kind: variable

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.

#### QuadThresholds quadThresholds

Kind: variable

AprilTag quad threshold parameters.

#### AprilTagConfig()

Kind: function

#### ~AprilTagConfig()

Kind: function

#### void serialize(std::vector< std::uint8_t > & metadata, DatatypeEnum & datatype)

Kind: function

#### DatatypeEnum getDatatype()

Kind: function

Get the datatype of this specific message.

return: DatatypeEnum

#### AprilTagConfig & setFamily(Family family)

Kind: function

parameters: family: AprilTag family

#### DEPTHAI_SERIALIZE(AprilTagConfig, Buffer::sequenceNum, Buffer::ts, Buffer::tsDevice, family, quadDecimate, quadSigma,
refineEdges, decodeSharpening, maxHammingDistance, quadThresholds)

Kind: function

### Need assistance?

Head over to [Discussion Forum](https://discuss.luxonis.com/) for technical support or any other questions you might have.
