From 2ecdd4a400ea654f54866b54af495b04236b68fa Mon Sep 17 00:00:00 2001 From: abi-appusamy9932 Date: Wed, 9 Jul 2025 15:04:26 -0400 Subject: [PATCH 01/11] led code LedIO + CANdle and Sim implementations LedStrip for high level control --- .../java/org/team2342/lib/leds/LedIO.java | 35 +++- .../org/team2342/lib/leds/LedIOCANdle.java | 89 ++++++++- .../java/org/team2342/lib/leds/LedIOSim.java | 48 +++++ .../java/org/team2342/lib/leds/LedStrip.java | 149 +++++++++++++++ .../team2342/lib/motors/dumb/DumbMotorIO.java | 20 ++ .../lib/motors/dumb/DumbMotorIOSim.java | 17 ++ .../lib/motors/dumb/DumbMotorIOTalonFX.java | 20 ++ vendordeps/Phoenix5-5.35.1.json | 171 ++++++++++++++++++ 8 files changed, 547 insertions(+), 2 deletions(-) create mode 100644 src/main/java/org/team2342/lib/leds/LedIOSim.java create mode 100644 src/main/java/org/team2342/lib/leds/LedStrip.java create mode 100644 vendordeps/Phoenix5-5.35.1.json diff --git a/src/main/java/org/team2342/lib/leds/LedIO.java b/src/main/java/org/team2342/lib/leds/LedIO.java index 3252197..b5b329c 100644 --- a/src/main/java/org/team2342/lib/leds/LedIO.java +++ b/src/main/java/org/team2342/lib/leds/LedIO.java @@ -6,4 +6,37 @@ package org.team2342.lib.leds; -public interface LedIO {} +import com.ctre.phoenix.led.Animation; +import edu.wpi.first.wpilibj.util.Color; + +/** + * Interface for LED input/output Allows for different LED implementations to use the same structure + */ +public interface LedIO { + /** Container class for LED inputs - used for logging and data updates. */ + public static class LedIOInputs { + public Color firstHalfColor = Color.kWhite; + public Color secondHalfColor = Color.kWhite; + } + + /** + * Called periodically to update the LED input data. + * + * @param inputs The object that stores LED readings to be logged or used somewhere else. + */ + public default void updateInputs(LedIOInputs inputs) {} + /** + * Sets the color for the first or second half of the LED strip. + * + * @param color The color to set for the half + */ + public default void setFirstHalfColor(Color color) {} + + public default void setSecondHalfColor(Color color) {} + /** + * Sets the animation for the LED strip. + * + * @param animation The animation to apply to the LED strip. + */ + public default void setAnimation(Animation animation) {} +} diff --git a/src/main/java/org/team2342/lib/leds/LedIOCANdle.java b/src/main/java/org/team2342/lib/leds/LedIOCANdle.java index e3e27c8..d69dddb 100644 --- a/src/main/java/org/team2342/lib/leds/LedIOCANdle.java +++ b/src/main/java/org/team2342/lib/leds/LedIOCANdle.java @@ -6,4 +6,91 @@ package org.team2342.lib.leds; -public class LedIOCANdle implements LedIO {} +import com.ctre.phoenix.led.Animation; +import com.ctre.phoenix.led.CANdle; +import com.ctre.phoenix.led.CANdle.LEDStripType; +import com.ctre.phoenix.led.CANdleConfiguration; +import edu.wpi.first.wpilibj.util.Color; + +/** + * Implementation of LedIO using a CANdle device. This class manages the LED strip by controlling + * the colors and animations. + */ +public class LedIOCANdle implements LedIO { + private final CANdle candle; + private final int totalLeds; + private final int halfLength; + + private Color firstHalfColor = Color.kWhite; + private Color secondHalfColor = Color.kWhite; + + /** + * Constructor for LedIOCANdle. Initializes the CANdle with the specified CAN ID and LED count. + * + * @param canId The CAN ID of the CANdle device. + * @param LedCount The total number of LEDs in the strip. + */ + public LedIOCANdle(int canId, int LedCount) { + candle = new CANdle(canId); + totalLeds = LedCount; + halfLength = LedCount / 2; + + CANdleConfiguration config = new CANdleConfiguration(); + config.stripType = LEDStripType.RGB; + config.brightnessScalar = 1.0; + candle.configAllSettings(config); + } + + /** + * Called periodically to update the LED input data. + * @param inputs The LedIOInputs object to update + */ + @Override + public void updateInputs(LedIOInputs inputs) { + inputs.firstHalfColor = firstHalfColor; + inputs.secondHalfColor = secondHalfColor; + } + + /** + * Sets the color for the first half and second half of the LED strip. + * + * @param color The color to set for the half + */ + @Override + public void setFirstHalfColor(Color color) { + firstHalfColor = color; + candle.clearAnimation(0); + candle.setLEDs( + (int) (color.red * 255), + (int) (color.green * 255), + (int) (color.blue * 255), + 0, + 0, + halfLength); + } + + @Override + public void setSecondHalfColor(Color color) { + secondHalfColor = color; + candle.clearAnimation(0); + candle.setLEDs( + (int) (color.red * 255), + (int) (color.green * 255), + (int) (color.blue * 255), + 0, + halfLength, + halfLength); + } + + /** + * Sets the animation for the LED strip. + * + * @param animation The animation to apply to the LED strip. + */ + @Override + public void setAnimation(Animation animation) { + candle.clearAnimation(0); + animation.setNumLed(totalLeds); + candle.animate(animation); + } +} diff --git a/src/main/java/org/team2342/lib/leds/LedIOSim.java b/src/main/java/org/team2342/lib/leds/LedIOSim.java new file mode 100644 index 0000000..8717985 --- /dev/null +++ b/src/main/java/org/team2342/lib/leds/LedIOSim.java @@ -0,0 +1,48 @@ +package org.team2342.lib.leds; + +import org.littletonrobotics.junction.Logger; +import edu.wpi.first.wpilibj.util.Color; + +/** + * Simulation implementation of LedIO + * Logs RGB values + * + */ +public class LedIOSim implements LedIO { + private Color firstHalfColor = Color.kWhite; + private Color secondHalfColor = Color.kWhite; + + /** + * Sets the color for the first or second half of the LED strip + * + * @param color The color to set for the half + */ + @Override + public void setFirstHalfColor(Color color) { + firstHalfColor = color; + } + + @Override + public void setSecondHalfColor(Color color) { + secondHalfColor = color; + } + + /** + * Called periodically to update the LED input data + * + * @param inputs The LedIOInputs object to update + */ + @Override + public void updateInputs(LedIOInputs inputs) { + inputs.firstHalfColor = firstHalfColor; + inputs.secondHalfColor = secondHalfColor; + + Logger.recordOutput("LED/FirstHalf/Red", firstHalfColor.red); + Logger.recordOutput("LED/FirstHalf/Green", firstHalfColor.green); + Logger.recordOutput("LED/FirstHalf/Blue", firstHalfColor.blue); + + Logger.recordOutput("LED/SecondHalf/Red", secondHalfColor.red); + Logger.recordOutput("LED/SecondHalf/Green", secondHalfColor.green); + Logger.recordOutput("LED/SecondHalf/Blue", secondHalfColor.blue); + } +} diff --git a/src/main/java/org/team2342/lib/leds/LedStrip.java b/src/main/java/org/team2342/lib/leds/LedStrip.java new file mode 100644 index 0000000..15e7ebc --- /dev/null +++ b/src/main/java/org/team2342/lib/leds/LedStrip.java @@ -0,0 +1,149 @@ +// Copyright (c) 2025 Team 2342 +// https://github.com/FRCTeamPhoenix +// +// This source code is licensed under the MIT License. +// See the LICENSE file in the root directory of this project. + +package org.team2342.lib.leds; + +import com.ctre.phoenix.led.*; +import edu.wpi.first.wpilibj.Timer; +import edu.wpi.first.wpilibj.util.Color; +import java.util.EnumSet; + +/** + * High-level LED control that splits a strip into two halves: one for the driver and one for the + * operator. Each side can be assigned a color and an effect (solid, flashing, animations). + * + *

Use `setDriver()` and `setOperator()` to configure each side. Call `periodic()` each loop to + * update animations or effects. Example usage in robot code: + * + *

{@code
+ * ledStrip.setDriver(Color.kRed, LedStrip.Effect.FIRE);
+ * ledStrip.setOperator(Color.kBlue, LedStrip.Effect.FLASHING);
+ * ledStrip.periodic(); // must be called regularly
+ * }
+ */ +public class LedStrip { + // LED options to choose from + public enum Effect { + SOLID, + FLASHING, + RAINBOW, + FIRE, + LARSON, + OFF + } + + private final LedIO io; + private final int totalLeds; + + private Color driverColor = Color.kWhite; + private Effect driverEffect = Effect.SOLID; + + private Color operatorColor = Color.kWhite; + private Effect operatorEffect = Effect.SOLID; + + private boolean flashing = true; + private double lastFlashTime = 0.0; + + // Set of effects that use animations + private static final EnumSet animations = + EnumSet.of(Effect.RAINBOW, Effect.FIRE, Effect.LARSON); + + /** + * Constructor for LedStrip. + * + * @param io The LedIO interface to control the LEDs. + * @param totalLeds The total number of LEDs in the strip. + */ + public LedStrip(LedIO io, int totalLeds) { + this.io = io; + this.totalLeds = totalLeds; + } + + /** + * Sets the color and effect for the driver side of the LED strip. + * + * @param color The color to set for the driver side. + * @param effect The effect to apply to the driver side. + */ + public void setDriverColor(Color color, Effect effect) { + driverColor = color; + driverEffect = effect; + } + + // Same as above, but for the operator side + public void setOperatorColor(Color color, Effect effect) { + operatorColor = color; + operatorEffect = effect; + } + + /** + * Updates the LED strip each cycle. Must be called regularly to keep flashing and animation + * effects in sync. + */ + public void periodic() { + double now = Timer.getFPGATimestamp(); + + if ((now - lastFlashTime) > 0.5) { + flashing = !flashing; + lastFlashTime = now; + } + + // Driver + if (animations.contains(driverEffect)) { + io.setAnimation(createAnimation(driverColor, driverEffect)); + } else { + io.setFirstHalfColor(resolve(driverColor, driverEffect)); + } + + // Operator + if (animations.contains(operatorEffect)) { + io.setAnimation(createAnimation(operatorColor, operatorEffect)); + } else { + io.setSecondHalfColor(resolve(operatorColor, operatorEffect)); + } + } + + /** + * Converts an effect and color into a real color value Used for SOLID, FLASHING, and OFF effects. + * + * @param color The base color to resolve + * @param effect The effect to apply + * @return The resolved color based on the effect. + */ + private Color resolve(Color color, Effect effect) { + return switch (effect) { + case SOLID -> color; + case FLASHING -> flashing ? color : Color.kBlack; + case OFF -> Color.kBlack; + default -> color; + }; + } + + /** + * Builds an animation object (CTRE) from the given effect. Used for RAINBOW, FIRE, and LARSON + * effects. + * + * @param color The base color for the animation. + * @param effect The effect type to create. + * @return The created Animation object. + */ + private Animation createAnimation(Color color, Effect effect) { + return switch (effect) { + case RAINBOW -> new RainbowAnimation(1.0, 0.5, totalLeds, false, 0); + case FIRE -> new FireAnimation(1.0, 0.5, totalLeds, 0.6, 0.1); + case LARSON -> new LarsonAnimation( + (int) (color.red * 255), + (int) (color.green * 255), + (int) (color.blue * 255), + 0, + 0.5, + totalLeds, + LarsonAnimation.BounceMode.Front, + (totalLeds / 5)); + default -> null; + }; + } +} diff --git a/src/main/java/org/team2342/lib/motors/dumb/DumbMotorIO.java b/src/main/java/org/team2342/lib/motors/dumb/DumbMotorIO.java index d5e8531..6fac1e8 100644 --- a/src/main/java/org/team2342/lib/motors/dumb/DumbMotorIO.java +++ b/src/main/java/org/team2342/lib/motors/dumb/DumbMotorIO.java @@ -8,7 +8,16 @@ import org.littletonrobotics.junction.AutoLog; +/* + * Interface for dumb motor input/output + * Lets simulation, real hardware, and different motor types to use same structure + */ + public interface DumbMotorIO { + /** + * Container class for motor inputs - used for logging and data updates. The @AutoLog annotation + * automatically generates code for logging with the AdvantageKit framework. + */ @AutoLog public static class DumbMotorIOInputs { public boolean connected = false; @@ -16,7 +25,18 @@ public static class DumbMotorIOInputs { public double currentAmps = 0.0; } + /** + * Called periodically to update the motor input data. + * + * @param inputs The object that stores motor readings to be logged or used somewhere else. + */ public default void updateInputs(DumbMotorIOInputs inputs) {} + /** + * Runs the motor at a specified voltage. This method is intended to be overridden by + * implementations to control the motor. + * + * @param voltage The voltage to apply to the motor. + */ public default void runVoltage(double voltage) {} } diff --git a/src/main/java/org/team2342/lib/motors/dumb/DumbMotorIOSim.java b/src/main/java/org/team2342/lib/motors/dumb/DumbMotorIOSim.java index 574b99c..37191d5 100644 --- a/src/main/java/org/team2342/lib/motors/dumb/DumbMotorIOSim.java +++ b/src/main/java/org/team2342/lib/motors/dumb/DumbMotorIOSim.java @@ -11,15 +11,27 @@ import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.wpilibj.simulation.LinearSystemSim; +/** Simulation implementation of DumbMotorIO Uses a LinearSystemSim to simulate */ public class DumbMotorIOSim implements DumbMotorIO { private final LinearSystemSim sim; private final DCMotor motor; + /** + * Constructs a new DumbMotorIOSim instance. + * + * @param motor The DC motor model to simulate + * @param sim The linear system simulation representing the motor's behavior + */ public DumbMotorIOSim(DCMotor motor, LinearSystemSim sim) { this.motor = motor; this.sim = sim; } + /** + * Updates the inputs for the motor controller + * + * @param inputs The inputs object to update with current values + */ @Override public void updateInputs(DumbMotorIOInputs inputs) { sim.update(0.02); @@ -31,6 +43,11 @@ public void updateInputs(DumbMotorIOInputs inputs) { inputs.currentAmps = current; } + /** + * Sets the motor to run at the specified voltage + * + * @param voltage The desired voltage to apply to the motor + */ @Override public void runVoltage(double voltage) { sim.setInput(voltage); diff --git a/src/main/java/org/team2342/lib/motors/dumb/DumbMotorIOTalonFX.java b/src/main/java/org/team2342/lib/motors/dumb/DumbMotorIOTalonFX.java index 269446c..3d6b4f1 100644 --- a/src/main/java/org/team2342/lib/motors/dumb/DumbMotorIOTalonFX.java +++ b/src/main/java/org/team2342/lib/motors/dumb/DumbMotorIOTalonFX.java @@ -19,6 +19,10 @@ import edu.wpi.first.units.measure.Voltage; import org.team2342.frc.util.PhoenixUtils; +/** + * Implementation of DumbMotorIO for a TalonFX motor controller Handles configuration, input + * updates, and voltage control for the motor + */ public class DumbMotorIOTalonFX implements DumbMotorIO { private final TalonFX talon; @@ -28,6 +32,12 @@ public class DumbMotorIOTalonFX implements DumbMotorIO { private final VoltageOut voltageRequest = new VoltageOut(0); private final Debouncer connectedDebouncer = new Debouncer(0.5); + /** + * Constructor to configure the TalonFX motor controller + * + * @param canID The CAN ID of the TalonFX motor controller + * @param config The configuration settings for the motor + */ public DumbMotorIOTalonFX(int canID, DumbMotorConfig config) { talon = new TalonFX(canID); @@ -57,6 +67,11 @@ public DumbMotorIOTalonFX(int canID, DumbMotorConfig config) { PhoenixUtils.tryUntilOk(5, () -> ParentDevice.optimizeBusUtilizationForAll(talon)); } + /** + * Updates the inputs for the motor controller + * + * @param inputs The inputs object to update with current values + */ @Override public void updateInputs(DumbMotorIOInputs inputs) { inputs.connected = @@ -65,6 +80,11 @@ public void updateInputs(DumbMotorIOInputs inputs) { inputs.currentAmps = current.getValueAsDouble(); } + /** + * Sets the motor to run at the specified voltage + * + * @param voltage The desired voltage to apply to the motor + */ @Override public void runVoltage(double voltage) { talon.setControl(voltageRequest.withOutput(voltage)); diff --git a/vendordeps/Phoenix5-5.35.1.json b/vendordeps/Phoenix5-5.35.1.json new file mode 100644 index 0000000..2190f40 --- /dev/null +++ b/vendordeps/Phoenix5-5.35.1.json @@ -0,0 +1,171 @@ +{ + "fileName": "Phoenix5-5.35.1.json", + "name": "CTRE-Phoenix (v5)", + "version": "5.35.1", + "frcYear": "2025", + "uuid": "ab676553-b602-441f-a38d-f1296eff6537", + "mavenUrls": [ + "https://maven.ctr-electronics.com/release/" + ], + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2025-latest.json", + "requires": [ + { + "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", + "errorMessage": "Phoenix 5 requires low-level libraries from Phoenix 6. Please add the Phoenix 6 vendordep before adding Phoenix 5.", + "offlineFileName": "Phoenix6-frc2025-latest.json", + "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-latest.json" + } + ], + "conflictsWith": [ + { + "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af", + "errorMessage": "Users must use the Phoenix 5 replay vendordep when using the Phoenix 6 replay vendordep.", + "offlineFileName": "Phoenix6-replay-frc2025-latest.json" + }, + { + "uuid": "fbc886a4-2cec-40c0-9835-71086a8cc3df", + "errorMessage": "Users cannot have both the replay and regular Phoenix 5 vendordeps in their robot program.", + "offlineFileName": "Phoenix5-replay-frc2025-latest.json" + } + ], + "javaDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "api-java", + "version": "5.35.1" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "wpiapi-java", + "version": "5.35.1" + } + ], + "jniDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "cci", + "version": "5.35.1", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "cci-sim", + "version": "5.35.1", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + } + ], + "cppDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "wpiapi-cpp", + "version": "5.35.1", + "libName": "CTRE_Phoenix_WPI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "api-cpp", + "version": "5.35.1", + "libName": "CTRE_Phoenix", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "cci", + "version": "5.35.1", + "libName": "CTRE_PhoenixCCI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "wpiapi-cpp-sim", + "version": "5.35.1", + "libName": "CTRE_Phoenix_WPISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "api-cpp-sim", + "version": "5.35.1", + "libName": "CTRE_PhoenixSim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "cci-sim", + "version": "5.35.1", + "libName": "CTRE_PhoenixCCISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + } + ] +} From 950ed5e745627335243ac0e62c1a2ec6a7c6e27b Mon Sep 17 00:00:00 2001 From: Phoenix2342-Bot Date: Wed, 9 Jul 2025 19:24:38 +0000 Subject: [PATCH 02/11] Auto-format code --- .../org/team2342/lib/leds/LedIOCANdle.java | 3 +- .../java/org/team2342/lib/leds/LedIOSim.java | 86 ++++++++++--------- 2 files changed, 46 insertions(+), 43 deletions(-) diff --git a/src/main/java/org/team2342/lib/leds/LedIOCANdle.java b/src/main/java/org/team2342/lib/leds/LedIOCANdle.java index d69dddb..c1b4772 100644 --- a/src/main/java/org/team2342/lib/leds/LedIOCANdle.java +++ b/src/main/java/org/team2342/lib/leds/LedIOCANdle.java @@ -43,7 +43,8 @@ public LedIOCANdle(int canId, int LedCount) { /** * Called periodically to update the LED input data. - * @param inputs The LedIOInputs object to update + * + * @param inputs The LedIOInputs object to update */ @Override public void updateInputs(LedIOInputs inputs) { diff --git a/src/main/java/org/team2342/lib/leds/LedIOSim.java b/src/main/java/org/team2342/lib/leds/LedIOSim.java index 8717985..62facb8 100644 --- a/src/main/java/org/team2342/lib/leds/LedIOSim.java +++ b/src/main/java/org/team2342/lib/leds/LedIOSim.java @@ -1,48 +1,50 @@ +// Copyright (c) 2025 Team 2342 +// https://github.com/FRCTeamPhoenix +// +// This source code is licensed under the MIT License. +// See the LICENSE file in the root directory of this project. + package org.team2342.lib.leds; -import org.littletonrobotics.junction.Logger; import edu.wpi.first.wpilibj.util.Color; +import org.littletonrobotics.junction.Logger; -/** - * Simulation implementation of LedIO - * Logs RGB values - * - */ +/** Simulation implementation of LedIO Logs RGB values */ public class LedIOSim implements LedIO { - private Color firstHalfColor = Color.kWhite; - private Color secondHalfColor = Color.kWhite; - - /** - * Sets the color for the first or second half of the LED strip - * - * @param color The color to set for the half - */ - @Override - public void setFirstHalfColor(Color color) { - firstHalfColor = color; - } - - @Override - public void setSecondHalfColor(Color color) { - secondHalfColor = color; - } - - /** - * Called periodically to update the LED input data - * - * @param inputs The LedIOInputs object to update - */ - @Override - public void updateInputs(LedIOInputs inputs) { - inputs.firstHalfColor = firstHalfColor; - inputs.secondHalfColor = secondHalfColor; - - Logger.recordOutput("LED/FirstHalf/Red", firstHalfColor.red); - Logger.recordOutput("LED/FirstHalf/Green", firstHalfColor.green); - Logger.recordOutput("LED/FirstHalf/Blue", firstHalfColor.blue); - - Logger.recordOutput("LED/SecondHalf/Red", secondHalfColor.red); - Logger.recordOutput("LED/SecondHalf/Green", secondHalfColor.green); - Logger.recordOutput("LED/SecondHalf/Blue", secondHalfColor.blue); - } + private Color firstHalfColor = Color.kWhite; + private Color secondHalfColor = Color.kWhite; + + /** + * Sets the color for the first or second half of the LED strip + * + * @param color The color to set for the half + */ + @Override + public void setFirstHalfColor(Color color) { + firstHalfColor = color; + } + + @Override + public void setSecondHalfColor(Color color) { + secondHalfColor = color; + } + + /** + * Called periodically to update the LED input data + * + * @param inputs The LedIOInputs object to update + */ + @Override + public void updateInputs(LedIOInputs inputs) { + inputs.firstHalfColor = firstHalfColor; + inputs.secondHalfColor = secondHalfColor; + + Logger.recordOutput("LED/FirstHalf/Red", firstHalfColor.red); + Logger.recordOutput("LED/FirstHalf/Green", firstHalfColor.green); + Logger.recordOutput("LED/FirstHalf/Blue", firstHalfColor.blue); + + Logger.recordOutput("LED/SecondHalf/Red", secondHalfColor.red); + Logger.recordOutput("LED/SecondHalf/Green", secondHalfColor.green); + Logger.recordOutput("LED/SecondHalf/Blue", secondHalfColor.blue); + } } From 0a72ed6eed87fa3af9f6ba80b961a140a74985f0 Mon Sep 17 00:00:00 2001 From: abi-appusamy9932 Date: Sun, 4 Jan 2026 17:47:42 -0500 Subject: [PATCH 03/11] finishing led code --- .../java/org/team2342/lib/leds/LedIO.java | 77 +++++--- .../org/team2342/lib/leds/LedIOCANdle.java | 181 +++++++++++------- .../java/org/team2342/lib/leds/LedIOSim.java | 90 ++++++--- .../java/org/team2342/lib/leds/LedStrip.java | 159 ++++----------- vendordeps/Phoenix5-5.35.1.json | 171 ----------------- ....3.2.json => Phoenix6-frc2025-latest.json} | 92 ++++++--- 6 files changed, 318 insertions(+), 452 deletions(-) delete mode 100644 vendordeps/Phoenix5-5.35.1.json rename vendordeps/{Phoenix6-25.3.2.json => Phoenix6-frc2025-latest.json} (86%) diff --git a/src/main/java/org/team2342/lib/leds/LedIO.java b/src/main/java/org/team2342/lib/leds/LedIO.java index b5b329c..af8f0ba 100644 --- a/src/main/java/org/team2342/lib/leds/LedIO.java +++ b/src/main/java/org/team2342/lib/leds/LedIO.java @@ -6,37 +6,58 @@ package org.team2342.lib.leds; -import com.ctre.phoenix.led.Animation; -import edu.wpi.first.wpilibj.util.Color; - -/** - * Interface for LED input/output Allows for different LED implementations to use the same structure - */ public interface LedIO { - /** Container class for LED inputs - used for logging and data updates. */ + + public enum Half { + FIRST, + SECOND, + ALL + } + + + public enum LedEffect { + SOLID, + FLASHING, + RAINBOW, + OFF + } + + public static class LedColor { + public int red; + public int green; + public int blue; + + public LedColor(int red, int green, int blue) { + this.red = red; + this.green = green; + this.blue = blue; + } + + public static LedColor off() { + return new LedColor(0, 0, 0); + } + } + public static class LedIOInputs { - public Color firstHalfColor = Color.kWhite; - public Color secondHalfColor = Color.kWhite; + public LedColor firstHalfColor = LedColor.off(); + public LedColor secondHalfColor = LedColor.off(); + public LedEffect firstHalfEffect = LedEffect.OFF; + public LedEffect secondHalfEffect = LedEffect.OFF; } - /** - * Called periodically to update the LED input data. - * - * @param inputs The object that stores LED readings to be logged or used somewhere else. - */ public default void updateInputs(LedIOInputs inputs) {} - /** - * Sets the color for the first or second half of the LED strip. - * - * @param color The color to set for the half - */ - public default void setFirstHalfColor(Color color) {} - - public default void setSecondHalfColor(Color color) {} - /** - * Sets the animation for the LED strip. - * - * @param animation The animation to apply to the LED strip. - */ - public default void setAnimation(Animation animation) {} + + public default void setColor(Half half, LedColor color) {} + + public default void setEffect(Half half, LedEffect effect, LedColor color) {} + + public default void setAllColor(LedColor color) { + setColor(Half.FIRST, color); + setColor(Half.SECOND, color); + } + + public default void setAllEffect(LedEffect effect, LedColor color) { + setEffect(Half.FIRST, effect, color); + setEffect(Half.SECOND, effect, color); + } } diff --git a/src/main/java/org/team2342/lib/leds/LedIOCANdle.java b/src/main/java/org/team2342/lib/leds/LedIOCANdle.java index c1b4772..41169fc 100644 --- a/src/main/java/org/team2342/lib/leds/LedIOCANdle.java +++ b/src/main/java/org/team2342/lib/leds/LedIOCANdle.java @@ -6,92 +6,127 @@ package org.team2342.lib.leds; -import com.ctre.phoenix.led.Animation; -import com.ctre.phoenix.led.CANdle; -import com.ctre.phoenix.led.CANdle.LEDStripType; -import com.ctre.phoenix.led.CANdleConfiguration; -import edu.wpi.first.wpilibj.util.Color; +import com.ctre.phoenix6.hardware.CANdle; +import com.ctre.phoenix6.configs.CANdleConfiguration; +import com.ctre.phoenix6.controls.SolidColor; +import com.ctre.phoenix6.controls.RainbowAnimation; +import com.ctre.phoenix6.signals.RGBWColor; +import com.ctre.phoenix6.signals.StripTypeValue; -/** - * Implementation of LedIO using a CANdle device. This class manages the LED strip by controlling - * the colors and animations. - */ -public class LedIOCANdle implements LedIO { - private final CANdle candle; - private final int totalLeds; - private final int halfLength; - private Color firstHalfColor = Color.kWhite; - private Color secondHalfColor = Color.kWhite; +public class LedIOCANdle implements LedIO { + private CANdle candle; + private int totalLeds; + private int firstHalfLength; + private int secondHalfLength; + + private LedColor lastFirstColor = LedColor.off(); + private LedColor lastSecondColor = LedColor.off(); + private LedEffect lastFirstEffect = LedEffect.OFF; + private LedEffect lastSecondEffect = LedEffect.OFF; - /** - * Constructor for LedIOCANdle. Initializes the CANdle with the specified CAN ID and LED count. - * - * @param canId The CAN ID of the CANdle device. - * @param LedCount The total number of LEDs in the strip. - */ - public LedIOCANdle(int canId, int LedCount) { - candle = new CANdle(canId); - totalLeds = LedCount; - halfLength = LedCount / 2; + public LedIOCANdle(int canID, int ledCount){ + this.candle = new CANdle(canID); + this.totalLeds = ledCount; + this.firstHalfLength = totalLeds / 2; + this.secondHalfLength = totalLeds - firstHalfLength; CANdleConfiguration config = new CANdleConfiguration(); - config.stripType = LEDStripType.RGB; - config.brightnessScalar = 1.0; - candle.configAllSettings(config); + config.LED.StripType = StripTypeValue.RGB; + candle.getConfigurator().apply(config); } - /** - * Called periodically to update the LED input data. - * - * @param inputs The LedIOInputs object to update - */ @Override - public void updateInputs(LedIOInputs inputs) { - inputs.firstHalfColor = firstHalfColor; - inputs.secondHalfColor = secondHalfColor; + public void updateInputs(LedIOInputs inputs){ + inputs.firstHalfColor = lastFirstColor; + inputs.secondHalfColor = lastSecondColor; + inputs.firstHalfEffect = lastFirstEffect; + inputs.secondHalfEffect = lastSecondEffect; } - - /** - * Sets the color for the first half and second half of the LED strip. - * - * @param color The color to set for the half - */ + @Override - public void setFirstHalfColor(Color color) { - firstHalfColor = color; - candle.clearAnimation(0); - candle.setLEDs( - (int) (color.red * 255), - (int) (color.green * 255), - (int) (color.blue * 255), - 0, - 0, - halfLength); + public void setColor(Half half, LedColor color) { + switch (half) { + case FIRST: + sendSolidColor(0, firstHalfLength, color); + lastFirstColor = color; + lastFirstEffect = LedEffect.SOLID; + break; + case SECOND: + sendSolidColor(firstHalfLength, secondHalfLength, color); + lastSecondColor = color; + lastSecondEffect = LedEffect.SOLID; + break; + case ALL: + sendSolidColor(0, totalLeds, color); + lastFirstColor = color; + lastSecondColor = color; + lastFirstEffect = LedEffect.SOLID; + lastSecondEffect = LedEffect.SOLID; + break; + } + } @Override - public void setSecondHalfColor(Color color) { - secondHalfColor = color; - candle.clearAnimation(0); - candle.setLEDs( - (int) (color.red * 255), - (int) (color.green * 255), - (int) (color.blue * 255), - 0, - halfLength, - halfLength); + public void setEffect(Half half, LedEffect effect, LedColor color) { + if (color == null){ + color = LedColor.off(); + } + + int start = 0; + int length = 0; + + switch (half) { + case FIRST: + start = 0; + length = firstHalfLength; + lastFirstColor = color; + lastFirstEffect = effect; + break; + case SECOND: + start = firstHalfLength; + length = secondHalfLength; + lastSecondColor = color; + lastSecondEffect = effect; + break; + case ALL: + start = 0; + length = totalLeds; + lastFirstEffect = effect; + lastSecondEffect = effect; + lastFirstColor = color; + lastSecondColor = color; + break; + } + + switch (effect) { + case SOLID: + sendSolidColor(start, length, color); + break; + case RAINBOW: + RainbowAnimation rainbow = new RainbowAnimation(start, length); + candle.setControl(rainbow); + break; + case FLASHING: + sendSolidColor(start, length, color); + break; + case OFF: + sendSolidColor(start, length, LedColor.off()); + break; + } } - /** - * Sets the animation for the LED strip. - * - * @param animation The animation to apply to the LED strip. - */ - @Override - public void setAnimation(Animation animation) { - candle.clearAnimation(0); - animation.setNumLed(totalLeds); - candle.animate(animation); + private RGBWColor toCTRE(LedColor c) { + if (c == null){ + return new RGBWColor(0,0,0,0); + } + return new RGBWColor(c.red, c.green, c.blue,0); + } + + private void sendSolidColor(int start, int length, LedColor color) { + SolidColor request = new SolidColor(start, length); + request.withColor(toCTRE(color)); + candle.setControl(request); } -} +} \ No newline at end of file diff --git a/src/main/java/org/team2342/lib/leds/LedIOSim.java b/src/main/java/org/team2342/lib/leds/LedIOSim.java index 62facb8..137d6b4 100644 --- a/src/main/java/org/team2342/lib/leds/LedIOSim.java +++ b/src/main/java/org/team2342/lib/leds/LedIOSim.java @@ -6,45 +6,77 @@ package org.team2342.lib.leds; -import edu.wpi.first.wpilibj.util.Color; import org.littletonrobotics.junction.Logger; -/** Simulation implementation of LedIO Logs RGB values */ public class LedIOSim implements LedIO { - private Color firstHalfColor = Color.kWhite; - private Color secondHalfColor = Color.kWhite; - - /** - * Sets the color for the first or second half of the LED strip - * - * @param color The color to set for the half - */ + private LedColor firstColor = LedColor.off(); + private LedColor secondColor = LedColor.off(); + private LedEffect firstEffect = LedEffect.OFF; + private LedEffect secondEffect = LedEffect.OFF; + @Override - public void setFirstHalfColor(Color color) { - firstHalfColor = color; + public void setColor(Half half, LedColor color) { + if (color == null) { + color = LedColor.off(); + } + + switch (half) { + case FIRST: + firstColor = color; + firstEffect = LedEffect.SOLID; + break; + case SECOND: + secondColor = color; + secondEffect = LedEffect.SOLID; + break; + case ALL: + firstColor = color; + secondColor = color; + firstEffect = LedEffect.SOLID; + secondEffect = LedEffect.SOLID; + break; + } } @Override - public void setSecondHalfColor(Color color) { - secondHalfColor = color; + public void setEffect(Half half, LedEffect effect, LedColor color){ + if (color == null) { + color = LedColor.off(); + } + + switch (half) { + case FIRST: + firstColor = color; + firstEffect = effect; + break; + case SECOND: + secondColor = color; + secondEffect = effect; + break; + case ALL: + firstColor = color; + secondColor = color; + firstEffect = effect; + secondEffect = effect; + break; + } } - /** - * Called periodically to update the LED input data - * - * @param inputs The LedIOInputs object to update - */ @Override - public void updateInputs(LedIOInputs inputs) { - inputs.firstHalfColor = firstHalfColor; - inputs.secondHalfColor = secondHalfColor; + public void updateInputs(LedIOInputs inputs){ + inputs.firstHalfColor = firstColor; + inputs.secondHalfColor = secondColor; + inputs.firstHalfEffect = firstEffect; + inputs.secondHalfEffect = secondEffect; - Logger.recordOutput("LED/FirstHalf/Red", firstHalfColor.red); - Logger.recordOutput("LED/FirstHalf/Green", firstHalfColor.green); - Logger.recordOutput("LED/FirstHalf/Blue", firstHalfColor.blue); + Logger.recordOutput("LED/FirstHalf/Red", firstColor.red); + Logger.recordOutput("LED/FirstHalf/Green", firstColor.green); + Logger.recordOutput("LED/FirstHalf/Blue", firstColor.blue); + Logger.recordOutput("LED/FirstHalf/Effect", firstEffect.toString()); - Logger.recordOutput("LED/SecondHalf/Red", secondHalfColor.red); - Logger.recordOutput("LED/SecondHalf/Green", secondHalfColor.green); - Logger.recordOutput("LED/SecondHalf/Blue", secondHalfColor.blue); + Logger.recordOutput("LED/SecondHalf/Red", secondColor.red); + Logger.recordOutput("LED/SecondHalf/Green", secondColor.green); + Logger.recordOutput("LED/SecondHalf/Blue", secondColor.blue); + Logger.recordOutput("LED/SecondHalf/Effect", secondEffect.toString()); } -} +} \ No newline at end of file diff --git a/src/main/java/org/team2342/lib/leds/LedStrip.java b/src/main/java/org/team2342/lib/leds/LedStrip.java index 15e7ebc..df971f7 100644 --- a/src/main/java/org/team2342/lib/leds/LedStrip.java +++ b/src/main/java/org/team2342/lib/leds/LedStrip.java @@ -6,144 +6,63 @@ package org.team2342.lib.leds; -import com.ctre.phoenix.led.*; import edu.wpi.first.wpilibj.Timer; -import edu.wpi.first.wpilibj.util.Color; -import java.util.EnumSet; - -/** - * High-level LED control that splits a strip into two halves: one for the driver and one for the - * operator. Each side can be assigned a color and an effect (solid, flashing, animations). - * - *

Use `setDriver()` and `setOperator()` to configure each side. Call `periodic()` each loop to - * update animations or effects. Example usage in robot code: - * - *

{@code
- * ledStrip.setDriver(Color.kRed, LedStrip.Effect.FIRE);
- * ledStrip.setOperator(Color.kBlue, LedStrip.Effect.FLASHING);
- * ledStrip.periodic(); // must be called regularly
- * }
- */ -public class LedStrip { - // LED options to choose from - public enum Effect { - SOLID, - FLASHING, - RAINBOW, - FIRE, - LARSON, - OFF - } +import edu.wpi.first.wpilibj2.command.SubsystemBase; +public class LedStrip extends SubsystemBase { private final LedIO io; - private final int totalLeds; - - private Color driverColor = Color.kWhite; - private Effect driverEffect = Effect.SOLID; - - private Color operatorColor = Color.kWhite; - private Effect operatorEffect = Effect.SOLID; + private LedIO.LedColor firstColor = LedIO.LedColor.off(); + private LedIO.LedEffect firstEffect = LedIO.LedEffect.OFF; + private LedIO.LedColor secondColor = LedIO.LedColor.off(); + private LedIO.LedEffect secondEffect = LedIO.LedEffect.OFF; - private boolean flashing = true; + private boolean flashing = false; private double lastFlashTime = 0.0; + private static final double FLASH_PERIOD_SEC = 0.5; - // Set of effects that use animations - private static final EnumSet animations = - EnumSet.of(Effect.RAINBOW, Effect.FIRE, Effect.LARSON); - - /** - * Constructor for LedStrip. - * - * @param io The LedIO interface to control the LEDs. - * @param totalLeds The total number of LEDs in the strip. - */ - public LedStrip(LedIO io, int totalLeds) { + public LedStrip(LedIO io){ this.io = io; - this.totalLeds = totalLeds; } - /** - * Sets the color and effect for the driver side of the LED strip. - * - * @param color The color to set for the driver side. - * @param effect The effect to apply to the driver side. - */ - public void setDriverColor(Color color, Effect effect) { - driverColor = color; - driverEffect = effect; + public void setFirst(LedIO.LedEffect effect, LedIO.LedColor color){ + firstEffect = effect; + firstColor = color; } - // Same as above, but for the operator side - public void setOperatorColor(Color color, Effect effect) { - operatorColor = color; - operatorEffect = effect; + public void setSecond(LedIO.LedEffect effect, LedIO.LedColor color){ + secondEffect = effect; + secondColor = color; } - /** - * Updates the LED strip each cycle. Must be called regularly to keep flashing and animation - * effects in sync. - */ + @Override public void periodic() { - double now = Timer.getFPGATimestamp(); + updateFlashing(); + applyEffect(LedIO.Half.FIRST, firstEffect, firstColor); + applyEffect(LedIO.Half.SECOND, secondEffect, secondColor); + } - if ((now - lastFlashTime) > 0.5) { + private void updateFlashing() { + double now = Timer.getFPGATimestamp(); + if (now - lastFlashTime >= FLASH_PERIOD_SEC) { flashing = !flashing; lastFlashTime = now; } - - // Driver - if (animations.contains(driverEffect)) { - io.setAnimation(createAnimation(driverColor, driverEffect)); - } else { - io.setFirstHalfColor(resolve(driverColor, driverEffect)); - } - - // Operator - if (animations.contains(operatorEffect)) { - io.setAnimation(createAnimation(operatorColor, operatorEffect)); - } else { - io.setSecondHalfColor(resolve(operatorColor, operatorEffect)); - } } - /** - * Converts an effect and color into a real color value Used for SOLID, FLASHING, and OFF effects. - * - * @param color The base color to resolve - * @param effect The effect to apply - * @return The resolved color based on the effect. - */ - private Color resolve(Color color, Effect effect) { - return switch (effect) { - case SOLID -> color; - case FLASHING -> flashing ? color : Color.kBlack; - case OFF -> Color.kBlack; - default -> color; - }; - } - - /** - * Builds an animation object (CTRE) from the given effect. Used for RAINBOW, FIRE, and LARSON - * effects. - * - * @param color The base color for the animation. - * @param effect The effect type to create. - * @return The created Animation object. - */ - private Animation createAnimation(Color color, Effect effect) { - return switch (effect) { - case RAINBOW -> new RainbowAnimation(1.0, 0.5, totalLeds, false, 0); - case FIRE -> new FireAnimation(1.0, 0.5, totalLeds, 0.6, 0.1); - case LARSON -> new LarsonAnimation( - (int) (color.red * 255), - (int) (color.green * 255), - (int) (color.blue * 255), - 0, - 0.5, - totalLeds, - LarsonAnimation.BounceMode.Front, - (totalLeds / 5)); - default -> null; - }; + private void applyEffect(LedIO.Half half, LedIO.LedEffect effect, LedIO.LedColor color){ + switch (effect) { + case SOLID: + io.setColor(half, color); + break; + case FLASHING: + io.setColor(half, (flashing ? color : LedIO.LedColor.off())); + break; + case RAINBOW: + io.setEffect(half, LedIO.LedEffect.RAINBOW, color); + break; + case OFF: + io.setColor(half, LedIO.LedColor.off()); + break; + } } -} +} \ No newline at end of file diff --git a/vendordeps/Phoenix5-5.35.1.json b/vendordeps/Phoenix5-5.35.1.json deleted file mode 100644 index 2190f40..0000000 --- a/vendordeps/Phoenix5-5.35.1.json +++ /dev/null @@ -1,171 +0,0 @@ -{ - "fileName": "Phoenix5-5.35.1.json", - "name": "CTRE-Phoenix (v5)", - "version": "5.35.1", - "frcYear": "2025", - "uuid": "ab676553-b602-441f-a38d-f1296eff6537", - "mavenUrls": [ - "https://maven.ctr-electronics.com/release/" - ], - "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2025-latest.json", - "requires": [ - { - "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", - "errorMessage": "Phoenix 5 requires low-level libraries from Phoenix 6. Please add the Phoenix 6 vendordep before adding Phoenix 5.", - "offlineFileName": "Phoenix6-frc2025-latest.json", - "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-latest.json" - } - ], - "conflictsWith": [ - { - "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af", - "errorMessage": "Users must use the Phoenix 5 replay vendordep when using the Phoenix 6 replay vendordep.", - "offlineFileName": "Phoenix6-replay-frc2025-latest.json" - }, - { - "uuid": "fbc886a4-2cec-40c0-9835-71086a8cc3df", - "errorMessage": "Users cannot have both the replay and regular Phoenix 5 vendordeps in their robot program.", - "offlineFileName": "Phoenix5-replay-frc2025-latest.json" - } - ], - "javaDependencies": [ - { - "groupId": "com.ctre.phoenix", - "artifactId": "api-java", - "version": "5.35.1" - }, - { - "groupId": "com.ctre.phoenix", - "artifactId": "wpiapi-java", - "version": "5.35.1" - } - ], - "jniDependencies": [ - { - "groupId": "com.ctre.phoenix", - "artifactId": "cci", - "version": "5.35.1", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix.sim", - "artifactId": "cci-sim", - "version": "5.35.1", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - } - ], - "cppDependencies": [ - { - "groupId": "com.ctre.phoenix", - "artifactId": "wpiapi-cpp", - "version": "5.35.1", - "libName": "CTRE_Phoenix_WPI", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix", - "artifactId": "api-cpp", - "version": "5.35.1", - "libName": "CTRE_Phoenix", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix", - "artifactId": "cci", - "version": "5.35.1", - "libName": "CTRE_PhoenixCCI", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix.sim", - "artifactId": "wpiapi-cpp-sim", - "version": "5.35.1", - "libName": "CTRE_Phoenix_WPISim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix.sim", - "artifactId": "api-cpp-sim", - "version": "5.35.1", - "libName": "CTRE_PhoenixSim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix.sim", - "artifactId": "cci-sim", - "version": "5.35.1", - "libName": "CTRE_PhoenixCCISim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - } - ] -} diff --git a/vendordeps/Phoenix6-25.3.2.json b/vendordeps/Phoenix6-frc2025-latest.json similarity index 86% rename from vendordeps/Phoenix6-25.3.2.json rename to vendordeps/Phoenix6-frc2025-latest.json index 368e61c..ce44ce4 100644 --- a/vendordeps/Phoenix6-25.3.2.json +++ b/vendordeps/Phoenix6-frc2025-latest.json @@ -1,7 +1,7 @@ { - "fileName": "Phoenix6-25.3.2.json", + "fileName": "Phoenix6-frc2025-latest.json", "name": "CTRE-Phoenix (v6)", - "version": "25.3.2", + "version": "25.4.0", "frcYear": "2025", "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", "mavenUrls": [ @@ -19,14 +19,14 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "wpiapi-java", - "version": "25.3.2" + "version": "25.4.0" } ], "jniDependencies": [ { "groupId": "com.ctre.phoenix6", "artifactId": "api-cpp", - "version": "25.3.2", + "version": "25.4.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -40,7 +40,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "tools", - "version": "25.3.2", + "version": "25.4.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -54,7 +54,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "api-cpp-sim", - "version": "25.3.2", + "version": "25.4.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -68,7 +68,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "tools-sim", - "version": "25.3.2", + "version": "25.4.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -82,7 +82,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonSRX", - "version": "25.3.2", + "version": "25.4.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -96,7 +96,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simVictorSPX", - "version": "25.3.2", + "version": "25.4.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -110,7 +110,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simPigeonIMU", - "version": "25.3.2", + "version": "25.4.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -124,7 +124,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simCANCoder", - "version": "25.3.2", + "version": "25.4.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -138,7 +138,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFX", - "version": "25.3.2", + "version": "25.4.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -152,7 +152,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFXS", - "version": "25.3.2", + "version": "25.4.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -166,7 +166,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANcoder", - "version": "25.3.2", + "version": "25.4.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -180,7 +180,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProPigeon2", - "version": "25.3.2", + "version": "25.4.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -194,7 +194,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANrange", - "version": "25.3.2", + "version": "25.4.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -208,7 +208,21 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANdi", - "version": "25.3.2", + "version": "25.4.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANdle", + "version": "25.4.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -224,7 +238,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "wpiapi-cpp", - "version": "25.3.2", + "version": "25.4.0", "libName": "CTRE_Phoenix6_WPI", "headerClassifier": "headers", "sharedLibrary": true, @@ -240,7 +254,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "tools", - "version": "25.3.2", + "version": "25.4.0", "libName": "CTRE_PhoenixTools", "headerClassifier": "headers", "sharedLibrary": true, @@ -256,7 +270,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "wpiapi-cpp-sim", - "version": "25.3.2", + "version": "25.4.0", "libName": "CTRE_Phoenix6_WPISim", "headerClassifier": "headers", "sharedLibrary": true, @@ -272,7 +286,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "tools-sim", - "version": "25.3.2", + "version": "25.4.0", "libName": "CTRE_PhoenixTools_Sim", "headerClassifier": "headers", "sharedLibrary": true, @@ -288,7 +302,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonSRX", - "version": "25.3.2", + "version": "25.4.0", "libName": "CTRE_SimTalonSRX", "headerClassifier": "headers", "sharedLibrary": true, @@ -304,7 +318,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simVictorSPX", - "version": "25.3.2", + "version": "25.4.0", "libName": "CTRE_SimVictorSPX", "headerClassifier": "headers", "sharedLibrary": true, @@ -320,7 +334,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simPigeonIMU", - "version": "25.3.2", + "version": "25.4.0", "libName": "CTRE_SimPigeonIMU", "headerClassifier": "headers", "sharedLibrary": true, @@ -336,7 +350,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simCANCoder", - "version": "25.3.2", + "version": "25.4.0", "libName": "CTRE_SimCANCoder", "headerClassifier": "headers", "sharedLibrary": true, @@ -352,7 +366,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFX", - "version": "25.3.2", + "version": "25.4.0", "libName": "CTRE_SimProTalonFX", "headerClassifier": "headers", "sharedLibrary": true, @@ -368,7 +382,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFXS", - "version": "25.3.2", + "version": "25.4.0", "libName": "CTRE_SimProTalonFXS", "headerClassifier": "headers", "sharedLibrary": true, @@ -384,7 +398,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANcoder", - "version": "25.3.2", + "version": "25.4.0", "libName": "CTRE_SimProCANcoder", "headerClassifier": "headers", "sharedLibrary": true, @@ -400,7 +414,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProPigeon2", - "version": "25.3.2", + "version": "25.4.0", "libName": "CTRE_SimProPigeon2", "headerClassifier": "headers", "sharedLibrary": true, @@ -416,7 +430,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANrange", - "version": "25.3.2", + "version": "25.4.0", "libName": "CTRE_SimProCANrange", "headerClassifier": "headers", "sharedLibrary": true, @@ -432,7 +446,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANdi", - "version": "25.3.2", + "version": "25.4.0", "libName": "CTRE_SimProCANdi", "headerClassifier": "headers", "sharedLibrary": true, @@ -444,6 +458,22 @@ "osxuniversal" ], "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANdle", + "version": "25.4.0", + "libName": "CTRE_SimProCANdle", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" } ] } From eca617773ce507724b3f5464853c1d6c11671c57 Mon Sep 17 00:00:00 2001 From: abi-appusamy9932 Date: Thu, 8 Jan 2026 13:49:03 -0500 Subject: [PATCH 04/11] implementing requested changes --- .../java/org/team2342/lib/leds/LedIO.java | 45 ++--- .../org/team2342/lib/leds/LedIOCANdle.java | 167 +++++++++--------- .../java/org/team2342/lib/leds/LedIOSim.java | 47 ++--- .../java/org/team2342/lib/leds/LedStrip.java | 63 ++----- 4 files changed, 128 insertions(+), 194 deletions(-) diff --git a/src/main/java/org/team2342/lib/leds/LedIO.java b/src/main/java/org/team2342/lib/leds/LedIO.java index af8f0ba..b5ec797 100644 --- a/src/main/java/org/team2342/lib/leds/LedIO.java +++ b/src/main/java/org/team2342/lib/leds/LedIO.java @@ -1,4 +1,4 @@ -// Copyright (c) 2025 Team 2342 +// Copyright (c) 2026 Team 2342 // https://github.com/FRCTeamPhoenix // // This source code is licensed under the MIT License. @@ -6,6 +6,8 @@ package org.team2342.lib.leds; +import edu.wpi.first.wpilibj.util.Color; + public interface LedIO { public enum Half { @@ -14,50 +16,31 @@ public enum Half { ALL } - public enum LedEffect { - SOLID, - FLASHING, - RAINBOW, + SOLID, + FLASHING, + RAINBOW, OFF } - public static class LedColor { - public int red; - public int green; - public int blue; - - public LedColor(int red, int green, int blue) { - this.red = red; - this.green = green; - this.blue = blue; - } - - public static LedColor off() { - return new LedColor(0, 0, 0); - } - } - public static class LedIOInputs { - public LedColor firstHalfColor = LedColor.off(); - public LedColor secondHalfColor = LedColor.off(); + public Color firstHalfColor = Color.kBlack; + public Color secondHalfColor = Color.kBlack; public LedEffect firstHalfEffect = LedEffect.OFF; public LedEffect secondHalfEffect = LedEffect.OFF; } public default void updateInputs(LedIOInputs inputs) {} - public default void setColor(Half half, LedColor color) {} + public default void setColor(Half half, Color color) {} - public default void setEffect(Half half, LedEffect effect, LedColor color) {} + public default void setEffect(Half half, LedEffect effect, Color color) {} - public default void setAllColor(LedColor color) { - setColor(Half.FIRST, color); - setColor(Half.SECOND, color); + public default void setColor(Color color) { + setColor(Half.ALL, color); } - public default void setAllEffect(LedEffect effect, LedColor color) { - setEffect(Half.FIRST, effect, color); - setEffect(Half.SECOND, effect, color); + public default void setEffect(LedEffect effect, Color color) { + setEffect(Half.ALL, effect, color); } } diff --git a/src/main/java/org/team2342/lib/leds/LedIOCANdle.java b/src/main/java/org/team2342/lib/leds/LedIOCANdle.java index 41169fc..4c41e92 100644 --- a/src/main/java/org/team2342/lib/leds/LedIOCANdle.java +++ b/src/main/java/org/team2342/lib/leds/LedIOCANdle.java @@ -1,4 +1,4 @@ -// Copyright (c) 2025 Team 2342 +// Copyright (c) 2026 Team 2342 // https://github.com/FRCTeamPhoenix // // This source code is licensed under the MIT License. @@ -6,30 +6,29 @@ package org.team2342.lib.leds; -import com.ctre.phoenix6.hardware.CANdle; import com.ctre.phoenix6.configs.CANdleConfiguration; -import com.ctre.phoenix6.controls.SolidColor; import com.ctre.phoenix6.controls.RainbowAnimation; +import com.ctre.phoenix6.controls.SolidColor; +import com.ctre.phoenix6.controls.StrobeAnimation; +import com.ctre.phoenix6.hardware.CANdle; import com.ctre.phoenix6.signals.RGBWColor; import com.ctre.phoenix6.signals.StripTypeValue; - +import edu.wpi.first.wpilibj.util.Color; public class LedIOCANdle implements LedIO { - private CANdle candle; - private int totalLeds; - private int firstHalfLength; - private int secondHalfLength; - - private LedColor lastFirstColor = LedColor.off(); - private LedColor lastSecondColor = LedColor.off(); - private LedEffect lastFirstEffect = LedEffect.OFF; - private LedEffect lastSecondEffect = LedEffect.OFF; + private final CANdle candle; + private final int ledCount; + private final int halfLength; - public LedIOCANdle(int canID, int ledCount){ - this.candle = new CANdle(canID); - this.totalLeds = ledCount; - this.firstHalfLength = totalLeds / 2; - this.secondHalfLength = totalLeds - firstHalfLength; + private Color firstColor = Color.kBlack; + private Color secondColor = Color.kBlack; + private LedEffect firstEffect = LedEffect.OFF; + private LedEffect secondEffect = LedEffect.OFF; + + public LedIOCANdle(int canId, int ledCount) { + this.candle = new CANdle(canId); + this.ledCount = ledCount; + this.halfLength = ledCount / 2; CANdleConfiguration config = new CANdleConfiguration(); config.LED.StripType = StripTypeValue.RGB; @@ -37,96 +36,92 @@ public LedIOCANdle(int canID, int ledCount){ } @Override - public void updateInputs(LedIOInputs inputs){ - inputs.firstHalfColor = lastFirstColor; - inputs.secondHalfColor = lastSecondColor; - inputs.firstHalfEffect = lastFirstEffect; - inputs.secondHalfEffect = lastSecondEffect; + public void updateInputs(LedIOInputs inputs) { + inputs.firstHalfColor = firstColor; + inputs.secondHalfColor = secondColor; + inputs.firstHalfEffect = firstEffect; + inputs.secondHalfEffect = secondEffect; } - + @Override - public void setColor(Half half, LedColor color) { + public void setColor(Half half, Color color) { switch (half) { - case FIRST: - sendSolidColor(0, firstHalfLength, color); - lastFirstColor = color; - lastFirstEffect = LedEffect.SOLID; - break; - case SECOND: - sendSolidColor(firstHalfLength, secondHalfLength, color); - lastSecondColor = color; - lastSecondEffect = LedEffect.SOLID; - break; - case ALL: - sendSolidColor(0, totalLeds, color); - lastFirstColor = color; - lastSecondColor = color; - lastFirstEffect = LedEffect.SOLID; - lastSecondEffect = LedEffect.SOLID; - break; + case FIRST -> { + sendSolidColor(0, halfLength, color); + firstColor = color; + firstEffect = LedEffect.SOLID; } - + case SECOND -> { + sendSolidColor(halfLength, ledCount, color); + secondColor = color; + secondEffect = LedEffect.SOLID; + } + case ALL -> { + sendSolidColor(0, ledCount, color); + firstColor = color; + secondColor = color; + firstEffect = LedEffect.SOLID; + secondEffect = LedEffect.SOLID; + } + } } @Override - public void setEffect(Half half, LedEffect effect, LedColor color) { - if (color == null){ - color = LedColor.off(); + public void setEffect(Half half, LedEffect effect, Color color) { + if (color == null) { + color = Color.kBlack; } - int start = 0; - int length = 0; - switch (half) { case FIRST: - start = 0; - length = firstHalfLength; - lastFirstColor = color; - lastFirstEffect = effect; + firstColor = color; + firstEffect = effect; + applyEffect(0, halfLength, effect, color); break; case SECOND: - start = firstHalfLength; - length = secondHalfLength; - lastSecondColor = color; - lastSecondEffect = effect; + secondColor = color; + secondEffect = effect; + applyEffect(halfLength, ledCount, effect, color); break; case ALL: - start = 0; - length = totalLeds; - lastFirstEffect = effect; - lastSecondEffect = effect; - lastFirstColor = color; - lastSecondColor = color; - break; - } - - switch (effect) { - case SOLID: - sendSolidColor(start, length, color); - break; - case RAINBOW: - RainbowAnimation rainbow = new RainbowAnimation(start, length); - candle.setControl(rainbow); - break; - case FLASHING: - sendSolidColor(start, length, color); - break; - case OFF: - sendSolidColor(start, length, LedColor.off()); + firstColor = color; + secondColor = color; + firstEffect = effect; + secondEffect = effect; break; } } - private RGBWColor toCTRE(LedColor c) { - if (c == null){ - return new RGBWColor(0,0,0,0); + private RGBWColor toCTRE(Color c) { + if (c == null) { + return new RGBWColor(0, 0, 0, 0); } - return new RGBWColor(c.red, c.green, c.blue,0); + return new RGBWColor((int) (c.red * 255), (int) (c.green * 255), (int) (c.blue * 255), 0); } - private void sendSolidColor(int start, int length, LedColor color) { - SolidColor request = new SolidColor(start, length); + private void sendSolidColor(int start, int end, Color color) { + SolidColor request = new SolidColor(start, end); request.withColor(toCTRE(color)); candle.setControl(request); } -} \ No newline at end of file + + private void applyEffect(int start, int end, LedEffect effect, Color color) { + switch (effect) { + case SOLID -> { + sendSolidColor(start, end, color); + } + case FLASHING -> { + StrobeAnimation request = new StrobeAnimation(start, end); + request.withColor(toCTRE(color)); + candle.setControl(request); + } + case RAINBOW -> { + RainbowAnimation request = new RainbowAnimation(start, end); + candle.setControl(request); + } + case OFF -> { + sendSolidColor(start, end, Color.kBlack); + } + } + } +} diff --git a/src/main/java/org/team2342/lib/leds/LedIOSim.java b/src/main/java/org/team2342/lib/leds/LedIOSim.java index 137d6b4..69f7372 100644 --- a/src/main/java/org/team2342/lib/leds/LedIOSim.java +++ b/src/main/java/org/team2342/lib/leds/LedIOSim.java @@ -1,4 +1,4 @@ -// Copyright (c) 2025 Team 2342 +// Copyright (c) 2026 Team 2342 // https://github.com/FRCTeamPhoenix // // This source code is licensed under the MIT License. @@ -6,56 +6,42 @@ package org.team2342.lib.leds; +import edu.wpi.first.wpilibj.util.Color; import org.littletonrobotics.junction.Logger; public class LedIOSim implements LedIO { - private LedColor firstColor = LedColor.off(); - private LedColor secondColor = LedColor.off(); + private Color firstColor = Color.kBlack; + private Color secondColor = Color.kBlack; private LedEffect firstEffect = LedEffect.OFF; private LedEffect secondEffect = LedEffect.OFF; @Override - public void setColor(Half half, LedColor color) { - if (color == null) { - color = LedColor.off(); - } - + public void setColor(Half half, Color color) { switch (half) { case FIRST: firstColor = color; - firstEffect = LedEffect.SOLID; break; case SECOND: secondColor = color; - secondEffect = LedEffect.SOLID; break; case ALL: firstColor = color; secondColor = color; - firstEffect = LedEffect.SOLID; - secondEffect = LedEffect.SOLID; - break; } } @Override - public void setEffect(Half half, LedEffect effect, LedColor color){ - if (color == null) { - color = LedColor.off(); - } + public void setEffect(Half half, LedEffect effect, Color color) { + setColor(half, color); switch (half) { case FIRST: - firstColor = color; firstEffect = effect; break; case SECOND: - secondColor = color; secondEffect = effect; break; case ALL: - firstColor = color; - secondColor = color; firstEffect = effect; secondEffect = effect; break; @@ -63,20 +49,19 @@ public void setEffect(Half half, LedEffect effect, LedColor color){ } @Override - public void updateInputs(LedIOInputs inputs){ + public void updateInputs(LedIOInputs inputs) { inputs.firstHalfColor = firstColor; inputs.secondHalfColor = secondColor; inputs.firstHalfEffect = firstEffect; inputs.secondHalfEffect = secondEffect; - Logger.recordOutput("LED/FirstHalf/Red", firstColor.red); - Logger.recordOutput("LED/FirstHalf/Green", firstColor.green); - Logger.recordOutput("LED/FirstHalf/Blue", firstColor.blue); - Logger.recordOutput("LED/FirstHalf/Effect", firstEffect.toString()); + Logger.recordOutput( + "LED/FirstHalf/Color", new double[] {firstColor.red, firstColor.green, firstColor.blue}); + Logger.recordOutput("LED/FirstHalf/Effect", firstEffect.name()); - Logger.recordOutput("LED/SecondHalf/Red", secondColor.red); - Logger.recordOutput("LED/SecondHalf/Green", secondColor.green); - Logger.recordOutput("LED/SecondHalf/Blue", secondColor.blue); - Logger.recordOutput("LED/SecondHalf/Effect", secondEffect.toString()); + Logger.recordOutput( + "LED/SecondHalf/Color", + new double[] {secondColor.red, secondColor.green, secondColor.blue}); + Logger.recordOutput("LED/SecondHalf/Effect", secondEffect.name()); } -} \ No newline at end of file +} diff --git a/src/main/java/org/team2342/lib/leds/LedStrip.java b/src/main/java/org/team2342/lib/leds/LedStrip.java index df971f7..20c8e52 100644 --- a/src/main/java/org/team2342/lib/leds/LedStrip.java +++ b/src/main/java/org/team2342/lib/leds/LedStrip.java @@ -1,4 +1,4 @@ -// Copyright (c) 2025 Team 2342 +// Copyright (c) 2026 Team 2342 // https://github.com/FRCTeamPhoenix // // This source code is licensed under the MIT License. @@ -6,63 +6,34 @@ package org.team2342.lib.leds; -import edu.wpi.first.wpilibj.Timer; +import edu.wpi.first.wpilibj.util.Color; import edu.wpi.first.wpilibj2.command.SubsystemBase; +import org.team2342.lib.leds.LedIO.LedEffect; +import org.team2342.lib.leds.LedIO.LedIOInputs; public class LedStrip extends SubsystemBase { private final LedIO io; - private LedIO.LedColor firstColor = LedIO.LedColor.off(); - private LedIO.LedEffect firstEffect = LedIO.LedEffect.OFF; - private LedIO.LedColor secondColor = LedIO.LedColor.off(); - private LedIO.LedEffect secondEffect = LedIO.LedEffect.OFF; + private final LedIOInputs inputs = new LedIOInputs(); - private boolean flashing = false; - private double lastFlashTime = 0.0; - private static final double FLASH_PERIOD_SEC = 0.5; - - public LedStrip(LedIO io){ + public LedStrip(LedIO io) { this.io = io; + setName("Leds"); } - public void setFirst(LedIO.LedEffect effect, LedIO.LedColor color){ - firstEffect = effect; - firstColor = color; + public void setDriver(Color color, LedEffect effect) { + io.setEffect(LedIO.Half.FIRST, effect, color); } - public void setSecond(LedIO.LedEffect effect, LedIO.LedColor color){ - secondEffect = effect; - secondColor = color; + public void setOperator(Color color, LedEffect effect) { + io.setEffect(LedIO.Half.SECOND, effect, color); } - @Override - public void periodic() { - updateFlashing(); - applyEffect(LedIO.Half.FIRST, firstEffect, firstColor); - applyEffect(LedIO.Half.SECOND, secondEffect, secondColor); + public void setAll(Color color, LedEffect effect) { + io.setEffect(effect, color); } - private void updateFlashing() { - double now = Timer.getFPGATimestamp(); - if (now - lastFlashTime >= FLASH_PERIOD_SEC) { - flashing = !flashing; - lastFlashTime = now; - } - } - - private void applyEffect(LedIO.Half half, LedIO.LedEffect effect, LedIO.LedColor color){ - switch (effect) { - case SOLID: - io.setColor(half, color); - break; - case FLASHING: - io.setColor(half, (flashing ? color : LedIO.LedColor.off())); - break; - case RAINBOW: - io.setEffect(half, LedIO.LedEffect.RAINBOW, color); - break; - case OFF: - io.setColor(half, LedIO.LedColor.off()); - break; - } + @Override + public void periodic() { + io.updateInputs(inputs); } -} \ No newline at end of file +} From c5d69c0674fc3cf249b4264a6bc04657a4fa2307 Mon Sep 17 00:00:00 2001 From: abi-appusamy9932 Date: Thu, 8 Jan 2026 20:48:32 -0500 Subject: [PATCH 05/11] minor fixes may need to review imports in LedStrip.java --- .../org/team2342/frc/util/PhoenixUtils.java | 17 ++++++++++- .../java/org/team2342/lib/leds/LedIO.java | 29 ++++++++++--------- .../org/team2342/lib/leds/LedIOCANdle.java | 13 ++------- .../java/org/team2342/lib/leds/LedStrip.java | 16 ++++++---- 4 files changed, 44 insertions(+), 31 deletions(-) diff --git a/src/main/java/org/team2342/frc/util/PhoenixUtils.java b/src/main/java/org/team2342/frc/util/PhoenixUtils.java index 6e5c3c8..f582675 100644 --- a/src/main/java/org/team2342/frc/util/PhoenixUtils.java +++ b/src/main/java/org/team2342/frc/util/PhoenixUtils.java @@ -1,4 +1,4 @@ -// Copyright (c) 2025 Team 2342 +// Copyright (c) 2026 Team 2342 // https://github.com/FRCTeamPhoenix // // This source code is licensed under the MIT License. @@ -8,6 +8,9 @@ import com.ctre.phoenix6.BaseStatusSignal; import com.ctre.phoenix6.StatusCode; +import com.ctre.phoenix6.signals.RGBWColor; +import edu.wpi.first.wpilibj.util.Color; + import java.util.function.Supplier; public class PhoenixUtils { @@ -47,4 +50,16 @@ public static void refreshSignals() { // Check to make sure there are signals to refresh if (registeredSignals.length > 0) BaseStatusSignal.refreshAll(registeredSignals); } + + /** + * Used to convert {@link edu.wpi.first.wpilibj.util.Color} to {@link com.ctre.phoenix6.signals.RGBWColor} + * + * @param c WPILib Color to be converted + */ + public static RGBWColor toCTREColor(Color c) { + if (c == null) { + return new RGBWColor(0, 0, 0, 0); + } + return new RGBWColor((int) (c.red * 255), (int) (c.green * 255), (int) (c.blue * 255), 0); + } } diff --git a/src/main/java/org/team2342/lib/leds/LedIO.java b/src/main/java/org/team2342/lib/leds/LedIO.java index b5ec797..e39d168 100644 --- a/src/main/java/org/team2342/lib/leds/LedIO.java +++ b/src/main/java/org/team2342/lib/leds/LedIO.java @@ -7,22 +7,10 @@ package org.team2342.lib.leds; import edu.wpi.first.wpilibj.util.Color; +import org.littletonrobotics.junction.AutoLog; public interface LedIO { - - public enum Half { - FIRST, - SECOND, - ALL - } - - public enum LedEffect { - SOLID, - FLASHING, - RAINBOW, - OFF - } - + @AutoLog public static class LedIOInputs { public Color firstHalfColor = Color.kBlack; public Color secondHalfColor = Color.kBlack; @@ -43,4 +31,17 @@ public default void setColor(Color color) { public default void setEffect(LedEffect effect, Color color) { setEffect(Half.ALL, effect, color); } + + public enum Half { + FIRST, + SECOND, + ALL + } + + public enum LedEffect { + SOLID, + FLASHING, + RAINBOW, + OFF + } } diff --git a/src/main/java/org/team2342/lib/leds/LedIOCANdle.java b/src/main/java/org/team2342/lib/leds/LedIOCANdle.java index 4c41e92..68de469 100644 --- a/src/main/java/org/team2342/lib/leds/LedIOCANdle.java +++ b/src/main/java/org/team2342/lib/leds/LedIOCANdle.java @@ -11,9 +11,9 @@ import com.ctre.phoenix6.controls.SolidColor; import com.ctre.phoenix6.controls.StrobeAnimation; import com.ctre.phoenix6.hardware.CANdle; -import com.ctre.phoenix6.signals.RGBWColor; import com.ctre.phoenix6.signals.StripTypeValue; import edu.wpi.first.wpilibj.util.Color; +import org.team2342.frc.util.PhoenixUtils; public class LedIOCANdle implements LedIO { private final CANdle candle; @@ -92,16 +92,9 @@ public void setEffect(Half half, LedEffect effect, Color color) { } } - private RGBWColor toCTRE(Color c) { - if (c == null) { - return new RGBWColor(0, 0, 0, 0); - } - return new RGBWColor((int) (c.red * 255), (int) (c.green * 255), (int) (c.blue * 255), 0); - } - private void sendSolidColor(int start, int end, Color color) { SolidColor request = new SolidColor(start, end); - request.withColor(toCTRE(color)); + request.withColor(PhoenixUtils.toCTREColor(color)); candle.setControl(request); } @@ -112,7 +105,7 @@ private void applyEffect(int start, int end, LedEffect effect, Color color) { } case FLASHING -> { StrobeAnimation request = new StrobeAnimation(start, end); - request.withColor(toCTRE(color)); + request.withColor(PhoenixUtils.toCTREColor(color)); candle.setControl(request); } case RAINBOW -> { diff --git a/src/main/java/org/team2342/lib/leds/LedStrip.java b/src/main/java/org/team2342/lib/leds/LedStrip.java index 20c8e52..073b696 100644 --- a/src/main/java/org/team2342/lib/leds/LedStrip.java +++ b/src/main/java/org/team2342/lib/leds/LedStrip.java @@ -8,23 +8,26 @@ import edu.wpi.first.wpilibj.util.Color; import edu.wpi.first.wpilibj2.command.SubsystemBase; +import org.littletonrobotics.junction.Logger; import org.team2342.lib.leds.LedIO.LedEffect; -import org.team2342.lib.leds.LedIO.LedIOInputs; +import org.team2342.lib.leds.LedIOInputsAutoLogged; public class LedStrip extends SubsystemBase { private final LedIO io; - private final LedIOInputs inputs = new LedIOInputs(); + private final String name; + private final LedIOInputsAutoLogged inputs = new LedIOInputsAutoLogged(); - public LedStrip(LedIO io) { + public LedStrip(LedIO io, String name) { this.io = io; - setName("Leds"); + this.name = name; + setName(name); } - public void setDriver(Color color, LedEffect effect) { + public void setFirst(Color color, LedEffect effect) { io.setEffect(LedIO.Half.FIRST, effect, color); } - public void setOperator(Color color, LedEffect effect) { + public void setSecond(Color color, LedEffect effect) { io.setEffect(LedIO.Half.SECOND, effect, color); } @@ -35,5 +38,6 @@ public void setAll(Color color, LedEffect effect) { @Override public void periodic() { io.updateInputs(inputs); + Logger.processInputs(name, inputs); } } From d51c621d9a31f8766948371652269991d46f336e Mon Sep 17 00:00:00 2001 From: abi-appusamy9932 Date: Sun, 11 Jan 2026 17:11:30 -0500 Subject: [PATCH 06/11] testing --- src/main/java/org/team2342/frc/Robot.java | 5 +- .../java/org/team2342/frc/RobotContainer.java | 6 +- .../subsystems/CANdleSystem/CANdleSystem.java | 186 ++++++++++++++++++ .../java/org/team2342/lib/leds/LedIO.java | 4 +- .../org/team2342/lib/leds/LedIOCANdle.java | 15 +- .../java/org/team2342/lib/leds/LedIOSim.java | 29 ++- .../java/org/team2342/lib/leds/LedStrip.java | 21 +- 7 files changed, 233 insertions(+), 33 deletions(-) create mode 100644 src/main/java/org/team2342/frc/subsystems/CANdleSystem/CANdleSystem.java diff --git a/src/main/java/org/team2342/frc/Robot.java b/src/main/java/org/team2342/frc/Robot.java index 3fbb08a..9b4b3ff 100644 --- a/src/main/java/org/team2342/frc/Robot.java +++ b/src/main/java/org/team2342/frc/Robot.java @@ -1,4 +1,4 @@ -// Copyright (c) 2025 Team 2342 +// Copyright (c) 2026 Team 2342 // https://github.com/FRCTeamPhoenix // // This source code is licensed under the MIT License. @@ -30,6 +30,7 @@ import org.littletonrobotics.junction.networktables.NT4Publisher; import org.littletonrobotics.junction.wpilog.WPILOGReader; import org.littletonrobotics.junction.wpilog.WPILOGWriter; +import org.team2342.frc.subsystems.CANdleSystem.CANdleSystem; import org.team2342.frc.util.PhoenixUtils; import org.team2342.lib.fsm.StateMachine; import org.team2342.lib.logging.ExecutionLogger; @@ -37,6 +38,7 @@ public class Robot extends LoggedRobot { private Command autonomousCommand; private static final double loopOverrunWarningTimeout = 0.2; + private final CANdleSystem candle = new CANdleSystem(null); private final RobotContainer robotContainer; @@ -188,6 +190,7 @@ public void robotPeriodic() { machine.requestTransition(testStates.STATE_3); machine.periodic(); ExecutionLogger.log("RobotPeriodic"); + candle.periodic(); } @Override diff --git a/src/main/java/org/team2342/frc/RobotContainer.java b/src/main/java/org/team2342/frc/RobotContainer.java index cee044d..bdea760 100644 --- a/src/main/java/org/team2342/frc/RobotContainer.java +++ b/src/main/java/org/team2342/frc/RobotContainer.java @@ -1,4 +1,4 @@ -// Copyright (c) 2025 Team 2342 +// Copyright (c) 2026 Team 2342 // https://github.com/FRCTeamPhoenix // // This source code is licensed under the MIT License. @@ -45,6 +45,9 @@ public class RobotContainer { @Getter private final Drive drive; @Getter private final Vision vision; + // public final LedIOCANdle candle = new LedIOCANdle(22, 37); + // public final LedStrip leds = new LedStrip(candle, "leds"); + private final LoggedDashboardChooser autoChooser; @Getter private final CommandXboxController driverController = new CommandXboxController(0); @@ -114,7 +117,6 @@ public RobotContainer() { autoChooser = new LoggedDashboardChooser<>("Auto Choices", AutoBuilder.buildAutoChooser()); autoChooser.get(); - if (Constants.TUNING) setupDevelopmentRoutines(); configureBindings(); diff --git a/src/main/java/org/team2342/frc/subsystems/CANdleSystem/CANdleSystem.java b/src/main/java/org/team2342/frc/subsystems/CANdleSystem/CANdleSystem.java new file mode 100644 index 0000000..09de6e4 --- /dev/null +++ b/src/main/java/org/team2342/frc/subsystems/CANdleSystem/CANdleSystem.java @@ -0,0 +1,186 @@ +// Copyright (c) 2026 Team 2342 +// https://github.com/FRCTeamPhoenix +// +// This source code is licensed under the MIT License. +// See the LICENSE file in the root directory of this project. + +package org.team2342.frc.subsystems.CANdleSystem; + +import com.ctre.phoenix6.CANBus; +import com.ctre.phoenix6.configs.CANdleConfiguration; +import com.ctre.phoenix6.controls.SolidColor; +import com.ctre.phoenix6.hardware.CANdle; +import com.ctre.phoenix6.signals.RGBWColor; +import com.ctre.phoenix6.signals.StatusLedWhenActiveValue; +import com.ctre.phoenix6.signals.StripTypeValue; +import edu.wpi.first.wpilibj.XboxController; +import edu.wpi.first.wpilibj2.command.SubsystemBase; + +public class CANdleSystem extends SubsystemBase { + private final CANdle m_candle = new CANdle(22, new CANBus("rio")); + private final int LedCount = 300; + private XboxController joystick; + + public enum AnimationTypes { + ColorFlow, + Fire, + Larson, + Rainbow, + RgbFade, + SingleFade, + Strobe, + Twinkle, + TwinkleOff, + SetAll + } + + private AnimationTypes m_currentAnimation; + + public CANdleSystem(XboxController joy) { + this.joystick = joy; + changeAnimation(AnimationTypes.SetAll); + CANdleConfiguration configAll = new CANdleConfiguration(); + configAll.CANdleFeatures.StatusLedWhenActive = StatusLedWhenActiveValue.Disabled; + configAll.LED.StripType = StripTypeValue.GRB; + m_candle.getConfigurator().apply(configAll); + } + + public void incrementAnimation() { + switch (m_currentAnimation) { + case ColorFlow: + changeAnimation(AnimationTypes.Fire); + break; + case Fire: + changeAnimation(AnimationTypes.Larson); + break; + case Larson: + changeAnimation(AnimationTypes.Rainbow); + break; + case Rainbow: + changeAnimation(AnimationTypes.RgbFade); + break; + case RgbFade: + changeAnimation(AnimationTypes.SingleFade); + break; + case SingleFade: + changeAnimation(AnimationTypes.Strobe); + break; + case Strobe: + changeAnimation(AnimationTypes.Twinkle); + break; + case Twinkle: + changeAnimation(AnimationTypes.TwinkleOff); + break; + case TwinkleOff: + changeAnimation(AnimationTypes.ColorFlow); + break; + case SetAll: + changeAnimation(AnimationTypes.ColorFlow); + break; + } + } + + public void decrementAnimation() { + switch (m_currentAnimation) { + case ColorFlow: + changeAnimation(AnimationTypes.TwinkleOff); + break; + case Fire: + changeAnimation(AnimationTypes.ColorFlow); + break; + case Larson: + changeAnimation(AnimationTypes.Fire); + break; + case Rainbow: + changeAnimation(AnimationTypes.Larson); + break; + case RgbFade: + changeAnimation(AnimationTypes.Rainbow); + break; + case SingleFade: + changeAnimation(AnimationTypes.RgbFade); + break; + case Strobe: + changeAnimation(AnimationTypes.SingleFade); + break; + case Twinkle: + changeAnimation(AnimationTypes.Strobe); + break; + case TwinkleOff: + changeAnimation(AnimationTypes.Twinkle); + break; + case SetAll: + changeAnimation(AnimationTypes.ColorFlow); + break; + } + } + + public void setColors() { + changeAnimation(AnimationTypes.SetAll); + } + + public void changeAnimation(AnimationTypes toChange) { + m_currentAnimation = toChange; + + // switch(toChange) + // { + // case ColorFlow: + // m_toAnimate = new ColorFlowAnimation(128, 20, 70, 0, 0.7, LedCount, + // Direction.Forward); + // break; + // case Fire: + // m_toAnimate = new FireAnimation(0.5, 0.7, LedCount, 0.7, 0.5); + // break; + // case Larson: + // m_toAnimate = new LarsonAnimation(0, 255, 46, 0, 1, LedCount, BounceMode.Front, 3); + // break; + // case Rainbow: + // m_toAnimate = new RainbowAnimation(1, 0.1, LedCount); + // break; + // case RgbFade: + // m_toAnimate = new RgbFadeAnimation(0.7, 0.4, LedCount); + // break; + // case SingleFade: + // m_toAnimate = new SingleFadeAnimation(50, 2, 200, 0, 0.5, LedCount); + // break; + // case Strobe: + // m_toAnimate = new StrobeAnimation(240, 10, 180, 0, 98.0 / 256.0, LedCount); + // break; + // case Twinkle: + // m_toAnimate = new TwinkleAnimation(30, 70, 60, 0, 0.4, LedCount, + // TwinklePercent.Percent6); + // break; + // case TwinkleOff: + // m_toAnimate = new TwinkleOffAnimation(70, 90, 175, 0, 0.8, LedCount, + // TwinkleOffPercent.Percent100); + // break; + // case SetAll: + // m_toAnimate = null; + // break; + // } + // System.out.println("Changed to " + m_currentAnimation.toString()); + } + + @Override + public void periodic() { + // This method will be called once per scheduler run + // SolidColor request = new SolidColor(0, 67); + // request.withColor(new RGBWColor(0, 255, 0,0)); + + m_candle.setControl(new SolidColor(0, 67).withColor(new RGBWColor(0, 217, 0, 0))); + + // if(m_toAnimate == null) { + // m_candle.setLEDs((int)(joystick.getLeftTriggerAxis() * 255), + // (int)(joystick.getRightTriggerAxis() * 255), + // (int)(joystick.getLeftX() * 255)); + // } else { + // m_candle.animate(m_toAnimate); + // } + // m_candle.modulateVBatOutput(joystick.getRightY()); + } + + @Override + public void simulationPeriodic() { + // This method will be called once per scheduler run during simulation + } +} diff --git a/src/main/java/org/team2342/lib/leds/LedIO.java b/src/main/java/org/team2342/lib/leds/LedIO.java index e39d168..518f2ed 100644 --- a/src/main/java/org/team2342/lib/leds/LedIO.java +++ b/src/main/java/org/team2342/lib/leds/LedIO.java @@ -7,10 +7,10 @@ package org.team2342.lib.leds; import edu.wpi.first.wpilibj.util.Color; -import org.littletonrobotics.junction.AutoLog; +// import org.littletonrobotics.junction.AutoLog; public interface LedIO { - @AutoLog + // @AutoLog public static class LedIOInputs { public Color firstHalfColor = Color.kBlack; public Color secondHalfColor = Color.kBlack; diff --git a/src/main/java/org/team2342/lib/leds/LedIOCANdle.java b/src/main/java/org/team2342/lib/leds/LedIOCANdle.java index 68de469..edeb4de 100644 --- a/src/main/java/org/team2342/lib/leds/LedIOCANdle.java +++ b/src/main/java/org/team2342/lib/leds/LedIOCANdle.java @@ -6,11 +6,14 @@ package org.team2342.lib.leds; +import com.ctre.phoenix6.CANBus; import com.ctre.phoenix6.configs.CANdleConfiguration; +import com.ctre.phoenix6.controls.EmptyAnimation; import com.ctre.phoenix6.controls.RainbowAnimation; import com.ctre.phoenix6.controls.SolidColor; import com.ctre.phoenix6.controls.StrobeAnimation; import com.ctre.phoenix6.hardware.CANdle; +import com.ctre.phoenix6.signals.Enable5VRailValue; import com.ctre.phoenix6.signals.StripTypeValue; import edu.wpi.first.wpilibj.util.Color; import org.team2342.frc.util.PhoenixUtils; @@ -26,12 +29,15 @@ public class LedIOCANdle implements LedIO { private LedEffect secondEffect = LedEffect.OFF; public LedIOCANdle(int canId, int ledCount) { - this.candle = new CANdle(canId); + this.candle = new CANdle(canId, new CANBus("rio")); this.ledCount = ledCount; this.halfLength = ledCount / 2; CANdleConfiguration config = new CANdleConfiguration(); - config.LED.StripType = StripTypeValue.RGB; + config.LED.StripType = StripTypeValue.GRB; + config.LED.BrightnessScalar = 0.7; + config.CANdleFeatures.Enable5VRail = Enable5VRailValue.Enabled; + // config.CANdleFeatures.StatusLedWhenActive = StatusLedWhenActiveValue.Disabled; candle.getConfigurator().apply(config); } @@ -93,6 +99,7 @@ public void setEffect(Half half, LedEffect effect, Color color) { } private void sendSolidColor(int start, int end, Color color) { + candle.setControl(new EmptyAnimation(end)); SolidColor request = new SolidColor(start, end); request.withColor(PhoenixUtils.toCTREColor(color)); candle.setControl(request); @@ -101,18 +108,22 @@ private void sendSolidColor(int start, int end, Color color) { private void applyEffect(int start, int end, LedEffect effect, Color color) { switch (effect) { case SOLID -> { + candle.setControl(new EmptyAnimation(end)); sendSolidColor(start, end, color); } case FLASHING -> { + candle.setControl(new EmptyAnimation(end)); StrobeAnimation request = new StrobeAnimation(start, end); request.withColor(PhoenixUtils.toCTREColor(color)); candle.setControl(request); } case RAINBOW -> { + candle.setControl(new EmptyAnimation(end)); RainbowAnimation request = new RainbowAnimation(start, end); candle.setControl(request); } case OFF -> { + candle.setControl(new EmptyAnimation(end)); sendSolidColor(start, end, Color.kBlack); } } diff --git a/src/main/java/org/team2342/lib/leds/LedIOSim.java b/src/main/java/org/team2342/lib/leds/LedIOSim.java index 69f7372..b7ed29f 100644 --- a/src/main/java/org/team2342/lib/leds/LedIOSim.java +++ b/src/main/java/org/team2342/lib/leds/LedIOSim.java @@ -7,7 +7,6 @@ package org.team2342.lib.leds; import edu.wpi.first.wpilibj.util.Color; -import org.littletonrobotics.junction.Logger; public class LedIOSim implements LedIO { private Color firstColor = Color.kBlack; @@ -48,20 +47,20 @@ public void setEffect(Half half, LedEffect effect, Color color) { } } - @Override - public void updateInputs(LedIOInputs inputs) { - inputs.firstHalfColor = firstColor; - inputs.secondHalfColor = secondColor; - inputs.firstHalfEffect = firstEffect; - inputs.secondHalfEffect = secondEffect; + // @Override + // public void updateInputs(LedIOInputs inputs) { + // inputs.firstHalfColor = firstColor; + // inputs.secondHalfColor = secondColor; + // inputs.firstHalfEffect = firstEffect; + // inputs.secondHalfEffect = secondEffect; - Logger.recordOutput( - "LED/FirstHalf/Color", new double[] {firstColor.red, firstColor.green, firstColor.blue}); - Logger.recordOutput("LED/FirstHalf/Effect", firstEffect.name()); + // Logger.recordOutput( + // "LED/FirstHalf/Color", new double[] {firstColor.red, firstColor.green, firstColor.blue}); + // Logger.recordOutput("LED/FirstHalf/Effect", firstEffect.name()); - Logger.recordOutput( - "LED/SecondHalf/Color", - new double[] {secondColor.red, secondColor.green, secondColor.blue}); - Logger.recordOutput("LED/SecondHalf/Effect", secondEffect.name()); - } + // Logger.recordOutput( + // "LED/SecondHalf/Color", + // new double[] {secondColor.red, secondColor.green, secondColor.blue}); + // Logger.recordOutput("LED/SecondHalf/Effect", secondEffect.name()); + // } } diff --git a/src/main/java/org/team2342/lib/leds/LedStrip.java b/src/main/java/org/team2342/lib/leds/LedStrip.java index 073b696..022f34d 100644 --- a/src/main/java/org/team2342/lib/leds/LedStrip.java +++ b/src/main/java/org/team2342/lib/leds/LedStrip.java @@ -8,16 +8,15 @@ import edu.wpi.first.wpilibj.util.Color; import edu.wpi.first.wpilibj2.command.SubsystemBase; -import org.littletonrobotics.junction.Logger; import org.team2342.lib.leds.LedIO.LedEffect; -import org.team2342.lib.leds.LedIOInputsAutoLogged; +// import org.team2342.lib.leds.LedIOInputsAutoLogged; public class LedStrip extends SubsystemBase { - private final LedIO io; + private final LedIOCANdle io; private final String name; - private final LedIOInputsAutoLogged inputs = new LedIOInputsAutoLogged(); + // private final LedIOInputsAutoLogged inputs = new LedIOInputsAutoLogged(); - public LedStrip(LedIO io, String name) { + public LedStrip(LedIOCANdle io, String name) { this.io = io; this.name = name; setName(name); @@ -32,12 +31,12 @@ public void setSecond(Color color, LedEffect effect) { } public void setAll(Color color, LedEffect effect) { - io.setEffect(effect, color); + io.setEffect(LedIO.Half.ALL, effect, color); } - @Override - public void periodic() { - io.updateInputs(inputs); - Logger.processInputs(name, inputs); - } + // @Override + // public void periodic() { + // io.updateInputs(inputs); + // Logger.processInputs(name, inputs); + // } } From ae7eca65cc4e2c6d669847a675fe6ed367012f93 Mon Sep 17 00:00:00 2001 From: Phoenix2342-Bot Date: Sun, 11 Jan 2026 22:12:38 +0000 Subject: [PATCH 07/11] Auto-format code --- src/main/java/org/team2342/frc/util/PhoenixUtils.java | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/java/org/team2342/frc/util/PhoenixUtils.java b/src/main/java/org/team2342/frc/util/PhoenixUtils.java index f582675..d49b330 100644 --- a/src/main/java/org/team2342/frc/util/PhoenixUtils.java +++ b/src/main/java/org/team2342/frc/util/PhoenixUtils.java @@ -10,7 +10,6 @@ import com.ctre.phoenix6.StatusCode; import com.ctre.phoenix6.signals.RGBWColor; import edu.wpi.first.wpilibj.util.Color; - import java.util.function.Supplier; public class PhoenixUtils { @@ -52,7 +51,8 @@ public static void refreshSignals() { } /** - * Used to convert {@link edu.wpi.first.wpilibj.util.Color} to {@link com.ctre.phoenix6.signals.RGBWColor} + * Used to convert {@link edu.wpi.first.wpilibj.util.Color} to {@link + * com.ctre.phoenix6.signals.RGBWColor} * * @param c WPILib Color to be converted */ From 32de1b87547c85ef5af9e300be41ac7d91de23da Mon Sep 17 00:00:00 2001 From: abi-appusamy9932 Date: Sat, 17 Jan 2026 14:16:59 -0500 Subject: [PATCH 08/11] update() fixes --- .../org/team2342/lib/leds/LedIOCANdle.java | 31 ++++++++++++------- .../java/org/team2342/lib/leds/LedStrip.java | 17 +++++----- 2 files changed, 29 insertions(+), 19 deletions(-) diff --git a/src/main/java/org/team2342/lib/leds/LedIOCANdle.java b/src/main/java/org/team2342/lib/leds/LedIOCANdle.java index edeb4de..4a87b91 100644 --- a/src/main/java/org/team2342/lib/leds/LedIOCANdle.java +++ b/src/main/java/org/team2342/lib/leds/LedIOCANdle.java @@ -51,19 +51,23 @@ public void updateInputs(LedIOInputs inputs) { @Override public void setColor(Half half, Color color) { + if (color == null){ + color = Color.kBlack; + } + switch (half) { case FIRST -> { - sendSolidColor(0, halfLength, color); + // sendSolidColor(0, halfLength, color); firstColor = color; firstEffect = LedEffect.SOLID; } case SECOND -> { - sendSolidColor(halfLength, ledCount, color); + //sendSolidColor(halfLength, ledCount, color); secondColor = color; secondEffect = LedEffect.SOLID; } case ALL -> { - sendSolidColor(0, ledCount, color); + //sendSolidColor(0, ledCount, color); firstColor = color; secondColor = color; firstEffect = LedEffect.SOLID; @@ -79,22 +83,22 @@ public void setEffect(Half half, LedEffect effect, Color color) { } switch (half) { - case FIRST: + case FIRST -> { firstColor = color; firstEffect = effect; - applyEffect(0, halfLength, effect, color); - break; - case SECOND: + //applyEffect(0, halfLength, effect, color); + } + case SECOND -> { secondColor = color; secondEffect = effect; - applyEffect(halfLength, ledCount, effect, color); - break; - case ALL: + //applyEffect(halfLength, ledCount, effect, color); + } + case ALL -> { firstColor = color; secondColor = color; firstEffect = effect; secondEffect = effect; - break; + } } } @@ -128,4 +132,9 @@ private void applyEffect(int start, int end, LedEffect effect, Color color) { } } } + + public void update() { + applyEffect(0, halfLength, firstEffect, firstColor); + applyEffect(halfLength, ledCount, secondEffect, secondColor); + } } diff --git a/src/main/java/org/team2342/lib/leds/LedStrip.java b/src/main/java/org/team2342/lib/leds/LedStrip.java index 022f34d..1275e2f 100644 --- a/src/main/java/org/team2342/lib/leds/LedStrip.java +++ b/src/main/java/org/team2342/lib/leds/LedStrip.java @@ -13,13 +13,13 @@ public class LedStrip extends SubsystemBase { private final LedIOCANdle io; - private final String name; + // private final String name; // private final LedIOInputsAutoLogged inputs = new LedIOInputsAutoLogged(); public LedStrip(LedIOCANdle io, String name) { this.io = io; - this.name = name; - setName(name); + // this.name = name; + // setName(name); } public void setFirst(Color color, LedEffect effect) { @@ -34,9 +34,10 @@ public void setAll(Color color, LedEffect effect) { io.setEffect(LedIO.Half.ALL, effect, color); } - // @Override - // public void periodic() { - // io.updateInputs(inputs); - // Logger.processInputs(name, inputs); - // } + @Override + public void periodic() { + //io.updateInputs(inputs); + io.update(); + //Logger.processInputs(name, inputs); + } } From 8e111f8ebead05ddc9f4df9d2334b27ef97579fe Mon Sep 17 00:00:00 2001 From: Phoenix2342-Bot Date: Sat, 17 Jan 2026 19:18:38 +0000 Subject: [PATCH 09/11] Auto-format code --- src/main/java/org/team2342/lib/leds/LedIOCANdle.java | 10 +++++----- src/main/java/org/team2342/lib/leds/LedStrip.java | 4 ++-- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/main/java/org/team2342/lib/leds/LedIOCANdle.java b/src/main/java/org/team2342/lib/leds/LedIOCANdle.java index 4a87b91..7c565b6 100644 --- a/src/main/java/org/team2342/lib/leds/LedIOCANdle.java +++ b/src/main/java/org/team2342/lib/leds/LedIOCANdle.java @@ -51,7 +51,7 @@ public void updateInputs(LedIOInputs inputs) { @Override public void setColor(Half half, Color color) { - if (color == null){ + if (color == null) { color = Color.kBlack; } @@ -62,12 +62,12 @@ public void setColor(Half half, Color color) { firstEffect = LedEffect.SOLID; } case SECOND -> { - //sendSolidColor(halfLength, ledCount, color); + // sendSolidColor(halfLength, ledCount, color); secondColor = color; secondEffect = LedEffect.SOLID; } case ALL -> { - //sendSolidColor(0, ledCount, color); + // sendSolidColor(0, ledCount, color); firstColor = color; secondColor = color; firstEffect = LedEffect.SOLID; @@ -86,12 +86,12 @@ public void setEffect(Half half, LedEffect effect, Color color) { case FIRST -> { firstColor = color; firstEffect = effect; - //applyEffect(0, halfLength, effect, color); + // applyEffect(0, halfLength, effect, color); } case SECOND -> { secondColor = color; secondEffect = effect; - //applyEffect(halfLength, ledCount, effect, color); + // applyEffect(halfLength, ledCount, effect, color); } case ALL -> { firstColor = color; diff --git a/src/main/java/org/team2342/lib/leds/LedStrip.java b/src/main/java/org/team2342/lib/leds/LedStrip.java index 1275e2f..1d45d1c 100644 --- a/src/main/java/org/team2342/lib/leds/LedStrip.java +++ b/src/main/java/org/team2342/lib/leds/LedStrip.java @@ -36,8 +36,8 @@ public void setAll(Color color, LedEffect effect) { @Override public void periodic() { - //io.updateInputs(inputs); + // io.updateInputs(inputs); io.update(); - //Logger.processInputs(name, inputs); + // Logger.processInputs(name, inputs); } } From c6fa5f86aa2ffb6c16cec4a9d5aa39880cc0ef7f Mon Sep 17 00:00:00 2001 From: abi-appusamy9932 Date: Sat, 17 Jan 2026 16:17:48 -0500 Subject: [PATCH 10/11] more candle --- src/main/java/org/team2342/frc/Robot.java | 6 +-- .../java/org/team2342/frc/RobotContainer.java | 11 ++++- .../org/team2342/lib/leds/LedIOCANdle.java | 40 ++++++++++++++----- .../java/org/team2342/lib/leds/LedStrip.java | 9 +++-- 4 files changed, 48 insertions(+), 18 deletions(-) diff --git a/src/main/java/org/team2342/frc/Robot.java b/src/main/java/org/team2342/frc/Robot.java index 9b4b3ff..b0ebd61 100644 --- a/src/main/java/org/team2342/frc/Robot.java +++ b/src/main/java/org/team2342/frc/Robot.java @@ -30,7 +30,7 @@ import org.littletonrobotics.junction.networktables.NT4Publisher; import org.littletonrobotics.junction.wpilog.WPILOGReader; import org.littletonrobotics.junction.wpilog.WPILOGWriter; -import org.team2342.frc.subsystems.CANdleSystem.CANdleSystem; +// import org.team2342.frc.subsystems.CANdleSystem.CANdleSystem; import org.team2342.frc.util.PhoenixUtils; import org.team2342.lib.fsm.StateMachine; import org.team2342.lib.logging.ExecutionLogger; @@ -38,7 +38,7 @@ public class Robot extends LoggedRobot { private Command autonomousCommand; private static final double loopOverrunWarningTimeout = 0.2; - private final CANdleSystem candle = new CANdleSystem(null); + // private final CANdleSystem candle = new CANdleSystem(null); private final RobotContainer robotContainer; @@ -190,7 +190,7 @@ public void robotPeriodic() { machine.requestTransition(testStates.STATE_3); machine.periodic(); ExecutionLogger.log("RobotPeriodic"); - candle.periodic(); + // candle.periodic(); } @Override diff --git a/src/main/java/org/team2342/frc/RobotContainer.java b/src/main/java/org/team2342/frc/RobotContainer.java index bdea760..a02c1fe 100644 --- a/src/main/java/org/team2342/frc/RobotContainer.java +++ b/src/main/java/org/team2342/frc/RobotContainer.java @@ -16,6 +16,7 @@ import edu.wpi.first.wpilibj.Alert.AlertType; import edu.wpi.first.wpilibj.PowerDistribution.ModuleType; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; +import edu.wpi.first.wpilibj.util.Color; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; @@ -40,13 +41,15 @@ import org.team2342.frc.subsystems.vision.VisionIOConstrainedSim; import org.team2342.frc.subsystems.vision.VisionIOPhoton; import org.team2342.frc.subsystems.vision.VisionIOSim; +import org.team2342.lib.leds.*; +import org.team2342.lib.leds.LedIO.LedEffect; public class RobotContainer { @Getter private final Drive drive; @Getter private final Vision vision; - // public final LedIOCANdle candle = new LedIOCANdle(22, 37); - // public final LedStrip leds = new LedStrip(candle, "leds"); + public final LedIOCANdle candle = new LedIOCANdle(22, 37); + public final LedStrip leds = new LedStrip(candle, "leds"); private final LoggedDashboardChooser autoChooser; @@ -159,6 +162,10 @@ private void configureBindings() { drive::getPose, () -> -driverController.getLeftY(), () -> -driverController.getLeftX())); + + leds.setFirst(Color.kRed, LedEffect.FLASHING); + leds.setSecond(Color.kBlue, LedEffect.RAINBOW); + // leds.setAll(Color.kGreen, LedEffect.RAINBOW); } public Command getAutonomousCommand() { diff --git a/src/main/java/org/team2342/lib/leds/LedIOCANdle.java b/src/main/java/org/team2342/lib/leds/LedIOCANdle.java index 7c565b6..c47706a 100644 --- a/src/main/java/org/team2342/lib/leds/LedIOCANdle.java +++ b/src/main/java/org/team2342/lib/leds/LedIOCANdle.java @@ -22,6 +22,10 @@ public class LedIOCANdle implements LedIO { private final CANdle candle; private final int ledCount; private final int halfLength; + private int startFirst = 0; + private int endFirst; + private int startSecond; + private int endSecond; private Color firstColor = Color.kBlack; private Color secondColor = Color.kBlack; @@ -86,18 +90,24 @@ public void setEffect(Half half, LedEffect effect, Color color) { case FIRST -> { firstColor = color; firstEffect = effect; - // applyEffect(0, halfLength, effect, color); + startFirst = 0; + endFirst = halfLength; } case SECOND -> { secondColor = color; secondEffect = effect; - // applyEffect(halfLength, ledCount, effect, color); + startSecond = halfLength; + endSecond = ledCount; } case ALL -> { firstColor = color; secondColor = color; firstEffect = effect; secondEffect = effect; + startFirst = 0; + endFirst = halfLength; + startSecond = halfLength; + endSecond = ledCount; } } } @@ -112,29 +122,39 @@ private void sendSolidColor(int start, int end, Color color) { private void applyEffect(int start, int end, LedEffect effect, Color color) { switch (effect) { case SOLID -> { - candle.setControl(new EmptyAnimation(end)); + // candle.setControl(new EmptyAnimation(end)); sendSolidColor(start, end, color); } case FLASHING -> { - candle.setControl(new EmptyAnimation(end)); - StrobeAnimation request = new StrobeAnimation(start, end); + // candle.setControl(new EmptyAnimation(end)); + StrobeAnimation request = new StrobeAnimation(start, end).withSlot(1); request.withColor(PhoenixUtils.toCTREColor(color)); candle.setControl(request); } case RAINBOW -> { - candle.setControl(new EmptyAnimation(end)); - RainbowAnimation request = new RainbowAnimation(start, end); + // candle.setControl(new EmptyAnimation(end)); + RainbowAnimation request = new RainbowAnimation(start, end).withSlot(0); candle.setControl(request); } case OFF -> { - candle.setControl(new EmptyAnimation(end)); + // candle.setControl(new EmptyAnimation(end)); sendSolidColor(start, end, Color.kBlack); } } } + public void clearAll() { + sendSolidColor(0, ledCount, Color.kBlack); + for (int i = 0; i < ledCount; ++i) { + candle.setControl(new EmptyAnimation(i)); + } + } + public void update() { - applyEffect(0, halfLength, firstEffect, firstColor); - applyEffect(halfLength, ledCount, secondEffect, secondColor); + clearAll(); + applyEffect(startFirst, endFirst, firstEffect, firstColor); + applyEffect(startSecond, endSecond, secondEffect, secondColor); + // applyEffect(startSecond, endSecond, secondEffect, secondColor); + } } diff --git a/src/main/java/org/team2342/lib/leds/LedStrip.java b/src/main/java/org/team2342/lib/leds/LedStrip.java index 1d45d1c..98ce33e 100644 --- a/src/main/java/org/team2342/lib/leds/LedStrip.java +++ b/src/main/java/org/team2342/lib/leds/LedStrip.java @@ -24,20 +24,23 @@ public LedStrip(LedIOCANdle io, String name) { public void setFirst(Color color, LedEffect effect) { io.setEffect(LedIO.Half.FIRST, effect, color); + io.update(); } public void setSecond(Color color, LedEffect effect) { io.setEffect(LedIO.Half.SECOND, effect, color); + io.update(); } public void setAll(Color color, LedEffect effect) { io.setEffect(LedIO.Half.ALL, effect, color); + io.update(); } @Override public void periodic() { - // io.updateInputs(inputs); - io.update(); - // Logger.processInputs(name, inputs); + //io.updateInputs(inputs); + //io.update(); + //Logger.processInputs(name, inputs); } } From 2a9c0755e3be5dd4c89e3acbb78989df7d5f41a4 Mon Sep 17 00:00:00 2001 From: Phoenix2342-Bot Date: Thu, 22 Jan 2026 23:42:46 +0000 Subject: [PATCH 11/11] Auto-format code --- .../java/org/team2342/lib/leds/LedStrip.java | 6 +- vendordeps/Phoenix6-26.1.0.json | 896 +++++++++--------- 2 files changed, 451 insertions(+), 451 deletions(-) diff --git a/src/main/java/org/team2342/lib/leds/LedStrip.java b/src/main/java/org/team2342/lib/leds/LedStrip.java index 98ce33e..bc9cf58 100644 --- a/src/main/java/org/team2342/lib/leds/LedStrip.java +++ b/src/main/java/org/team2342/lib/leds/LedStrip.java @@ -39,8 +39,8 @@ public void setAll(Color color, LedEffect effect) { @Override public void periodic() { - //io.updateInputs(inputs); - //io.update(); - //Logger.processInputs(name, inputs); + // io.updateInputs(inputs); + // io.update(); + // Logger.processInputs(name, inputs); } } diff --git a/vendordeps/Phoenix6-26.1.0.json b/vendordeps/Phoenix6-26.1.0.json index dc5dc62..5d2d04d 100644 --- a/vendordeps/Phoenix6-26.1.0.json +++ b/vendordeps/Phoenix6-26.1.0.json @@ -1,449 +1,449 @@ { - "fileName": "Phoenix6-26.1.0.json", - "name": "CTRE-Phoenix (v6)", - "version": "26.1.0", - "frcYear": "2026", - "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", - "mavenUrls": [ - "https://maven.ctr-electronics.com/release/" - ], - "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2026-latest.json", - "conflictsWith": [ - { - "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af", - "errorMessage": "Users can not have both the replay and regular Phoenix 6 vendordeps in their robot program.", - "offlineFileName": "Phoenix6-replay-frc2026-latest.json" - } - ], - "javaDependencies": [ - { - "groupId": "com.ctre.phoenix6", - "artifactId": "wpiapi-java", - "version": "26.1.0" - } - ], - "jniDependencies": [ - { - "groupId": "com.ctre.phoenix6", - "artifactId": "api-cpp", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6", - "artifactId": "tools", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "api-cpp-sim", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "tools-sim", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simTalonSRX", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simVictorSPX", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simPigeonIMU", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProTalonFX", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProTalonFXS", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANcoder", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProPigeon2", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANrange", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANdi", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANdle", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - } - ], - "cppDependencies": [ - { - "groupId": "com.ctre.phoenix6", - "artifactId": "wpiapi-cpp", - "version": "26.1.0", - "libName": "CTRE_Phoenix6_WPI", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6", - "artifactId": "tools", - "version": "26.1.0", - "libName": "CTRE_PhoenixTools", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "wpiapi-cpp-sim", - "version": "26.1.0", - "libName": "CTRE_Phoenix6_WPISim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "tools-sim", - "version": "26.1.0", - "libName": "CTRE_PhoenixTools_Sim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simTalonSRX", - "version": "26.1.0", - "libName": "CTRE_SimTalonSRX", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simVictorSPX", - "version": "26.1.0", - "libName": "CTRE_SimVictorSPX", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simPigeonIMU", - "version": "26.1.0", - "libName": "CTRE_SimPigeonIMU", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProTalonFX", - "version": "26.1.0", - "libName": "CTRE_SimProTalonFX", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProTalonFXS", - "version": "26.1.0", - "libName": "CTRE_SimProTalonFXS", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANcoder", - "version": "26.1.0", - "libName": "CTRE_SimProCANcoder", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProPigeon2", - "version": "26.1.0", - "libName": "CTRE_SimProPigeon2", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANrange", - "version": "26.1.0", - "libName": "CTRE_SimProCANrange", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANdi", - "version": "26.1.0", - "libName": "CTRE_SimProCANdi", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANdle", - "version": "26.1.0", - "libName": "CTRE_SimProCANdle", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - } - ] -} \ No newline at end of file + "fileName": "Phoenix6-26.1.0.json", + "name": "CTRE-Phoenix (v6)", + "version": "26.1.0", + "frcYear": "2026", + "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", + "mavenUrls": [ + "https://maven.ctr-electronics.com/release/" + ], + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2026-latest.json", + "conflictsWith": [ + { + "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af", + "errorMessage": "Users can not have both the replay and regular Phoenix 6 vendordeps in their robot program.", + "offlineFileName": "Phoenix6-replay-frc2026-latest.json" + } + ], + "javaDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "wpiapi-java", + "version": "26.1.0" + } + ], + "jniDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "api-cpp", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "api-cpp-sim", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "tools-sim", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonSRX", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simVictorSPX", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simPigeonIMU", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFX", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFXS", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANcoder", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProPigeon2", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANrange", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANdi", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANdle", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + } + ], + "cppDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "wpiapi-cpp", + "version": "26.1.0", + "libName": "CTRE_Phoenix6_WPI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", + "version": "26.1.0", + "libName": "CTRE_PhoenixTools", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "wpiapi-cpp-sim", + "version": "26.1.0", + "libName": "CTRE_Phoenix6_WPISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "tools-sim", + "version": "26.1.0", + "libName": "CTRE_PhoenixTools_Sim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonSRX", + "version": "26.1.0", + "libName": "CTRE_SimTalonSRX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simVictorSPX", + "version": "26.1.0", + "libName": "CTRE_SimVictorSPX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simPigeonIMU", + "version": "26.1.0", + "libName": "CTRE_SimPigeonIMU", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFX", + "version": "26.1.0", + "libName": "CTRE_SimProTalonFX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFXS", + "version": "26.1.0", + "libName": "CTRE_SimProTalonFXS", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANcoder", + "version": "26.1.0", + "libName": "CTRE_SimProCANcoder", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProPigeon2", + "version": "26.1.0", + "libName": "CTRE_SimProPigeon2", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANrange", + "version": "26.1.0", + "libName": "CTRE_SimProCANrange", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANdi", + "version": "26.1.0", + "libName": "CTRE_SimProCANdi", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANdle", + "version": "26.1.0", + "libName": "CTRE_SimProCANdle", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + } + ] +}