API Reference#

class pupil_apriltags.Detection#

Bases: object

Combined pythonic wrapper for apriltag_detection and apriltag_pose

Note: Attributes with an asterisks are computed only if estimate_tag_pose=True

center#

The center of the detection in image pixel coordinates.

corners#

The corners of the tag in image pixel coordinates. These always wrap counter- clock wise around the tag.

decision_margin#

A measure of the quality of the binary decoding process

The average difference between the intensity of a data bit versus the decision threshold. Higher numbers roughly indicate better decodes. This is a reasonable measure of detection accuracy only for very small tags–not effective for larger tags (where we could have sampled anywhere within a bit cell and still gotten a good detection.)

hamming: int#

How many error bits were corrected? Note: accepting large numbers of corrected errors leads to greatly increased false positive rates. Note: As of this implementation, the detector cannot detect tags with a Hamming distance greater than 2.

homography#

The 3x3 homography matrix describing the projection from an “ideal” tag (with corners at (-1,1), (1,1), (1,-1), and (-1, -1)) to pixels in the image.

pose_R#

* Rotation matrix of the pose estimate.

pose_err#

* Object-space error of the estimation.

pose_t#

* Translation of the pose estimate.

tag_family: str#

The family of the tag.

tag_id: int#

The decoded ID of the tag.

class pupil_apriltags.Detector(families: str = 'tag36h11', nthreads: int = 1, quad_decimate: float = 2.0, quad_sigma: float = 0.0, refine_edges: int = 1, decode_sharpening: float = 0.25, debug: int = 0, searchpath: Tuple[Path, ...] = (PosixPath('/home/docs/checkouts/readthedocs.org/user_builds/pupil-apriltags/envs/stable/lib/python3.7/site-packages/pupil_apriltags/lib'), PosixPath('/home/docs/checkouts/readthedocs.org/user_builds/pupil-apriltags/envs/stable/lib/python3.7/site-packages/pupil_apriltags/lib64')))#

Bases: object

Pythonic wrapper for apriltag_detector.

Parameters:
  • families – Tag families, separated with a space, default: tag36h11

  • nthreads – Number of threads, default: 1

  • quad_decimate – 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: 2.0

  • quad_sigma – What Gaussian blur should be applied to the segmented image (used for quad detection?) Parameter is the standard deviation in pixels. Very noisy images benefit from non-zero values (e.g. 0.8), default: 0.0

  • refine_edges – 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 (1). Very computationally inexpensive. Option is ignored if quad_decimate = 1, default: 1

  • decode_sharpening – 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 = 0.25

  • debug – If 1, will save debug images. Runs very slow, default: 0

  • searchpath – Where to look for the Apriltag 3 library, must be a list, default: [“src/lib”, “src/lib64”]

detect(img: ndarray[Any, dtype[uint8]], estimate_tag_pose: bool = False, camera_params: Optional[Tuple[float, float, float, float]] = None, tag_size: Optional[float] = None) Detection#

Run detectons on the provided image.

The image must be a grayscale image of type numpy.uint8.

If you also want to extract the tag pose, estimate_tag_pose should be set to True and camera_params ([fx, fy, cx, cy]) and tag_size (in meters) should be supplied.