WPILibC++ 2024.3.2
frc::AprilTagDetector::Config Struct Reference

Detector configuration. More...

#include <frc/apriltag/AprilTagDetector.h>

Public Member Functions

bool operator== (const Config &) const =default
 

Public Attributes

int numThreads = 1
 How many threads should be used for computation. More...
 
float quadDecimate = 2.0f
 Quad decimation. More...
 
float quadSigma = 0.0f
 What Gaussian blur should be applied to the segmented image (used for quad detection). More...
 
bool refineEdges = true
 When true, the edges of the each quad are adjusted to "snap to" strong gradients nearby. More...
 
double decodeSharpening = 0.25
 How much sharpening should be done to decoded images. More...
 
bool debug = false
 Debug mode. More...
 

Detailed Description

Detector configuration.

Member Function Documentation

◆ operator==()

bool frc::AprilTagDetector::Config::operator== ( const Config ) const
default

Member Data Documentation

◆ debug

bool frc::AprilTagDetector::Config::debug = false

Debug mode.

When true, the decoder writes a variety of debugging images to the current working directory at various stages through the detection process. This is slow and should not be used on space-limited systems such as the RoboRIO. Default is disabled (false).

◆ decodeSharpening

double frc::AprilTagDetector::Config::decodeSharpening = 0.25

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. Default is 0.25.

◆ numThreads

int frc::AprilTagDetector::Config::numThreads = 1

How many threads should be used for computation.

Default is single-threaded operation (1 thread).

◆ quadDecimate

float frc::AprilTagDetector::Config::quadDecimate = 2.0f

Quad decimation.

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. Default is 2.0.

◆ quadSigma

float frc::AprilTagDetector::Config::quadSigma = 0.0f

What Gaussian blur should be applied to the segmented image (used for quad detection).

Very noisy images benefit from non-zero values (e.g. 0.8). Default is 0.0.

◆ refineEdges

bool frc::AprilTagDetector::Config::refineEdges = true

When true, 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 (true). Default is true.

Very computationally inexpensive. Option is ignored if quad_decimate = 1.


The documentation for this struct was generated from the following file: