diff --git a/.github/workflows/format.yml b/.github/workflows/format.yml index c563087..a1d025e 100644 --- a/.github/workflows/format.yml +++ b/.github/workflows/format.yml @@ -14,12 +14,13 @@ jobs: steps: # Checks-out your repository under $GITHUB_WORKSPACE, so your job can access it - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: ref: ${{ github.event.pull_request.head.ref }} - - uses: actions/setup-java@v2 - with: - java-version: 17 + - uses: actions/setup-java@v4 + with: + java-version: '17' + distribution: 'oracle' - uses: axel-op/googlejavaformat-action@v3 with: args: "--skip-sorting-imports --replace" diff --git a/README.md b/README.md index c3afaab..6aeca4c 100644 --- a/README.md +++ b/README.md @@ -9,4 +9,4 @@ Thank you to the following who has contributed, supplied the tools to make this - [CTR Electronics](https://github.com/CrossTheRoadElec) - Provided an example and starter [repository](https://github.com/CrossTheRoadElec/Phoenix6-Examples/tree/main/java/SwerveWithPathPlanner) to build from - [Ian Tapply](https://github.com/IanTapply22) - Main student contributor - [Kaleb Dodd](https://github.com/kaleb-dodd) - Project coordinator -- [Cole MacPhail](https://github.com/colemacphail) - Project coordinator \ No newline at end of file +- [Cole MacPhail](https://github.com/colemacphail) - Project coordinator diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 556d128..6bf31d9 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -11,6 +11,7 @@ import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.InstantCommand; import frc.robot.generated.TunerConstants; +import frc.robot.subsystems.led.LEDSubsystem; public class RobotContainer { final double MaxSpeed = 6; // 6 meters per second desired top speed @@ -20,6 +21,7 @@ public class RobotContainer { CommandController driver = new CommandController(0); // Driver Controller CommandController operator = new CommandController(1); // Operator Controller CommandSwerveDrivetrain drivetrain = TunerConstants.DriveTrain; // My drivetrain + private final LEDSubsystem ledSubsystem; SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric() .withIsOpenLoop(true) @@ -39,6 +41,8 @@ public class RobotContainer { Pose2d odomStart = new Pose2d(0, 0, new Rotation2d(0, 0)); private void configureBindings() { + ledSubsystem.setDefaultCommand(new InstantCommand(() -> ledSubsystem.periodic(), ledSubsystem)); + drivetrain.setDefaultCommand( // Drivetrain will execute this command periodically drivetrain .applyRequest( @@ -67,7 +71,6 @@ private void configureBindings() { // drivetrain.seedFieldRelative(new Pose2d(new Translation2d(), Rotation2d.fromDegrees(90))); // } drivetrain.registerTelemetry(logger::telemeterize); - driver.POVUp() .whileTrue( drivetrain.applyRequest(() -> forwardStraight.withVelocityX(0.5).withVelocityY(0))); @@ -78,6 +81,7 @@ private void configureBindings() { public RobotContainer() { configureBindings(); + ledSubsystem = new LEDSubsystem(); } public Command getAutonomousCommand() { diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeConstants.java b/src/main/java/frc/robot/subsystems/intake/IntakeConstants.java index 9667bad..1e00685 100644 --- a/src/main/java/frc/robot/subsystems/intake/IntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/intake/IntakeConstants.java @@ -2,35 +2,33 @@ public class IntakeConstants { - /** Used when scoring/outtaking */ - public class OuttakeSpeeds { - public static final double LOW_CUBE = 0.3; - public static final double LOW_CONE = 0.6; - public static final double LOW_CUBE_AUTO = 0.3; - public static final double LOW_CONE_AUTO = 1.0; - - public static final double MID_CONE = 0.1; - public static final double MID_CONE_TIPPED = 0.8; - public static final double MID_CUBE = 0.25; - public static final double MID_CUBE_AUTO = 0.2; - - public static final double HIGH_CONE = 0.15; - public static final double HIGH_CONE_AUTO = 0.15; - public static final double HIGH_CUBE = 0.55; - public static final double HIGH_CUBE_AUTO = 0.6; - } - - public static final double INTAKING_SPEED = 0.95; - - public static final int INTAKE_MOTOR_CHANNEL = 6; - public static final double INTAKE_AMP_THRESHOLD = 16; - - // 20ms per periodic cycle * number of periodic cycles / 1000 to get as milliseconds - public static final double INTAKE_CUBE_DELAY = (20 * 15) / 1000; - public static final double INTAKE_CONE_DELAY = (20 * 18) / 1000; - - public static final double HOLD_CONE_SPEED = 0.18; - public static final double HOLD_CUBE_SPEED = 0.15; - - + /** Used when scoring/outtaking */ + public class OuttakeSpeeds { + public static final double LOW_CUBE = 0.3; + public static final double LOW_CONE = 0.6; + public static final double LOW_CUBE_AUTO = 0.3; + public static final double LOW_CONE_AUTO = 1.0; + + public static final double MID_CONE = 0.1; + public static final double MID_CONE_TIPPED = 0.8; + public static final double MID_CUBE = 0.25; + public static final double MID_CUBE_AUTO = 0.2; + + public static final double HIGH_CONE = 0.15; + public static final double HIGH_CONE_AUTO = 0.15; + public static final double HIGH_CUBE = 0.55; + public static final double HIGH_CUBE_AUTO = 0.6; + } + + public static final double INTAKING_SPEED = 0.95; + + public static final int INTAKE_MOTOR_CHANNEL = 6; + public static final double INTAKE_AMP_THRESHOLD = 16; + + // 20ms per periodic cycle * number of periodic cycles / 1000 to get as milliseconds + public static final double INTAKE_CUBE_DELAY = (20 * 15) / 1000; + public static final double INTAKE_CONE_DELAY = (20 * 18) / 1000; + + public static final double HOLD_CONE_SPEED = 0.18; + public static final double HOLD_CUBE_SPEED = 0.15; } diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeSubsystem.java b/src/main/java/frc/robot/subsystems/intake/IntakeSubsystem.java index 9b5a3df..05ef9f3 100644 --- a/src/main/java/frc/robot/subsystems/intake/IntakeSubsystem.java +++ b/src/main/java/frc/robot/subsystems/intake/IntakeSubsystem.java @@ -10,184 +10,190 @@ import frc.robot.subsystems.intake.enums.IntakeScoreType; /** - * This an example implementation of our - * intake subsystem from 2023. - * - * Each subsystem represents a different purpose of the robot - * such as arms, LEDs, drivetrains, shooter, etc. + * This an example implementation of our intake subsystem from 2023. + * + *
Each subsystem represents a different purpose of the robot such as arms, LEDs, drivetrains, + * shooter, etc. */ public class IntakeSubsystem extends SubsystemBase { - private VictorSP intakeMotor = new VictorSP(IntakeConstants.INTAKE_MOTOR_CHANNEL); - private PowerDistribution pdp; - - public IntakeSubsystem(PowerDistribution pdp) { - this.pdp = pdp; - } - - /** - * This method runs once every 20ms. - * - * This is useful for updating subsystem-specific - * state that you don't want to offload to a Command. - * - * Teams should try to be consistent within their - * own codebases about which responsibilities will - * be handled by Commands, and which will be handled here. - */ - @Override - public void periodic() { - SmartDashboard.putNumber("INTAKE CURRENT", this.pdp.getCurrent(IntakeConstants.INTAKE_MOTOR_CHANNEL)); - SmartDashboard.putNumber("INTAKE SPEED", this.intakeMotor.get()); - } - - /** - * Runs a command that stops the intake - * - * @return a command that stops the intake - */ - public Command stopIntakeCommand() { - return runOnce(() -> this.intakeMotor.set(0)) - .ignoringDisable(true); - } - - /** - * Runs a command to score a gamepiece. - * - * @param type the type of the score you want to make - * @param expectedPiece the type of gamepiece to expect when scoring - * @return a command that scores a gamepiece - */ - public Command intakeScoreCommand(IntakeScoreType type, IntakeGamepieces expectedPiece) { - return run(() -> { - - switch (type) { - case MID_CONE -> { - Commands.runOnce(() -> outtakeCommand(IntakeConstants.OuttakeSpeeds.MID_CONE), this) - .andThen(Commands.waitSeconds(0.5)) - .andThen(stopIntakeCommand()); - } - - case MID_CONE_TIPPED -> { - Commands.runOnce(() -> outtakeCommand(IntakeConstants.OuttakeSpeeds.MID_CONE_TIPPED), this) - .andThen(Commands.waitSeconds(0.5)) - .andThen(stopIntakeCommand()); - } - - case MID_CUBE -> { - Commands.runOnce(() -> outtakeCommand(IntakeConstants.OuttakeSpeeds.MID_CUBE), this) - .andThen(Commands.waitSeconds(0.5)) - .andThen(stopIntakeCommand()); - } - - case MID_CUBE_AUTO -> { - Commands.runOnce(() -> outtakeCommand(IntakeConstants.OuttakeSpeeds.MID_CUBE_AUTO), this) - .andThen(Commands.waitSeconds(0.5)) - .andThen(stopIntakeCommand()); - } - - case HIGH_CONE -> { - Commands.runOnce(() -> outtakeCommand(IntakeConstants.OuttakeSpeeds.HIGH_CONE), this) - .andThen(Commands.waitSeconds(0.5)) - .andThen(stopIntakeCommand()); - } - - case HIGH_CONE_AUTO -> { - Commands.runOnce(() -> outtakeCommand(IntakeConstants.OuttakeSpeeds.HIGH_CONE_AUTO), this) - .andThen(Commands.waitSeconds(0.5)) - .andThen(stopIntakeCommand()); - } - - case HIGH_CUBE -> { - Commands.runOnce(() -> outtakeCommand(IntakeConstants.OuttakeSpeeds.HIGH_CUBE), this) - .andThen(Commands.waitSeconds(0.5)) - .andThen(stopIntakeCommand()); - } - - case HIGH_CUBE_AUTO -> { - Commands.runOnce(() -> outtakeCommand(IntakeConstants.OuttakeSpeeds.HIGH_CUBE_AUTO), this) - .andThen(Commands.waitSeconds(0.5)) - .andThen(stopIntakeCommand()); - } - - case LOW -> { - if (expectedPiece.equals(IntakeGamepieces.CUBE)) { - Commands.runOnce(() -> outtakeCommand(IntakeConstants.OuttakeSpeeds.LOW_CUBE), this) - .andThen(Commands.waitSeconds(1)) - .andThen(stopIntakeCommand()); - } else { - Commands.runOnce(() -> outtakeCommand(IntakeConstants.OuttakeSpeeds.LOW_CONE), this) - .andThen(Commands.waitSeconds(1)) - .andThen(stopIntakeCommand()); - } - } - - case LOW_AUTO -> { - if (expectedPiece.equals(IntakeGamepieces.CUBE)) { - Commands.runOnce(() -> outtakeCommand(IntakeConstants.OuttakeSpeeds.LOW_CUBE_AUTO), this) - .andThen(Commands.waitSeconds(1)) - .andThen(stopIntakeCommand()); - } else { - Commands.runOnce(() -> outtakeCommand(IntakeConstants.OuttakeSpeeds.LOW_CONE_AUTO), this) - .andThen(Commands.waitSeconds(1)) - .andThen(stopIntakeCommand()); - } - } + private VictorSP intakeMotor = new VictorSP(IntakeConstants.INTAKE_MOTOR_CHANNEL); + private PowerDistribution pdp; + + public IntakeSubsystem(PowerDistribution pdp) { + this.pdp = pdp; + } + + /** + * This method runs once every 20ms. + * + *
This is useful for updating subsystem-specific state that you don't want to offload to a + * Command. + * + *
Teams should try to be consistent within their own codebases about which responsibilities + * will be handled by Commands, and which will be handled here. + */ + @Override + public void periodic() { + SmartDashboard.putNumber( + "INTAKE CURRENT", this.pdp.getCurrent(IntakeConstants.INTAKE_MOTOR_CHANNEL)); + SmartDashboard.putNumber("INTAKE SPEED", this.intakeMotor.get()); + } + + /** + * Runs a command that stops the intake + * + * @return a command that stops the intake + */ + public Command stopIntakeCommand() { + return runOnce(() -> this.intakeMotor.set(0)).ignoringDisable(true); + } + + /** + * Runs a command to score a gamepiece. + * + * @param type the type of the score you want to make + * @param expectedPiece the type of gamepiece to expect when scoring + * @return a command that scores a gamepiece + */ + public Command intakeScoreCommand(IntakeScoreType type, IntakeGamepieces expectedPiece) { + return run(() -> { + switch (type) { + case MID_CONE -> { + Commands.runOnce(() -> outtakeCommand(IntakeConstants.OuttakeSpeeds.MID_CONE), this) + .andThen(Commands.waitSeconds(0.5)) + .andThen(stopIntakeCommand()); } - }).andThen(stopIntakeCommand()); - } - - /** - * Runs a command that intakes and holds a gamepiece - * - * @param gamepiece the type of gamepiece to expect - * @return a command that forces the intake to hold the specified gamepiece - */ - public Command intakeHoldCommand(IntakeGamepieces gamepiece) { - return run(() -> { - this.intakeMotor.set(IntakeConstants.INTAKING_SPEED); - - // this will keep the motor running as long as the current is low enough - // this results in something similar to an if statement - Commands.waitUntil(() -> this.pdp - .getCurrent(IntakeConstants.INTAKE_MOTOR_CHANNEL) < IntakeConstants.INTAKE_AMP_THRESHOLD); - - if (gamepiece.equals(IntakeGamepieces.CUBE)) { - // wait a short amount of time so the gamepiece gets pulled in - Commands.waitSeconds(IntakeConstants.INTAKE_CUBE_DELAY); - this.intakeMotor.set(IntakeConstants.HOLD_CUBE_SPEED); + + case MID_CONE_TIPPED -> { + Commands.runOnce( + () -> outtakeCommand(IntakeConstants.OuttakeSpeeds.MID_CONE_TIPPED), this) + .andThen(Commands.waitSeconds(0.5)) + .andThen(stopIntakeCommand()); + } + + case MID_CUBE -> { + Commands.runOnce(() -> outtakeCommand(IntakeConstants.OuttakeSpeeds.MID_CUBE), this) + .andThen(Commands.waitSeconds(0.5)) + .andThen(stopIntakeCommand()); + } + + case MID_CUBE_AUTO -> { + Commands.runOnce( + () -> outtakeCommand(IntakeConstants.OuttakeSpeeds.MID_CUBE_AUTO), this) + .andThen(Commands.waitSeconds(0.5)) + .andThen(stopIntakeCommand()); + } + + case HIGH_CONE -> { + Commands.runOnce(() -> outtakeCommand(IntakeConstants.OuttakeSpeeds.HIGH_CONE), this) + .andThen(Commands.waitSeconds(0.5)) + .andThen(stopIntakeCommand()); + } + + case HIGH_CONE_AUTO -> { + Commands.runOnce( + () -> outtakeCommand(IntakeConstants.OuttakeSpeeds.HIGH_CONE_AUTO), this) + .andThen(Commands.waitSeconds(0.5)) + .andThen(stopIntakeCommand()); + } + + case HIGH_CUBE -> { + Commands.runOnce(() -> outtakeCommand(IntakeConstants.OuttakeSpeeds.HIGH_CUBE), this) + .andThen(Commands.waitSeconds(0.5)) + .andThen(stopIntakeCommand()); + } + + case HIGH_CUBE_AUTO -> { + Commands.runOnce( + () -> outtakeCommand(IntakeConstants.OuttakeSpeeds.HIGH_CUBE_AUTO), this) + .andThen(Commands.waitSeconds(0.5)) + .andThen(stopIntakeCommand()); + } + + case LOW -> { + if (expectedPiece.equals(IntakeGamepieces.CUBE)) { + Commands.runOnce(() -> outtakeCommand(IntakeConstants.OuttakeSpeeds.LOW_CUBE), this) + .andThen(Commands.waitSeconds(1)) + .andThen(stopIntakeCommand()); + } else { + Commands.runOnce(() -> outtakeCommand(IntakeConstants.OuttakeSpeeds.LOW_CONE), this) + .andThen(Commands.waitSeconds(1)) + .andThen(stopIntakeCommand()); + } } - if (gamepiece.equals(IntakeGamepieces.CONE)) { - // we have a cone, so run the motor at a higher speed - Commands.waitSeconds(IntakeConstants.INTAKE_CONE_DELAY); - this.intakeMotor.set(IntakeConstants.HOLD_CONE_SPEED); + + case LOW_AUTO -> { + if (expectedPiece.equals(IntakeGamepieces.CUBE)) { + Commands.runOnce( + () -> outtakeCommand(IntakeConstants.OuttakeSpeeds.LOW_CUBE_AUTO), this) + .andThen(Commands.waitSeconds(1)) + .andThen(stopIntakeCommand()); + } else { + Commands.runOnce( + () -> outtakeCommand(IntakeConstants.OuttakeSpeeds.LOW_CONE_AUTO), this) + .andThen(Commands.waitSeconds(1)) + .andThen(stopIntakeCommand()); + } } - }).finallyDo(() -> this.intakeMotor.set(0)) - .ignoringDisable(false); - } - - /** - * Runs a command that spits out its gamepiece - * - * @param speed speed to run the motor at, this is pre-inverted - * @return a command that forces the intake to spit out its gamepiece - */ - public Command outtakeCommand(double speed) { - return runOnce(() -> this.intakeMotor.set(-speed)); - } - - /** - * This method is similar to periodic, - * but only runs in simulation mode. - * - * Useful for updating subsystem-specific state - * that needs to be maintained for simulations, such as - * for updating edu.wpi.first.wpilibj.simulation classes - * and setting simulated sensor readings. - */ - @Override - public void simulationPeriodic() { - SmartDashboard.putNumber("INTAKE CURRENT", this.pdp.getCurrent(IntakeConstants.INTAKE_MOTOR_CHANNEL)); - SmartDashboard.putNumber("INTAKE SPEED", this.intakeMotor.get()); - } + } + }) + .andThen(stopIntakeCommand()); + } + + /** + * Runs a command that intakes and holds a gamepiece + * + * @param gamepiece the type of gamepiece to expect + * @return a command that forces the intake to hold the specified gamepiece + */ + public Command intakeHoldCommand(IntakeGamepieces gamepiece) { + return run(() -> { + this.intakeMotor.set(IntakeConstants.INTAKING_SPEED); + + // this will keep the motor running as long as the current is low enough + // this results in something similar to an if statement + Commands.waitUntil( + () -> + this.pdp.getCurrent(IntakeConstants.INTAKE_MOTOR_CHANNEL) + < IntakeConstants.INTAKE_AMP_THRESHOLD); + + if (gamepiece.equals(IntakeGamepieces.CUBE)) { + // wait a short amount of time so the gamepiece gets pulled in + Commands.waitSeconds(IntakeConstants.INTAKE_CUBE_DELAY); + this.intakeMotor.set(IntakeConstants.HOLD_CUBE_SPEED); + } + if (gamepiece.equals(IntakeGamepieces.CONE)) { + // we have a cone, so run the motor at a higher speed + Commands.waitSeconds(IntakeConstants.INTAKE_CONE_DELAY); + this.intakeMotor.set(IntakeConstants.HOLD_CONE_SPEED); + } + }) + .finallyDo(() -> this.intakeMotor.set(0)) + .ignoringDisable(false); + } + + /** + * Runs a command that spits out its gamepiece + * + * @param speed speed to run the motor at, this is pre-inverted + * @return a command that forces the intake to spit out its gamepiece + */ + public Command outtakeCommand(double speed) { + return runOnce(() -> this.intakeMotor.set(-speed)); + } + + /** + * This method is similar to periodic, but only runs in simulation mode. + * + *
Useful for updating subsystem-specific state that needs to be maintained for simulations,
+ * such as for updating edu.wpi.first.wpilibj.simulation classes and setting simulated sensor
+ * readings.
+ */
+ @Override
+ public void simulationPeriodic() {
+ SmartDashboard.putNumber(
+ "INTAKE CURRENT", this.pdp.getCurrent(IntakeConstants.INTAKE_MOTOR_CHANNEL));
+ SmartDashboard.putNumber("INTAKE SPEED", this.intakeMotor.get());
+ }
}
diff --git a/src/main/java/frc/robot/subsystems/intake/enums/IntakeGamepieces.java b/src/main/java/frc/robot/subsystems/intake/enums/IntakeGamepieces.java
index c5eb73b..3a87c37 100644
--- a/src/main/java/frc/robot/subsystems/intake/enums/IntakeGamepieces.java
+++ b/src/main/java/frc/robot/subsystems/intake/enums/IntakeGamepieces.java
@@ -1,6 +1,6 @@
package frc.robot.subsystems.intake.enums;
public enum IntakeGamepieces {
- CONE,
- CUBE
+ CONE,
+ CUBE
}
diff --git a/src/main/java/frc/robot/subsystems/intake/enums/IntakeScoreType.java b/src/main/java/frc/robot/subsystems/intake/enums/IntakeScoreType.java
index 12e6a64..f1fe54e 100644
--- a/src/main/java/frc/robot/subsystems/intake/enums/IntakeScoreType.java
+++ b/src/main/java/frc/robot/subsystems/intake/enums/IntakeScoreType.java
@@ -1,14 +1,14 @@
package frc.robot.subsystems.intake.enums;
public enum IntakeScoreType {
- HIGH_CONE,
- HIGH_CONE_AUTO,
- HIGH_CUBE,
- HIGH_CUBE_AUTO,
- MID_CONE,
- MID_CONE_TIPPED,
- MID_CUBE,
- MID_CUBE_AUTO,
- LOW,
- LOW_AUTO
+ HIGH_CONE,
+ HIGH_CONE_AUTO,
+ HIGH_CUBE,
+ HIGH_CUBE_AUTO,
+ MID_CONE,
+ MID_CONE_TIPPED,
+ MID_CUBE,
+ MID_CUBE_AUTO,
+ LOW,
+ LOW_AUTO
}
diff --git a/src/main/java/frc/robot/subsystems/led/LEDColour.java b/src/main/java/frc/robot/subsystems/led/LEDColour.java
new file mode 100644
index 0000000..c908bb2
--- /dev/null
+++ b/src/main/java/frc/robot/subsystems/led/LEDColour.java
@@ -0,0 +1,89 @@
+package frc.robot.subsystems.led;
+
+/**
+ * This is only used for setting solid colour states. Please see the LEDModes.java class for special
+ * LED modes
+ */
+public class LEDColour {
+ private double red, green, blue;
+
+ public LEDColour(int red, int green, int blue) {
+ this.red = red;
+ this.green = green;
+ this.blue = blue;
+ }
+
+ public LEDColour(double red, double green, double blue) {
+ this.red = red;
+ this.green = green;
+ this.blue = blue;
+ }
+
+ /**
+ * Copies the RGB values from an LEDState object to the current one
+ *
+ * @param ledState The LEDState to copy the RGB values from
+ * @return The current instane of LEDColour with the new RGB values
+ */
+ public LEDColour copy(LEDColour ledState) {
+ this.red = ledState.red;
+ this.green = ledState.green;
+ this.blue = ledState.blue;
+
+ return this;
+ }
+
+ /**
+ * Gets the red value of an LED state object
+ *
+ * @return The double value of the red value in the RGB sequence
+ */
+ public double getRed() {
+ return this.red;
+ }
+
+ /**
+ * Gets the red value of an LED state object as an integer
+ *
+ * @return The integer value of the red value in the RGB sequence
+ */
+ public int getRedInt() {
+ return (int) this.red;
+ }
+
+ /**
+ * Gets the green value of an LED state object
+ *
+ * @return The double value of the green value in the RGB sequence
+ */
+ public double getGreen() {
+ return this.green;
+ }
+
+ /**
+ * Gets the green value of an LED state object as an integer
+ *
+ * @return The integer value of the green value in the RGB sequence
+ */
+ public int getGreenInt() {
+ return (int) this.green;
+ }
+
+ /**
+ * Gets the blue value of an LED state object
+ *
+ * @return The integer value of the blue value in the RGB sequence
+ */
+ public double getBlue() {
+ return this.blue;
+ }
+
+ /**
+ * Gets the blue value of an LED state object as an integer
+ *
+ * @return The integer value of the blue value in the RGB sequence
+ */
+ public int getBlueInt() {
+ return (int) this.blue;
+ }
+}
diff --git a/src/main/java/frc/robot/subsystems/led/LEDConstants.java b/src/main/java/frc/robot/subsystems/led/LEDConstants.java
new file mode 100644
index 0000000..970777a
--- /dev/null
+++ b/src/main/java/frc/robot/subsystems/led/LEDConstants.java
@@ -0,0 +1,7 @@
+package frc.robot.subsystems.led;
+
+public class LEDConstants {
+
+ public static final int ledsPerSegment =
+ 16; // The number LEDs (actual diodes) there are on each segment
+}
diff --git a/src/main/java/frc/robot/subsystems/led/LEDSegment.java b/src/main/java/frc/robot/subsystems/led/LEDSegment.java
new file mode 100644
index 0000000..9c6e9c7
--- /dev/null
+++ b/src/main/java/frc/robot/subsystems/led/LEDSegment.java
@@ -0,0 +1,76 @@
+package frc.robot.subsystems.led;
+
+import frc.robot.subsystems.led.exceptions.InvalidLEDSegmentException;
+import frc.robot.subsystems.led.modes.Breathing;
+import frc.robot.subsystems.led.modes.LEDMode;
+import frc.robot.subsystems.led.modes.Solid;
+
+/**
+ * We are going to attach a name to each index in the LED modes array here. Remember that all
+ * indexes start at 0 and NOT 1
+ */
+public enum LEDSegment {
+
+ // Add all aliases for segments below
+ FrontLeft(0, new Solid(new LEDColour(255, 0, 0))), // Set the LEDs to solid red
+ BackLeft(1, new Breathing(new LEDColour(0, 255, 0))), // Create a green breathing effect
+ BackRight(2, new Breathing(new LEDColour(0, 255, 0))), // Create a green breathing effect
+ FrontRight(3, new Solid(new LEDColour(255, 0, 0))); // Set the LEDs to solid red
+
+ public final int segmentNumber; // The segment number of the LED strip (starts at 1 and goes up)
+ public LEDMode ledMode; // The mode of the LED strip
+
+ private LEDSegment(int segmentNumber, LEDMode defaultLedMode) {
+ this.segmentNumber = segmentNumber;
+ this.ledMode = defaultLedMode;
+ }
+
+ /**
+ * Checks if the LED segment is a valid segment based off of the number of segments in
+ * LEDConstants.java
+ *
+ * @return True if it is within the index bounds, false if it isn't
+ */
+ private boolean isValid() {
+ // Return a boolean based on if the segment number is greater than number of
+ // segments
+ return (this.getSegmentIdentifier() < LEDSubsystem.ledSegments.size());
+ }
+
+ /**
+ * Sets the mode of the current segment
+ *
+ * @param ledMode The mode to set the LEDs to
+ */
+ public void setLedMode(LEDMode ledMode) {
+ // Guard clause to check if the segment is within the bounds of the number of
+ // available segments
+ if (!this.isValid()) {
+ throw new InvalidLEDSegmentException(
+ String.format(
+ "Invalid LED segment: %d. Number of segments: %d",
+ this.getSegmentIdentifier(),
+ LEDSubsystem.ledSegments.size())); // Throw an exception with the segment information
+ }
+
+ this.ledMode = ledMode;
+ }
+
+ /**
+ * Retrieves the true segment number of an LED segment
+ *
+ * @return The segment number of the LED segment
+ */
+ public int getSegmentIdentifier() {
+ return this.segmentNumber;
+ }
+
+ /**
+ * Gets the LED mode for this segment
+ *
+ * @return The LED mode of the current segment as an LEDMode object
+ */
+ public LEDMode getLedMode() {
+ return this.ledMode;
+ }
+}
diff --git a/src/main/java/frc/robot/subsystems/led/LEDSubsystem.java b/src/main/java/frc/robot/subsystems/led/LEDSubsystem.java
new file mode 100644
index 0000000..e0242d8
--- /dev/null
+++ b/src/main/java/frc/robot/subsystems/led/LEDSubsystem.java
@@ -0,0 +1,60 @@
+package frc.robot.subsystems.led;
+
+import java.util.ArrayList;
+import java.util.List;
+
+import edu.wpi.first.wpilibj.AddressableLED;
+import edu.wpi.first.wpilibj.AddressableLEDBuffer;
+import edu.wpi.first.wpilibj2.command.SubsystemBase;
+import frc.robot.subsystems.led.modes.LEDMode;
+
+public class LEDSubsystem extends SubsystemBase {
+
+ public static List