9#include <unordered_map>
47 kBlueAllianceWallRightSide,
49 kRedAllianceWallRightSide,
77 units::meter_t fieldLength, units::meter_t fieldWidth);
146 std::unordered_map<int, AprilTag> m_apriltags;
147 units::meter_t m_fieldLength;
148 units::meter_t m_fieldWidth;
171[[deprecated(
"Use AprilTagFieldLayout::LoadField() instead")]]
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
namespace for Niels Lohmann
Definition json.h:99
Class for representing a layout of AprilTags on a field and reading them from a JSON format.
Definition AprilTagFieldLayout.h:40
friend WPILIB_DLLEXPORT void to_json(wpi::json &json, const AprilTagFieldLayout &layout)
AprilTagFieldLayout(std::vector< AprilTag > apriltags, units::meter_t fieldLength, units::meter_t fieldWidth)
Construct a new AprilTagFieldLayout from a vector of AprilTag objects.
bool operator==(const AprilTagFieldLayout &) const =default
units::meter_t GetFieldLength() const
Returns the length of the field the layout is representing.
OriginPosition
Common origin positions for the AprilTag coordinate system.
Definition AprilTagFieldLayout.h:45
static AprilTagFieldLayout LoadField(AprilTagField field)
Loads an AprilTagFieldLayout from a predefined field.
std::optional< Pose3d > GetTagPose(int ID) const
Gets an AprilTag pose by its ID.
void Serialize(std::string_view path)
Serializes an AprilTagFieldLayout to a JSON file.
units::meter_t GetFieldWidth() const
Returns the length of the field the layout is representing.
std::vector< AprilTag > GetTags() const
Returns a vector of all the april tags used in this layout.
friend WPILIB_DLLEXPORT void from_json(const wpi::json &json, AprilTagFieldLayout &layout)
Pose3d GetOrigin() const
Returns the origin used for tag pose transformation.
AprilTagFieldLayout(std::string_view path)
Construct a new AprilTagFieldLayout with values imported from a JSON file.
void SetOrigin(const Pose3d &origin)
Sets the origin for tag pose transformation.
AprilTagFieldLayout()=default
void SetOrigin(OriginPosition origin)
Sets the origin based on a predefined enumeration of coordinate frame origins.
Represents a 3D pose containing translational and rotational elements.
Definition Pose3d.h:28
WPILIB_DLLEXPORT void to_json(wpi::json &json, const Rotation3d &rotation)
AprilTagField
Loadable AprilTag field layouts.
Definition AprilTagFields.h:16
WPILIB_DLLEXPORT void from_json(const wpi::json &json, Rotation3d &rotation)
WPILIB_DLLEXPORT AprilTagFieldLayout LoadAprilTagLayoutField(AprilTagField field)
Loads an AprilTagFieldLayout from a predefined field.