Skip to content

Commit df05096

Browse files
Added static classes to check for alliance side.
1 parent f3d86c8 commit df05096

4 files changed

Lines changed: 30 additions & 34 deletions

File tree

src/main/java/frc/robot/subsystems/auto/AutoAlgaeHeights.java

Lines changed: 3 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -3,12 +3,11 @@
33
import edu.wpi.first.apriltag.AprilTagFieldLayout;
44
import edu.wpi.first.apriltag.AprilTagFields;
55
import edu.wpi.first.math.geometry.Pose2d;
6-
import edu.wpi.first.wpilibj.DriverStation;
7-
import edu.wpi.first.wpilibj.DriverStation.Alliance;
86
import edu.wpi.first.wpilibj2.command.Command;
97
import frc.robot.Controls;
108
import frc.robot.subsystems.SuperStructure;
119
import frc.robot.subsystems.drivebase.CommandSwerveDrivetrain;
10+
import frc.robot.util.AllianceUtils;
1211
import frc.robot.util.ScoringMode;
1312
import java.util.List;
1413

@@ -54,20 +53,14 @@ public static Command autoAlgaeIntakeCommand(
5453
return new AutoAlgaeHeights(drivebase, s, c);
5554
}
5655

57-
private static boolean isBlue() {
58-
return DriverStation.getAlliance()
59-
.map(alliance -> alliance.equals(Alliance.Blue))
60-
.orElse(false);
61-
}
62-
6356
private static Pose2d getNearestAlgae(Pose2d robotPose) {
64-
List<Pose2d> poses = isBlue() ? blueAlgaePoses : redAlgaePoses;
57+
List<Pose2d> poses = AllianceUtils.isBlue() ? blueAlgaePoses : redAlgaePoses;
6558
return robotPose.nearest(poses);
6659
}
6760

6861
private String aprilTagToAlgaeHeight(Pose2d algaePose) {
6962
// Map poses to two heights only
70-
List<Pose2d> poses = isBlue() ? blueAlgaePoses : redAlgaePoses;
63+
List<Pose2d> poses = AllianceUtils.isBlue() ? blueAlgaePoses : redAlgaePoses;
7164
int index = poses.indexOf(algaePose);
7265

7366
if (index >= 3) {

src/main/java/frc/robot/subsystems/auto/AutoAlign.java

Lines changed: 6 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -12,10 +12,10 @@
1212
import edu.wpi.first.math.geometry.Transform2d;
1313
import edu.wpi.first.math.util.Units;
1414
import edu.wpi.first.wpilibj.DriverStation;
15-
import edu.wpi.first.wpilibj.DriverStation.Alliance;
1615
import edu.wpi.first.wpilibj2.command.Command;
1716
import frc.robot.Controls;
1817
import frc.robot.subsystems.drivebase.CommandSwerveDrivetrain;
18+
import frc.robot.util.AllianceUtils;
1919
import java.util.List;
2020

2121
public class AutoAlign {
@@ -32,17 +32,6 @@ public static Command autoAlign(
3232
return new AutoAlignCommand(drivebaseSubsystem, controls, type).withName("Auto Align");
3333
}
3434

35-
public static Boolean isBlue() {
36-
boolean isBlue;
37-
38-
if (!DriverStation.getAlliance().isEmpty()) {
39-
isBlue = DriverStation.getAlliance().get().equals(Alliance.Blue);
40-
} else {
41-
isBlue = false;
42-
}
43-
return isBlue;
44-
}
45-
4635
public static boolean readyToScore() {
4736
return isStationary() && isLevel() && isCloseEnough(AlignType.ALLB);
4837
}
@@ -277,7 +266,7 @@ public static Pose2d getTargetPose(Pose2d pose, AlignType type) {
277266

278267
private static Pose2d getNearestBranch(Pose2d p) {
279268
List<Pose2d> branchPose2ds =
280-
isBlue()
269+
AllianceUtils.isBlue()
281270
? List.of(
282271
blueBranchA,
283272
blueBranchB,
@@ -309,7 +298,7 @@ private static Pose2d getNearestBranch(Pose2d p) {
309298

310299
private static Pose2d getNearestLeftBranch(Pose2d p) {
311300
List<Pose2d> branchPose2ds =
312-
isBlue()
301+
AllianceUtils.isBlue()
313302
? List.of(
314303
blueBranchA, blueBranchC, blueBranchE, blueBranchG, blueBranchI, blueBranchK)
315304
: List.of(redBranchA, redBranchC, redBranchE, redBranchG, redBranchI, redBranchK);
@@ -318,7 +307,7 @@ private static Pose2d getNearestLeftBranch(Pose2d p) {
318307

319308
private static Pose2d getNearestRightBranch(Pose2d p) {
320309
List<Pose2d> branchPose2ds =
321-
isBlue()
310+
AllianceUtils.isBlue()
322311
? List.of(
323312
blueBranchB, blueBranchD, blueBranchF, blueBranchH, blueBranchJ, blueBranchL)
324313
: List.of(redBranchB, redBranchD, redBranchF, redBranchH, redBranchJ, redBranchL);
@@ -327,7 +316,7 @@ private static Pose2d getNearestRightBranch(Pose2d p) {
327316

328317
private static Pose2d getNearestL1L(Pose2d p) {
329318
List<Pose2d> reefFacesPose2ds =
330-
isBlue()
319+
AllianceUtils.isBlue()
331320
? List.of(
332321
lBlueReefFaceAB,
333322
lBlueReefFaceCD,
@@ -347,7 +336,7 @@ private static Pose2d getNearestL1L(Pose2d p) {
347336

348337
private static Pose2d getNearestL1R(Pose2d p) {
349338
List<Pose2d> reefFacesPose2ds =
350-
isBlue()
339+
AllianceUtils.isBlue()
351340
? List.of(
352341
rBlueReefFaceAB,
353342
rBlueReefFaceCD,

src/main/java/frc/robot/subsystems/auto/AutoBuilderConfig.java

Lines changed: 2 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -5,10 +5,10 @@
55
import com.pathplanner.lib.config.PIDConstants;
66
import com.pathplanner.lib.config.RobotConfig;
77
import com.pathplanner.lib.controllers.PPHolonomicDriveController;
8-
import edu.wpi.first.wpilibj.DriverStation;
98
import frc.robot.Robot;
109
import frc.robot.Subsystems;
1110
import frc.robot.subsystems.drivebase.CommandSwerveDrivetrain;
11+
import frc.robot.util.AllianceUtils;
1212
import java.io.IOException;
1313
import org.json.simple.parser.ParseException;
1414

@@ -42,12 +42,7 @@ public static void buildAuto(CommandSwerveDrivetrain drivebase) {
4242
// Boolean supplier that controls when the path will be mirrored for the red alliance
4343
// This will flip the path being followed to the red side of the field.
4444
// THE ORIGIN WILL REMAIN ON THE BLUE SIDE
45-
46-
var alliance = DriverStation.getAlliance();
47-
if (alliance.isPresent()) {
48-
return !AutoAlign.isBlue(); // Checking alliance is red
49-
}
50-
return false;
45+
return AllianceUtils.isRed(); // Checking alliance is red
5146
},
5247
s.drivebaseSubsystem // Reference to this subsystem to set requirements
5348
);
Lines changed: 19 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,19 @@
1+
package frc.robot.util;
2+
3+
import edu.wpi.first.wpilibj.DriverStation;
4+
5+
public final class AllianceUtils {
6+
public static boolean isBlue() {
7+
if (!DriverStation.getAlliance().isEmpty()) {
8+
return DriverStation.getAlliance().get().equals(DriverStation.Alliance.Blue);
9+
}
10+
return false;
11+
}
12+
13+
public static boolean isRed() {
14+
if (!DriverStation.getAlliance().isEmpty()) {
15+
return DriverStation.getAlliance().get().equals(DriverStation.Alliance.Red);
16+
}
17+
return false;
18+
}
19+
}

0 commit comments

Comments
 (0)