001// Copyright (c) Choreo contributors 002 003package choreo.util; 004 005import static choreo.util.FieldDimensions.FIELD_LENGTH; 006import static choreo.util.FieldDimensions.FIELD_WIDTH; 007 008import edu.wpi.first.math.geometry.Pose2d; 009import edu.wpi.first.math.geometry.Pose3d; 010import edu.wpi.first.math.geometry.Rotation2d; 011import edu.wpi.first.math.geometry.Rotation3d; 012import edu.wpi.first.math.geometry.Translation2d; 013import edu.wpi.first.math.geometry.Translation3d; 014import edu.wpi.first.wpilibj.DriverStation; 015import edu.wpi.first.wpilibj.DriverStation.Alliance; 016import java.util.HashMap; 017import java.util.Optional; 018import java.util.function.Supplier; 019 020/** 021 * A utility to standardize flipping of coordinate data based on the current alliance across 022 * different years. 023 * 024 * <p>If every vendor used this, the user would be able to specify the year and no matter the year 025 * the vendor's code is from, the user would be able to flip as expected. 026 * 027 * <p>This API still allows vendors and users to match case against the flipping variant as a way to 028 * specially handle cases or throw errors if a variant is explicitly not supported. 029 */ 030public class ChoreoAllianceFlipUtil { 031 /** The flipper to use for flipping coordinates. */ 032 public static enum Flipper { 033 /** 034 * X becomes fieldLength - x, leaves the y coordinate unchanged, and heading becomes PI - 035 * heading. 036 */ 037 MIRRORED { 038 public double flipX(double x) { 039 return activeYear.fieldLength - x; 040 } 041 042 public double flipY(double y) { 043 return y; 044 } 045 046 public double flipHeading(double heading) { 047 return Math.PI - heading; 048 } 049 }, 050 /** X becomes fieldLength - x, Y becomes fieldWidth - y, and heading becomes PI - heading. */ 051 ROTATE_AROUND { 052 public double flipX(double x) { 053 return activeYear.fieldLength - x; 054 } 055 056 public double flipY(double y) { 057 return activeYear.fieldWidth - y; 058 } 059 060 public double flipHeading(double heading) { 061 return Math.PI + heading; 062 } 063 }; 064 065 /** 066 * Flips the X coordinate. 067 * 068 * @param x The X coordinate to flip. 069 * @return The flipped X coordinate. 070 */ 071 public abstract double flipX(double x); 072 073 /** 074 * Flips the Y coordinate. 075 * 076 * @param y The Y coordinate to flip. 077 * @return The flipped Y coordinate. 078 */ 079 public abstract double flipY(double y); 080 081 /** 082 * Flips the heading. 083 * 084 * @param heading The heading to flip. 085 * @return The flipped heading. 086 */ 087 public abstract double flipHeading(double heading); 088 } 089 090 private static record YearInfo(Flipper flipper, double fieldLength, double fieldWidth) {} 091 092 // TODO: Update and expand this map 093 private static final HashMap<Integer, YearInfo> flipperMap = 094 new HashMap<Integer, YearInfo>() { 095 { 096 put(2020, new YearInfo(Flipper.ROTATE_AROUND, 16.5811, 8.19912)); 097 put(2021, new YearInfo(Flipper.ROTATE_AROUND, 16.5811, 8.19912)); 098 put(2022, new YearInfo(Flipper.ROTATE_AROUND, 16.5811, 8.19912)); 099 put(2023, new YearInfo(Flipper.MIRRORED, 16.5811, 8.19912)); 100 put(2024, new YearInfo(Flipper.MIRRORED, 16.5811, 8.19912)); 101 put(2025, new YearInfo(Flipper.ROTATE_AROUND, FIELD_LENGTH, FIELD_WIDTH)); 102 } 103 }; 104 105 private static YearInfo activeYear = flipperMap.get(2025); 106 107 /** Default constructor. */ 108 private ChoreoAllianceFlipUtil() {} 109 110 /** 111 * Get the flipper that is currently active for flipping coordinates. It's recommended not to 112 * store this locally as the flipper may change. 113 * 114 * @return The active flipper. 115 */ 116 public static Flipper getFlipper() { 117 return activeYear.flipper; 118 } 119 120 /** 121 * Returns if you are on red alliance. 122 * 123 * @return If you are on red alliance. 124 */ 125 public static boolean shouldFlip() { 126 return DriverStation.getAlliance().orElse(Alliance.Blue) == Alliance.Red; 127 } 128 129 /** 130 * Set the year to determine the Alliance Coordinate Flipper to use. 131 * 132 * @param year The year to set the flipper to. [2020 - 2024] 133 */ 134 public static void setYear(int year) { 135 if (!flipperMap.containsKey(year)) { 136 throw new IllegalArgumentException("Year " + year + " is not supported."); 137 } 138 activeYear = flipperMap.get(year); 139 } 140 141 /** 142 * Flips the X coordinate. 143 * 144 * @param x The X coordinate to flip. 145 * @return The flipped X coordinate. 146 */ 147 public static double flipX(double x) { 148 return activeYear.flipper.flipX(x); 149 } 150 151 /** 152 * Flips the Y coordinate. 153 * 154 * @param y The Y coordinate to flip. 155 * @return The flipped Y coordinate. 156 */ 157 public static double flipY(double y) { 158 return activeYear.flipper.flipY(y); 159 } 160 161 /** 162 * Flips the heading. 163 * 164 * @param heading The heading to flip. 165 * @return The flipped heading. 166 */ 167 public static double flipHeading(double heading) { 168 return activeYear.flipper.flipHeading(heading); 169 } 170 171 /** 172 * Flips the translation. 173 * 174 * @param translation The translation to flip. 175 * @return The flipped translation. 176 */ 177 public static Translation2d flip(Translation2d translation) { 178 return new Translation2d(flipX(translation.getX()), flipY(translation.getY())); 179 } 180 181 /** 182 * Flips the rotation. 183 * 184 * @param rotation The rotation to flip. 185 * @return The flipped rotation. 186 */ 187 public static Rotation2d flip(Rotation2d rotation) { 188 return switch (activeYear.flipper) { 189 case MIRRORED -> new Rotation2d(-rotation.getCos(), rotation.getSin()); 190 case ROTATE_AROUND -> new Rotation2d(-rotation.getCos(), -rotation.getSin()); 191 }; 192 } 193 194 /** 195 * Flips the pose. 196 * 197 * @param pose The pose to flip. 198 * @return The flipped pose. 199 */ 200 public static Pose2d flip(Pose2d pose) { 201 return new Pose2d(flip(pose.getTranslation()), flip(pose.getRotation())); 202 } 203 204 /** 205 * Flips the translation. 206 * 207 * @param translation The translation to flip. 208 * @return The flipped translation. 209 */ 210 public static Translation3d flip(Translation3d translation) { 211 return new Translation3d( 212 flipX(translation.getX()), flipY(translation.getY()), translation.getZ()); 213 } 214 215 /** 216 * Flips the rotation. 217 * 218 * @param rotation The rotation to flip. 219 * @return The flipped rotation. 220 */ 221 public static Rotation3d flip(Rotation3d rotation) { 222 return new Rotation3d( 223 rotation.getX(), rotation.getY(), flip(rotation.toRotation2d()).getRadians()); 224 } 225 226 /** 227 * Flips the pose. 228 * 229 * @param pose The pose to flip. 230 * @return The flipped pose. 231 */ 232 public static Pose3d flip(Pose3d pose) { 233 return new Pose3d(flip(pose.getTranslation()), flip(pose.getRotation())); 234 } 235 236 /** 237 * Creates a Supplier<Optional<Pose2d>> based on a 238 * Supplier<Optional<Alliance>> and original Optional<Pose2d> 239 * 240 * @param poseOpt The pose to flip 241 * @param allianceOpt The current alliance 242 * @param doFlip Returns true if flipping based on the alliance should be done 243 * @return empty if the alliance is empty; the original pose optional if the alliance is blue or 244 * doFlip is false; the flipped pose optional if the alliance is red and doFlip is true 245 */ 246 public static Supplier<Optional<Pose2d>> optionalFlippedPose2d( 247 Optional<Pose2d> poseOpt, Supplier<Optional<Alliance>> allianceOpt, boolean doFlip) { 248 return () -> 249 doFlip 250 ? allianceOpt 251 .get() 252 .flatMap(ally -> poseOpt.map(pose -> ally == Alliance.Red ? flip(pose) : pose)) 253 : poseOpt; 254 } 255 256 /** 257 * Creates a Supplier<Optional<Translation2d>> that is flipped based on a 258 * Supplier<Optional<Alliance>> and original Optional<Translation2d> 259 * 260 * @param translationOpt The translation to flip 261 * @param allianceOpt The current alliance 262 * @param doFlip Returns true if flipping based on the alliance should be done 263 * @return empty if the alliance is empty; the original translation optional if the alliance is 264 * blue or doFlip is false; the flipped translation optional if the alliance is red and doFlip 265 * is true 266 */ 267 public static Supplier<Optional<Translation2d>> optionalFlippedTranslation2d( 268 Optional<Translation2d> translationOpt, 269 Supplier<Optional<Alliance>> allianceOpt, 270 boolean doFlip) { 271 return () -> 272 doFlip 273 ? allianceOpt 274 .get() 275 .flatMap( 276 ally -> 277 translationOpt.map( 278 translation -> ally == Alliance.Red ? flip(translation) : translation)) 279 : translationOpt; 280 } 281}