AprilTagFieldLayout

class robotpy_apriltag.AprilTagFieldLayout(*args, **kwargs)

Bases: pybind11_object

Class for representing a layout of AprilTags on a field and reading them from a JSON format.

The JSON format contains two top-level objects, “tags” and “field”. The “tags” object is a list of all AprilTags contained within a layout. Each AprilTag serializes to a JSON object containing an ID and a Pose3d. The “field” object is a descriptor of the size of the field in meters with “width” and “length” values. This is to account for arbitrary field sizes when transforming the poses.

Pose3ds in the JSON are measured using the normal FRC coordinate system, NWU with the origin at the bottom-right corner of the blue alliance wall. SetOrigin(OriginPosition) can be used to change the poses returned from GetTagPose(int) to be from the perspective of a specific alliance.

Tag poses represent the center of the tag, with a zero rotation representing a tag that is upright and facing away from the (blue) alliance wall (that is, towards the opposing alliance).

Overloaded function.

  1. __init__(self: robotpy_apriltag._apriltag.AprilTagFieldLayout) -> None

  2. __init__(self: robotpy_apriltag._apriltag.AprilTagFieldLayout, path: str) -> None

Construct a new AprilTagFieldLayout with values imported from a JSON file.

Parameters:

path – Path of the JSON file to import from.

  1. __init__(self: robotpy_apriltag._apriltag.AprilTagFieldLayout, apriltags: List[robotpy_apriltag._apriltag.AprilTag], fieldLength: meters, fieldWidth: meters) -> None

Construct a new AprilTagFieldLayout from a vector of AprilTag objects.

Parameters:
  • apriltags – Vector of AprilTags.

  • fieldLength – Length of field the layout is representing.

  • fieldWidth – Width of field the layout is representing.

class OriginPosition(value: int)

Bases: pybind11_object

Members:

kBlueAllianceWallRightSide

kRedAllianceWallRightSide

kBlueAllianceWallRightSide = <OriginPosition.kBlueAllianceWallRightSide: 0>
kRedAllianceWallRightSide = <OriginPosition.kRedAllianceWallRightSide: 1>
property name
property value
getTagPose(ID: int) wpimath.geometry._geometry.Pose3d | None

Gets an AprilTag pose by its ID.

Parameters:

ID – The ID of the tag.

Returns:

The pose corresponding to the ID that was passed in or an empty optional if a tag with that ID is not found.

serialize(path: str) None

Serializes an AprilTagFieldLayout to a JSON file.

Parameters:

path – The path to write the JSON file to.

setOrigin(*args, **kwargs)

Overloaded function.

  1. setOrigin(self: robotpy_apriltag._apriltag.AprilTagFieldLayout, origin: robotpy_apriltag._apriltag.AprilTagFieldLayout.OriginPosition) -> None

Sets the origin based on a predefined enumeration of coordinate frame origins. The origins are calculated from the field dimensions.

This transforms the Pose3ds returned by GetTagPose(int) to return the correct pose relative to a predefined coordinate frame.

Parameters:

origin – The predefined origin

  1. setOrigin(self: robotpy_apriltag._apriltag.AprilTagFieldLayout, origin: wpimath.geometry._geometry.Pose3d) -> None

Sets the origin for tag pose transformation.

This transforms the Pose3ds returned by GetTagPose(int) to return the correct pose relative to the provided origin.

Parameters:

origin – The new origin for tag transformations