AprilTagDetector

class robotpy_apriltag.AprilTagDetector

Bases: pybind11_object

An AprilTag detector engine. This is expensive to set up and tear down, so most use cases should only create one of these, add a family to it, set up any other configuration, and repeatedly call Detect().

class Config

Bases: pybind11_object

Detector configuration.

class QuadThresholdParameters

Bases: pybind11_object

Quad threshold parameters.

addFamily(fam: str, bitsCorrected: SupportsInt | SupportsIndex = 2) bool

Adds a family of tags to be detected.

Parameters:
  • fam – Family name, e.g. “tag16h5”

  • bitsCorrected – Maximum number of bits to correct

Returns:

False if family can’t be found

clearFamilies() None

Unregister all families.

close() None

Frees all resources associated with this detector

detect(image: collections.abc.Buffer) list[robotpy_apriltag._apriltag.AprilTagDetection]

Detect tags from an 8-bit grayscale image with shape (height, width)

Returns:

list of results

getConfig() robotpy_apriltag._apriltag.AprilTagDetector.Config

Gets detector configuration.

Returns:

Configuration

getQuadThresholdParameters() robotpy_apriltag._apriltag.AprilTagDetector.QuadThresholdParameters

Gets quad threshold parameters.

Returns:

Parameters

removeFamily(fam: str) None

Removes a family of tags from the detector.

Parameters:

fam – Family name, e.g. “tag16h5”

setConfig(config: robotpy_apriltag._apriltag.AprilTagDetector.Config) None

Sets detector configuration.

Parameters:

config – Configuration

setQuadThresholdParameters(params: robotpy_apriltag._apriltag.AprilTagDetector.QuadThresholdParameters) None

Sets quad threshold parameters.

Parameters:

params – Parameters