Package xbot.common.subsystems.pose
Class GameField
java.lang.Object
xbot.common.subsystems.pose.GameField
Represents the field the robot is on and provides helpers for transforming field coordinates.
-
Nested Class Summary
Nested ClassesModifier and TypeClassDescriptionstatic enum
Represents the symmetry type of the field. -
Constructor Summary
ConstructorsConstructorDescriptionGameField
(AprilTagFieldLayout fieldLayout, GameField.Symmetry symmetry) Creates a new GameField. -
Method Summary
Modifier and TypeMethodDescriptionGets the center of the field.Gets the length of the field.Gets the width of the field.getMirroredPose
(Pose2d original) Gets the mirrored pose of a given pose per the field symmetry.getMirroredRotation
(Rotation2d original) Gets the mirrored rotation of a given rotation per the field symmetry.getMirroredTranslation
(Translation2d original) Gets the mirrored translation of a given translation per the field symmetry.Gets the symmetry of the field.
-
Constructor Details
-
GameField
Creates a new GameField.- Parameters:
fieldLayout
- The layout of the field.symmetry
- The symmetry of the field.
-
-
Method Details
-
getFieldWidth
Gets the width of the field.- Returns:
- The width of the field.
-
getFieldLength
Gets the length of the field.- Returns:
- The length of the field.
-
getSymmetry
Gets the symmetry of the field.- Returns:
- The symmetry of the field.
-
getFieldCenter
Gets the center of the field.- Returns:
- The center of the field. Distances are in meters.
-
getMirroredTranslation
Gets the mirrored translation of a given translation per the field symmetry.- Parameters:
original
- The original translation. Distances are in meters.- Returns:
- The mirrored translation. Distances are in meters.
-
getMirroredRotation
Gets the mirrored rotation of a given rotation per the field symmetry.- Parameters:
original
- The original rotation.- Returns:
- The mirrored rotation.
-
getMirroredPose
Gets the mirrored pose of a given pose per the field symmetry.- Parameters:
original
- The original pose. Distances are in meters.- Returns:
- The mirrored pose. Distances are in meters.
-