Package frc.robot.lib.BLine
Class FlippingUtil
java.lang.Object
frc.robot.lib.BLine.FlippingUtil
-
Nested Class Summary
Nested ClassesModifier and TypeClassDescriptionstatic enumEnum representing the different types of field symmetry -
Field Summary
FieldsModifier and TypeFieldDescriptionstatic doubleThe X size or length of the current field in metersstatic doubleThe Y size or width of the current field in metersstatic FlippingUtil.FieldSymmetryThe type of symmetry for the current field -
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptionstatic double[]flipFeedforwards(double[] feedforwards) Flip an array of drive feedforwards for the other side of the field.static double[]flipFeedforwardXs(double[] feedforwardXs) Flip an array of drive feedforward X components for the other side of the field.static double[]flipFeedforwardYs(double[] feedforwardYs) Flip an array of drive feedforward Y components for the other side of the field.static edu.wpi.first.math.geometry.Pose2dflipFieldPose(edu.wpi.first.math.geometry.Pose2d pose) Flip a field pose to the other side of the field, maintaining a blue alliance originstatic edu.wpi.first.math.geometry.Translation2dflipFieldPosition(edu.wpi.first.math.geometry.Translation2d pos) Flip a field position to the other side of the field, maintaining a blue alliance originstatic edu.wpi.first.math.geometry.Rotation2dflipFieldRotation(edu.wpi.first.math.geometry.Rotation2d rotation) Flip a field rotation to the other side of the field, maintaining a blue alliance originstatic edu.wpi.first.math.kinematics.ChassisSpeedsflipFieldSpeeds(edu.wpi.first.math.kinematics.ChassisSpeeds fieldSpeeds) Flip field relative chassis speeds for the other side of the field, maintaining a blue alliance origin
-
Field Details
-
symmetryType
The type of symmetry for the current field -
fieldSizeX
public static double fieldSizeXThe X size or length of the current field in meters -
fieldSizeY
public static double fieldSizeYThe Y size or width of the current field in meters
-
-
Constructor Details
-
FlippingUtil
public FlippingUtil()
-
-
Method Details
-
flipFieldPosition
public static edu.wpi.first.math.geometry.Translation2d flipFieldPosition(edu.wpi.first.math.geometry.Translation2d pos) Flip a field position to the other side of the field, maintaining a blue alliance origin- Parameters:
pos- The position to flip- Returns:
- The flipped position
-
flipFieldRotation
public static edu.wpi.first.math.geometry.Rotation2d flipFieldRotation(edu.wpi.first.math.geometry.Rotation2d rotation) Flip a field rotation to the other side of the field, maintaining a blue alliance origin- Parameters:
rotation- The rotation to flip- Returns:
- The flipped rotation
-
flipFieldPose
public static edu.wpi.first.math.geometry.Pose2d flipFieldPose(edu.wpi.first.math.geometry.Pose2d pose) Flip a field pose to the other side of the field, maintaining a blue alliance origin- Parameters:
pose- The pose to flip- Returns:
- The flipped pose
-
flipFieldSpeeds
public static edu.wpi.first.math.kinematics.ChassisSpeeds flipFieldSpeeds(edu.wpi.first.math.kinematics.ChassisSpeeds fieldSpeeds) Flip field relative chassis speeds for the other side of the field, maintaining a blue alliance origin- Parameters:
fieldSpeeds- Field relative chassis speeds- Returns:
- Flipped speeds
-
flipFeedforwards
public static double[] flipFeedforwards(double[] feedforwards) Flip an array of drive feedforwards for the other side of the field. Only does anything if mirrored symmetry is used- Parameters:
feedforwards- Array of drive feedforwards- Returns:
- The flipped feedforwards
-
flipFeedforwardXs
public static double[] flipFeedforwardXs(double[] feedforwardXs) Flip an array of drive feedforward X components for the other side of the field. Only does anything if mirrored symmetry is used- Parameters:
feedforwardXs- Array of drive feedforward X components- Returns:
- The flipped feedforward X components
-
flipFeedforwardYs
public static double[] flipFeedforwardYs(double[] feedforwardYs) Flip an array of drive feedforward Y components for the other side of the field. Only does anything if mirrored symmetry is used- Parameters:
feedforwardYs- Array of drive feedforward Y components- Returns:
- The flipped feedforward Y components
-