WPILibC++ 2024.1.1-beta-4
frc::AprilTagFieldLayout Class Reference

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

#include <frc/apriltag/AprilTagFieldLayout.h>

Public Types

enum class  OriginPosition { kBlueAllianceWallRightSide , kRedAllianceWallRightSide }
 

Public Member Functions

 AprilTagFieldLayout ()=default
 
 AprilTagFieldLayout (std::string_view path)
 Construct a new AprilTagFieldLayout with values imported from a JSON file. More...
 
 AprilTagFieldLayout (std::vector< AprilTag > apriltags, units::meter_t fieldLength, units::meter_t fieldWidth)
 Construct a new AprilTagFieldLayout from a vector of AprilTag objects. More...
 
units::meter_t GetFieldLength () const
 Returns the length of the field the layout is representing. More...
 
units::meter_t GetFieldWidth () const
 Returns the length of the field the layout is representing. More...
 
std::vector< AprilTagGetTags () const
 Returns a vector of all the april tags used in this layout. More...
 
void SetOrigin (OriginPosition origin)
 Sets the origin based on a predefined enumeration of coordinate frame origins. More...
 
void SetOrigin (const Pose3d &origin)
 Sets the origin for tag pose transformation. More...
 
Pose3d GetOrigin () const
 Returns the origin used for tag pose transformation. More...
 
std::optional< Pose3dGetTagPose (int ID) const
 Gets an AprilTag pose by its ID. More...
 
void Serialize (std::string_view path)
 Serializes an AprilTagFieldLayout to a JSON file. More...
 
bool operator== (const AprilTagFieldLayout &) const =default
 

Friends

WPILIB_DLLEXPORT void to_json (wpi::json &json, const AprilTagFieldLayout &layout)
 
WPILIB_DLLEXPORT void from_json (const wpi::json &json, AprilTagFieldLayout &layout)
 

Detailed Description

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).

Member Enumeration Documentation

◆ OriginPosition

Enumerator
kBlueAllianceWallRightSide 
kRedAllianceWallRightSide 

Constructor & Destructor Documentation

◆ AprilTagFieldLayout() [1/3]

frc::AprilTagFieldLayout::AprilTagFieldLayout ( )
default

◆ AprilTagFieldLayout() [2/3]

frc::AprilTagFieldLayout::AprilTagFieldLayout ( std::string_view  path)
explicit

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

Parameters
pathPath of the JSON file to import from.

◆ AprilTagFieldLayout() [3/3]

frc::AprilTagFieldLayout::AprilTagFieldLayout ( std::vector< AprilTag apriltags,
units::meter_t  fieldLength,
units::meter_t  fieldWidth 
)

Construct a new AprilTagFieldLayout from a vector of AprilTag objects.

Parameters
apriltagsVector of AprilTags.
fieldLengthLength of field the layout is representing.
fieldWidthWidth of field the layout is representing.

Member Function Documentation

◆ GetFieldLength()

units::meter_t frc::AprilTagFieldLayout::GetFieldLength ( ) const

Returns the length of the field the layout is representing.

Returns
length

◆ GetFieldWidth()

units::meter_t frc::AprilTagFieldLayout::GetFieldWidth ( ) const

Returns the length of the field the layout is representing.

Returns
width

◆ GetOrigin()

Pose3d frc::AprilTagFieldLayout::GetOrigin ( ) const

Returns the origin used for tag pose transformation.

Returns
the origin

◆ GetTagPose()

std::optional< Pose3d > frc::AprilTagFieldLayout::GetTagPose ( int  ID) const

Gets an AprilTag pose by its ID.

Parameters
IDThe 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.

◆ GetTags()

std::vector< AprilTag > frc::AprilTagFieldLayout::GetTags ( ) const

Returns a vector of all the april tags used in this layout.

Returns
list of tags

◆ operator==()

bool frc::AprilTagFieldLayout::operator== ( const AprilTagFieldLayout ) const
default

◆ Serialize()

void frc::AprilTagFieldLayout::Serialize ( std::string_view  path)

Serializes an AprilTagFieldLayout to a JSON file.

Parameters
pathThe path to write the JSON file to.

◆ SetOrigin() [1/2]

void frc::AprilTagFieldLayout::SetOrigin ( const Pose3d origin)

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
originThe new origin for tag transformations

◆ SetOrigin() [2/2]

void frc::AprilTagFieldLayout::SetOrigin ( OriginPosition  origin)

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
originThe predefined origin

Friends And Related Function Documentation

◆ from_json

WPILIB_DLLEXPORT void from_json ( const wpi::json &  json,
AprilTagFieldLayout layout 
)
friend

◆ to_json

WPILIB_DLLEXPORT void to_json ( wpi::json &  json,
const AprilTagFieldLayout layout 
)
friend

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