Class AprilTagFieldLayout
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).
-
Nested Class Summary
Nested ClassesModifier and TypeClassDescriptionstatic enumCommon origin positions for the AprilTag coordinate system. -
Constructor Summary
ConstructorsConstructorDescriptionAprilTagFieldLayout(String path) Construct a new AprilTagFieldLayout with values imported from a JSON file.AprilTagFieldLayout(Path path) Construct a new AprilTagFieldLayout with values imported from a JSON file.AprilTagFieldLayout(List<AprilTag> apriltags, double fieldLength, double fieldWidth) Construct a new AprilTagFieldLayout from a list ofAprilTagobjects. -
Method Summary
Modifier and TypeMethodDescriptionbooleandoubleReturns the length of the field the layout is representing in meters.doubleReturns the length of the field the layout is representing in meters.Returns the origin used for tag pose transformation.getTagPose(int ID) Gets an AprilTag pose by its ID.getTags()Returns a List of theAprilTagsused in this layout.inthashCode()static AprilTagFieldLayoutloadField(AprilTagFields field) Get an officialAprilTagFieldLayout.static AprilTagFieldLayoutloadFromResource(String resourcePath) Deserializes a field layout from a resource within a internal jar file.voidSerializes a AprilTagFieldLayout to a JSON file.voidSerializes a AprilTagFieldLayout to a JSON file.final voidSets the origin based on a predefined enumeration of coordinate frame origins.final voidSets the origin for tag pose transformation.
-
Constructor Details
-
AprilTagFieldLayout
Construct a new AprilTagFieldLayout with values imported from a JSON file.- Parameters:
path- Path of the JSON file to import from.- Throws:
IOException- If reading from the file fails.
-
AprilTagFieldLayout
Construct a new AprilTagFieldLayout with values imported from a JSON file.- Parameters:
path- Path of the JSON file to import from.- Throws:
IOException- If reading from the file fails.
-
AprilTagFieldLayout
Construct a new AprilTagFieldLayout from a list ofAprilTagobjects.- Parameters:
apriltags- List ofAprilTag.fieldLength- Length of the field the layout is representing in meters.fieldWidth- Width of the field the layout is representing in meters.
-
-
Method Details
-
getTags
Returns a List of theAprilTagsused in this layout.- Returns:
- The
AprilTagsused in this layout.
-
getFieldLength
Returns the length of the field the layout is representing in meters.- Returns:
- length, in meters
-
getFieldWidth
Returns the length of the field the layout is representing in meters.- Returns:
- width, in meters
-
setOrigin
Sets the origin based on a predefined enumeration of coordinate frame origins. The origins are calculated from the field dimensions.This transforms the Pose3d objects returned by
getTagPose(int)to return the correct pose relative to a predefined coordinate frame.- Parameters:
origin- The predefined origin
-
setOrigin
Sets the origin for tag pose transformation.This transforms the Pose3d objects returned by
getTagPose(int)to return the correct pose relative to the provided origin.- Parameters:
origin- The new origin for tag transformations
-
getOrigin
Returns the origin used for tag pose transformation.- Returns:
- the origin
-
getTagPose
Gets an AprilTag pose by its ID.- Parameters:
ID- The ID of the tag.- Returns:
- The pose corresponding to the ID passed in or an empty optional if a tag with that ID was not found.
-
serialize
Serializes a AprilTagFieldLayout to a JSON file.- Parameters:
path- The path to write to.- Throws:
IOException- If writing to the file fails.
-
serialize
Serializes a AprilTagFieldLayout to a JSON file.- Parameters:
path- The path to write to.- Throws:
IOException- If writing to the file fails.
-
loadField
Get an officialAprilTagFieldLayout.- Parameters:
field- The loadable AprilTag field layout.- Returns:
- AprilTagFieldLayout of the field.
- Throws:
UncheckedIOException- If the layout does not exist.
-
loadFromResource
Deserializes a field layout from a resource within a internal jar file.Users should use
AprilTagFields.loadAprilTagLayoutField()to load official layouts andAprilTagFieldLayout(String)for custom layouts.- Parameters:
resourcePath- The absolute path of the resource- Returns:
- The deserialized layout
- Throws:
IOException- If the resource could not be loaded
-
equals
-
hashCode
-