Package choreo.util

Class ChoreoAllianceFlipUtil.Flipper

java.lang.Object
choreo.util.ChoreoAllianceFlipUtil.Flipper
Enclosing class:
ChoreoAllianceFlipUtil

public abstract static class ChoreoAllianceFlipUtil.Flipper extends Object
The flipper to use for flipping coordinates.
  • Field Details

  • Constructor Details

    • Flipper

      protected Flipper()
      Constructs a flipper.
    • Flipper

      public Flipper(double fieldLength, double fieldWidth)
      Constructs a flipper with the given field dimensions.
      Parameters:
      fieldLength - The length of the field.
      fieldWidth - The width of the field.
  • Method Details

    • mirroredX

      public static choreo.util.ChoreoAllianceFlipUtil.Flipper.MirroredX mirroredX(double fieldLength, double fieldWidth)
      Creates a new flipper that mirrors across x=fieldLength/2. This is intended for alliance-based flipping in rotationally asymmetric games.
      Parameters:
      fieldLength - The length of the field.
      fieldWidth - The width of the field.
      Returns:
      a new flipper.
    • mirroredY

      public static choreo.util.ChoreoAllianceFlipUtil.Flipper.MirroredY mirroredY(double fieldLength, double fieldWidth)
      Creates a new flipper that mirrors across y=fieldWidth/2. This keeps the positions on the same alliance half, but can be used to mirror left and right sides of the field, from driver perspective.
      Parameters:
      fieldLength - The length of the field.
      fieldWidth - The width of the field.
      Returns:
      a new flipper.
    • rotatedAround

      public static choreo.util.ChoreoAllianceFlipUtil.Flipper.RotatedAround rotatedAround(double fieldLength, double fieldWidth)
      Creates a new rotated flipper around the center of the field. This is intended for alliance-based flipping in rotationally symmetric games.
      Parameters:
      fieldLength - The length of the field.
      fieldWidth - The width of the field.
      Returns:
      A new rotated flipper around the center of the field.
    • getFieldLength

      public double getFieldLength()
      Gets the length (X axis) of the field.
      Returns:
      the length (X axis) of the field.
    • getFieldWidth

      public double getFieldWidth()
      Gets the width (Y axis) of the field.
      Returns:
      the width (Y axis) of the field.
    • flipX

      public abstract double flipX(double x)
      Flips the X coordinate.
      Parameters:
      x - The X coordinate to flip.
      Returns:
      The flipped X coordinate.
    • flipY

      public abstract double flipY(double y)
      Flips the Y coordinate.
      Parameters:
      y - The Y coordinate to flip.
      Returns:
      The flipped Y coordinate.
    • flipHeading

      public abstract double flipHeading(double heading)
      Flips the heading.
      Parameters:
      heading - The heading to flip.
      Returns:
      The flipped heading.
    • flip

      public abstract Rotation2d flip(Rotation2d rotation)
      Flips a Rotation2d.
      Parameters:
      rotation - the Rotation2d to flip.
      Returns:
      The flipped Rotation2d.
    • flip

      public abstract SwerveSample flip(SwerveSample sample)
      Flips a SwerveSample.
      Parameters:
      sample - The SwerveSample to flip.
      Returns:
      The flipped SwerveSample.
    • flip

      public abstract DifferentialSample flip(DifferentialSample sample)
      Flips a DifferentialSample.
      Parameters:
      sample - The DifferentialSample to flip.
      Returns:
      The flipped DifferentialSample.
    • flip

      public Translation2d flip(Translation2d translation)
      Flips a Translation2d.
      Parameters:
      translation - the Translation2d to flip.
      Returns:
      The flipped Translation2d.
    • flip

      public Pose2d flip(Pose2d pose)
      Flips the pose.
      Parameters:
      pose - The pose to flip.
      Returns:
      The flipped pose.
    • flip

      public Translation3d flip(Translation3d translation)
      Flips the translation.
      Parameters:
      translation - The translation to flip.
      Returns:
      The flipped translation.
    • flip

      public Rotation3d flip(Rotation3d rotation)
      Flips the rotation.
      Parameters:
      rotation - The rotation to flip.
      Returns:
      The flipped rotation.
    • flip

      public Pose3d flip(Pose3d pose)
      Flips the pose.
      Parameters:
      pose - The pose to flip.
      Returns:
      The flipped pose.