RawAprilTags configuration structure. More...
#include <RawAprilTagConfig.hpp>
Classes | |
struct | QuadThresholds |
Public Types | |
enum | Family : std::int32_t { Family::TAG_36H11 = 0, Family::TAG_36H10, Family::TAG_25H9, Family::TAG_16H5, Family::TAG_CIR21H7, Family::TAG_STAND41H12 } |
Public Member Functions | |
DEPTHAI_SERIALIZE (RawAprilTagConfig, family, quadDecimate, quadSigma, refineEdges, decodeSharpening, maxHammingDistance, quadThresholds) | |
DatatypeEnum | getType () const override |
void | serialize (std::vector< std::uint8_t > &metadata, DatatypeEnum &datatype) const override |
![]() | |
DEPTHAI_SERIALIZE (RawBuffer, sequenceNum, ts, tsDevice) | |
virtual | ~RawBuffer ()=default |
Public Attributes | |
float | decodeSharpening = 0.25f |
Family | family = Family::TAG_36H11 |
std::int32_t | maxHammingDistance = 1 |
std::int32_t | quadDecimate = 4 |
float | quadSigma = 0.0f |
QuadThresholds | quadThresholds |
bool | refineEdges = true |
![]() | |
std::vector< std::uint8_t > | data |
int64_t | sequenceNum = 0 |
Timestamp | ts = {} |
Timestamp | tsDevice = {} |
RawAprilTags configuration structure.
Definition at line 13 of file RawAprilTagConfig.hpp.
|
strong |
Supported AprilTag families.
Enumerator | |
---|---|
TAG_36H11 | |
TAG_36H10 | |
TAG_25H9 | |
TAG_16H5 | |
TAG_CIR21H7 | |
TAG_STAND41H12 |
Definition at line 17 of file RawAprilTagConfig.hpp.
dai::RawAprilTagConfig::DEPTHAI_SERIALIZE | ( | RawAprilTagConfig | , |
family | , | ||
quadDecimate | , | ||
quadSigma | , | ||
refineEdges | , | ||
decodeSharpening | , | ||
maxHammingDistance | , | ||
quadThresholds | |||
) |
|
inlineoverridevirtual |
Reimplemented from dai::RawBuffer.
Definition at line 118 of file RawAprilTagConfig.hpp.
|
inlineoverridevirtual |
Reimplemented from dai::RawBuffer.
Definition at line 113 of file RawAprilTagConfig.hpp.
float dai::RawAprilTagConfig::decodeSharpening = 0.25f |
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.
Definition at line 54 of file RawAprilTagConfig.hpp.
Family dai::RawAprilTagConfig::family = Family::TAG_36H11 |
AprilTag family.
Definition at line 22 of file RawAprilTagConfig.hpp.
std::int32_t dai::RawAprilTagConfig::maxHammingDistance = 1 |
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.
Definition at line 62 of file RawAprilTagConfig.hpp.
std::int32_t dai::RawAprilTagConfig::quadDecimate = 4 |
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.
Definition at line 30 of file RawAprilTagConfig.hpp.
float dai::RawAprilTagConfig::quadSigma = 0.0f |
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).
Definition at line 37 of file RawAprilTagConfig.hpp.
QuadThresholds dai::RawAprilTagConfig::quadThresholds |
AprilTag quad threshold parameters.
Definition at line 111 of file RawAprilTagConfig.hpp.
bool dai::RawAprilTagConfig::refineEdges = true |
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.
Definition at line 46 of file RawAprilTagConfig.hpp.