From: iefomit Date: Sat, 7 Mar 2026 19:23:57 +0000 (-0800) Subject: Merge branch 'main' into week-2-merge-260307-2 X-Git-Url: https://git.taranathan.com/?a=commitdiff_plain;h=ec1aac561de5751a6fb4ca7d5be60d2c56902510;p=FRC2026.git Merge branch 'main' into week-2-merge-260307-2 tested on the bot, approved by sam --- diff --git a/src/main/java/frc/robot/ClimbCommand.java b/src/main/java/frc/robot/ClimbCommand.java deleted file mode 100644 index 3a78464..0000000 --- a/src/main/java/frc/robot/ClimbCommand.java +++ /dev/null @@ -1,5 +0,0 @@ -package frc.robot; - -public class ClimbCommand { - -} diff --git a/src/main/java/frc/robot/commands/gpm/Superstructure.java b/src/main/java/frc/robot/commands/gpm/Superstructure.java index bdffb1b..255e1b3 100644 --- a/src/main/java/frc/robot/commands/gpm/Superstructure.java +++ b/src/main/java/frc/robot/commands/gpm/Superstructure.java @@ -120,8 +120,7 @@ public class Superstructure extends Command { goalState = ShooterPhysics.getShotParams( Translation2d.kZero, target3d.minus(lookahead3d), - target == FieldConstants.getHubTranslation().toTranslation2d() ? - 2.0 : 2.0); + 2.0); double TOFAdjustment = 0.85; timeOfFlight = goalState.timeOfFlight() * TOFAdjustment; diff --git a/src/main/java/frc/robot/constants/FieldConstants.java b/src/main/java/frc/robot/constants/FieldConstants.java index 2f33c89..9a91454 100644 --- a/src/main/java/frc/robot/constants/FieldConstants.java +++ b/src/main/java/frc/robot/constants/FieldConstants.java @@ -190,10 +190,7 @@ public class FieldConstants { * @return Whether Y coordinate is in the upper half (left side on blue alliance) */ public static boolean isOnLeftSideOfField(Translation2d drivepose){ - if (drivepose.getY() > FIELD_WIDTH/2){ - return true; - } - return false; + return drivepose.getY() > FIELD_WIDTH/2; } public static Translation3d getOppositionTranslation(boolean sideLeft) { diff --git a/src/main/java/frc/robot/controls/GameControllerDriverConfig.java b/src/main/java/frc/robot/controls/GameControllerDriverConfig.java index e21c1eb..9c1fdbd 100644 --- a/src/main/java/frc/robot/controls/GameControllerDriverConfig.java +++ b/src/main/java/frc/robot/controls/GameControllerDriverConfig.java @@ -77,5 +77,4 @@ public class GameControllerDriverConfig extends BaseDriverConfig { public GameController getGameController() { return driver; } - } diff --git a/src/main/java/frc/robot/controls/PS5ControllerDriverConfig.java b/src/main/java/frc/robot/controls/PS5ControllerDriverConfig.java index 1364d12..81b70d8 100644 --- a/src/main/java/frc/robot/controls/PS5ControllerDriverConfig.java +++ b/src/main/java/frc/robot/controls/PS5ControllerDriverConfig.java @@ -8,9 +8,7 @@ import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.CommandScheduler; import edu.wpi.first.wpilibj2.command.FunctionalCommand; import edu.wpi.first.wpilibj2.command.InstantCommand; -import edu.wpi.first.wpilibj2.command.SequentialCommandGroup; import edu.wpi.first.wpilibj2.command.StartEndCommand; -import edu.wpi.first.wpilibj2.command.WaitCommand; import frc.robot.Robot; import frc.robot.commands.gpm.ClimbDriveCommand; import frc.robot.commands.gpm.IntakeMovementCommand; @@ -113,7 +111,7 @@ public class PS5ControllerDriverConfig extends BaseDriverConfig { } }, intake)); - // Retract if hold for 3 seconds + // Retract if hold for 2 seconds controller.get(PS5Button.RIGHT_TRIGGER).debounce(2.0).onTrue(new InstantCommand(() -> { intake.retract(); intakeBoolean = true; @@ -139,6 +137,7 @@ public class PS5ControllerDriverConfig extends BaseDriverConfig { // Spindexer if (spindexer != null) { + // Toggle spindexer controller.get(PS5Button.LEFT_TRIGGER).toggleOnTrue( new RunSpindexer(spindexer, turret) @@ -168,12 +167,8 @@ public class PS5ControllerDriverConfig extends BaseDriverConfig { climb.retract(); })); - // Drive to climb position and rumble - controller.get(PS5Button.TRIANGLE).onTrue(new SequentialCommandGroup( - new ClimbDriveCommand(climb, getDrivetrain()), - new InstantCommand(() -> this.startRumble()), - new WaitCommand(1), - new InstantCommand(() -> this.endRumble()))); + // Drive to climb position + controller.get(PS5Button.TRIANGLE).onTrue(new ClimbDriveCommand(climb, getDrivetrain())); } // Hood @@ -228,12 +223,4 @@ public class PS5ControllerDriverConfig extends BaseDriverConfig { public boolean getIsAlign() { return false; } - - public void startRumble() { - controller.rumbleOn(); - } - - public void endRumble() { - controller.rumbleOff(); - } } diff --git a/src/main/java/frc/robot/controls/PS5XboxModeDriverConfig.java b/src/main/java/frc/robot/controls/PS5XboxModeDriverConfig.java new file mode 100644 index 0000000..af8a0f8 --- /dev/null +++ b/src/main/java/frc/robot/controls/PS5XboxModeDriverConfig.java @@ -0,0 +1,266 @@ +package frc.robot.controls; + +import java.util.function.BooleanSupplier; + +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.wpilibj.DriverStation.Alliance; +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.CommandScheduler; +import edu.wpi.first.wpilibj2.command.FunctionalCommand; +import edu.wpi.first.wpilibj2.command.InstantCommand; +import edu.wpi.first.wpilibj2.command.SequentialCommandGroup; +import edu.wpi.first.wpilibj2.command.WaitCommand; +import frc.robot.Robot; +import frc.robot.commands.gpm.AutoShootCommand; +import frc.robot.commands.gpm.ClimbDriveCommand; +import frc.robot.commands.gpm.ReverseMotors; +import frc.robot.constants.Constants; +import frc.robot.subsystems.Climb.LinearClimb; +import frc.robot.subsystems.drivetrain.Drivetrain; +import frc.robot.subsystems.hood.Hood; +import frc.robot.subsystems.Intake.Intake; +import frc.robot.subsystems.shooter.Shooter; +import frc.robot.subsystems.spindexer.Spindexer; +import frc.robot.subsystems.turret.Turret; +import lib.controllers.GameController; +import lib.controllers.GameController.Axis; +import lib.controllers.GameController.Button; +import lib.controllers.GameController.DPad; + +/** + * Driver config for PS5 controllers using Xbox 360 emulation mode. + * This lets SCUF and other PS5 controllers work with WPILib rumble. + * + * Setup: + * - download DSX (https://dualsensex.com/download/) + * - install ViGEmBus driver (if app doesn't auto prompt) + * - in dsx, set "controller emulation" to Xbox 360 + * - ensure rumble is enabled in dsx settings + * - once code is depoloyed, change controller to "Xbox 360" in driverstation + */ + +public class PS5XboxModeDriverConfig extends BaseDriverConfig { + private final GameController controller = new GameController(Constants.DRIVER_JOY); + private final BooleanSupplier slowModeSupplier = () -> false; + private boolean intakeBoolean = true; + private Command autoShoot = null; + private Command reverseMotors = null; + private Shooter shooter; + private Turret turret; + private Hood hood; + private Intake intake; + private Spindexer spindexer; + private LinearClimb climb; + + // PS5 button aliases + private final Button CROSS = Button.A; + private final Button CIRCLE = Button.B; + private final Button SQUARE = Button.X; + private final Button TRIANGLE = Button.Y; + private final Button LB = Button.LB; + private final Button RB = Button.RB; + private final Button CREATE = Button.BACK; + private final Button OPTIONS = Button.START; + private final Button LEFT_JOY = Button.LEFT_JOY; + private final Button RIGHT_JOY = Button.RIGHT_JOY; + + // PS5 trigger buttons + private final BooleanSupplier LEFT_TRIGGER_BUTTON = controller.LEFT_TRIGGER_BUTTON; + private final BooleanSupplier RIGHT_TRIGGER_BUTTON = controller.RIGHT_TRIGGER_BUTTON; + + // PS5 axis aliases + private final Axis LEFT_X = Axis.LEFT_X; + private final Axis LEFT_Y = Axis.LEFT_Y; + private final Axis RIGHT_X = Axis.RIGHT_X; + private final Axis RIGHT_Y = Axis.RIGHT_Y; + private final Axis LEFT_TRIGGER = Axis.LEFT_TRIGGER; + private final Axis RIGHT_TRIGGER = Axis.RIGHT_TRIGGER; + + public PS5XboxModeDriverConfig( + Drivetrain drive, + Shooter shooter, + Turret turret, + Hood hood, + Intake intake, + Spindexer spindexer, + LinearClimb climb) { + super(drive); + this.shooter = shooter; + this.turret = turret; + this.hood = hood; + this.intake = intake; + this.spindexer = spindexer; + this.climb = climb; + } + + public void configureControls() { + // Reset the yaw. Mainly useful for testing/driver practice + controller.get(CREATE).onTrue(new InstantCommand(() -> getDrivetrain().setYaw( + new Rotation2d(Robot.getAlliance() == Alliance.Blue ? 0 : Math.PI)))); + + // Cancel commands + controller.get(RB).onTrue(new InstantCommand(() -> { + getDrivetrain().setIsAlign(false); + getDrivetrain().setDesiredPose(() -> null); + CommandScheduler.getInstance().cancelAll(); + })); + + // Align wheels + controller.get(DPad.RIGHT).onTrue(new FunctionalCommand( + () -> getDrivetrain().setStateDeadband(false), + getDrivetrain()::alignWheels, + interrupted -> getDrivetrain().setStateDeadband(true), + () -> false, getDrivetrain()).withTimeout(2)); + + // Trench align + controller.get(DPad.LEFT).onTrue(new InstantCommand(() -> { + getDrivetrain().setTrenchAssist(true); + getDrivetrain().setTrenchAlign(true); + })) + .onFalse(new InstantCommand(() -> { + getDrivetrain().setTrenchAssist(false); + getDrivetrain().setTrenchAlign(false); + })); + + // Reverse motors + if (intake != null && spindexer != null && shooter != null) { + controller.get(CIRCLE).onTrue(new InstantCommand(() -> { + reverseMotors = new ReverseMotors(intake, spindexer); + CommandScheduler.getInstance().schedule(reverseMotors); + })).onFalse(new InstantCommand(() -> { + if (reverseMotors != null) { + reverseMotors.cancel(); + } + })); + } + + // Intake + if (intake != null) { + // Toggle intake + controller.get(RIGHT_TRIGGER_BUTTON).onTrue(new InstantCommand(() -> { + if (intakeBoolean) { + intake.extend(); + intake.spinStart(); + intakeBoolean = false; + } else { + intake.intermediateExtend(); + intake.spinStop(); + intakeBoolean = true; + } + })); + + // Retract if hold for 3 seconds + controller.get(RIGHT_TRIGGER_BUTTON).debounce(3.0).onTrue(new InstantCommand(() -> { + intake.retract(); + intakeBoolean = true; + })); + + // Calibration + controller.get(LEFT_JOY).onTrue(new InstantCommand(() -> { + intake.calibrate(); + })).onFalse(new InstantCommand(() -> { + intake.stopCalibrating(); + })); + } + + // Spindexer + if (spindexer != null) { + // Will only run if we are not calling default shoot command + controller.get(LEFT_TRIGGER_BUTTON).onTrue(new InstantCommand(() -> spindexer.maxSpindexer())) + .onFalse(new InstantCommand(() -> spindexer.stopSpindexer())); + } + + // Auto shoot + if (turret != null && hood != null && shooter != null) { + controller.get(SQUARE).onTrue( + new InstantCommand(() -> { + if (autoShoot != null && autoShoot.isScheduled()) { + autoShoot.cancel(); + } else { + autoShoot = new AutoShootCommand(turret, getDrivetrain(), hood, shooter, spindexer); + CommandScheduler.getInstance().schedule(autoShoot); + } + })); + } + + // Climb + if (climb != null) { + // Calibration + controller.get(OPTIONS).onTrue(new InstantCommand(() -> { + climb.hardstopCalibration(); + })).onFalse(new InstantCommand(() -> { + climb.stopCalibrating(); + })); + + // Climb retract + controller.get(CROSS).onTrue(new InstantCommand(() -> { + climb.retract(); + })); + + // Drive to climb position and rumble + controller.get(TRIANGLE).onTrue(new SequentialCommandGroup( + new ClimbDriveCommand(climb, getDrivetrain()), + new InstantCommand(() -> this.startRumble()), + new WaitCommand(1), + new InstantCommand(() -> this.endRumble()))); + } + + // Hood + if (hood != null) { + controller.get(LEFT_JOY).onTrue(new InstantCommand(() -> { + hood.calibrate(); + })).onFalse(new InstantCommand(() -> { + hood.stopCalibrating(); + })); + } + + // Rumble test + controller.get(RIGHT_JOY).onTrue(new SequentialCommandGroup( + new InstantCommand(() -> controller.setRumble(GameController.RumbleStatus.RUMBLE_ON)), + new WaitCommand(0.5), + new InstantCommand(() -> controller.setRumble(GameController.RumbleStatus.RUMBLE_OFF)))); + } + + @Override + public double getRawSideTranslation() { + return controller.get(LEFT_X); + } + + @Override + public double getRawForwardTranslation() { + return controller.get(LEFT_Y); + } + + @Override + public double getRawRotation() { + return controller.get(RIGHT_X); + } + + @Override + public double getRawHeadingAngle() { + return Math.atan2(controller.get(RIGHT_X), -controller.get(RIGHT_Y)) - Math.PI / 2; + } + + @Override + public double getRawHeadingMagnitude() { + return Math.hypot(controller.get(RIGHT_X), controller.get(RIGHT_Y)); + } + + @Override + public boolean getIsSlowMode() { + return slowModeSupplier.getAsBoolean(); + } + + @Override + public boolean getIsAlign() { + return false; + } + + public void startRumble() { + controller.setRumble(GameController.RumbleStatus.RUMBLE_ON); + } + + public void endRumble() { + controller.setRumble(GameController.RumbleStatus.RUMBLE_OFF); + } +} diff --git a/src/main/java/frc/robot/subsystems/Climb/LinearClimb.java b/src/main/java/frc/robot/subsystems/Climb/LinearClimb.java index 9667a77..163f253 100644 --- a/src/main/java/frc/robot/subsystems/Climb/LinearClimb.java +++ b/src/main/java/frc/robot/subsystems/Climb/LinearClimb.java @@ -73,9 +73,6 @@ public class LinearClimb extends SubsystemBase implements LinearClimbIO{ * @param setpoint in rotations */ public void setSetpoint(double setpoint) { - TalonFXConfiguration config = new TalonFXConfiguration(); - config.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; - motor.getConfigurator().apply(config); pid.setSetpoint(setpoint); } diff --git a/src/main/java/frc/robot/subsystems/Intake/Intake.java b/src/main/java/frc/robot/subsystems/Intake/Intake.java index ca0a840..7721f50 100644 --- a/src/main/java/frc/robot/subsystems/Intake/Intake.java +++ b/src/main/java/frc/robot/subsystems/Intake/Intake.java @@ -230,15 +230,6 @@ public class Intake extends SubsystemBase implements IntakeIO{ * @param setpoint in inches */ public void setPosition(double setpoint) { - leftMotor.getConfigurator().apply( - new MotorOutputConfigs().withInverted(InvertedValue.Clockwise_Positive) - .withNeutralMode(NeutralModeValue.Coast) - ); - - rightMotor.getConfigurator().apply( - new MotorOutputConfigs().withNeutralMode(NeutralModeValue.Coast) - ); - double motorRotations = inchesToRotations(setpoint); rightMotor.setControl(voltageRequest.withPosition(motorRotations)); leftMotor.setControl(voltageRequest.withPosition(motorRotations)); diff --git a/src/main/java/frc/robot/util/HubActive.java b/src/main/java/frc/robot/util/HubActive.java new file mode 100644 index 0000000..dd5b762 --- /dev/null +++ b/src/main/java/frc/robot/util/HubActive.java @@ -0,0 +1,149 @@ +package frc.robot.util; + +import java.util.Optional; + +import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.wpilibj.DriverStation.Alliance; + +public class HubActive { + + static public boolean isHubActive() { + Optional alliance = DriverStation.getAlliance(); + // If we have no alliance, we cannot be enabled, therefore no hub. + if (alliance.isEmpty()) { + return false; + } + // Hub is always enabled in autonomous. + if (DriverStation.isAutonomousEnabled()) { + return true; + } + // At this point, if we're not teleop enabled, there is no hub. + if (!DriverStation.isTeleopEnabled()) { + return false; + } + + // We're teleop enabled, compute. + double matchTime = DriverStation.getMatchTime(); + String gameData = DriverStation.getGameSpecificMessage(); + // If we have no game data, we cannot compute, assume hub is active, as its + // likely early in teleop. + if (gameData.isEmpty()) { + return true; + } + boolean redInactiveFirst = false; + switch (gameData.charAt(0)) { + case 'R' -> redInactiveFirst = true; + case 'B' -> redInactiveFirst = false; + default -> { + // If we have invalid game data, assume hub is active. + return true; + } + } + + // Shift was is active for blue if red won auto, or red if blue won auto. + boolean shift1Active = switch (alliance.get()) { + case Red -> !redInactiveFirst; + case Blue -> redInactiveFirst; + }; + + if (matchTime > 130) { + // Transition shift, hub is active. + return true; + } else if (matchTime > 105) { + // Shift 1 + return shift1Active; + } else if (matchTime > 80) { + // Shift 2 + return !shift1Active; + } else if (matchTime > 55) { + // Shift 3 + return shift1Active; + } else if (matchTime > 30) { + // Shift 4 + return !shift1Active; + } else { + // End game, hub always active. + return true; + } + } + + static public Optional timeToActive() { + + Optional alliance = DriverStation.getAlliance(); + // If we have no alliance, we cannot be enabled, therefore no hub. + if (alliance.isEmpty()) { + return Optional.empty(); + } + // Hub is always enabled in autonomous. + if (DriverStation.isAutonomousEnabled()) { + return Optional.of(0.0); + } + // At this point, if we're not teleop enabled, there is no hub. + if (!DriverStation.isTeleopEnabled()) { + return Optional.empty(); + } + + // We're teleop enabled, compute. + double matchTime = DriverStation.getMatchTime(); + String gameData = DriverStation.getGameSpecificMessage(); + // If we have no game data, we cannot compute, assume hub is active, as its + // likely early in teleop. + if (gameData.isEmpty()) { + return Optional.of(0.0); + } + boolean redInactiveFirst = false; + switch (gameData.charAt(0)) { + case 'R' -> redInactiveFirst = true; + case 'B' -> redInactiveFirst = false; + default -> { + // If we have invalid game data, assume hub is active. + return Optional.of(0.0); + } + } + + // Shift was is active for blue if red won auto, or red if blue won auto. + boolean shift1Active = switch (alliance.get()) { + case Red -> !redInactiveFirst; + case Blue -> redInactiveFirst; + }; + + if (matchTime > 130) { + // Transition shift, hub is active. + return Optional.of(0.0); + } else if (matchTime > 105) { + // Shift 1 + if (shift1Active) { + return Optional.of(matchTime - 105.0); + } else { + return Optional.empty(); + } + } else if (matchTime > 80) { + // Shift 2 + + if (!shift1Active) { + return Optional.of(matchTime - 80.0); + } else { + return Optional.empty(); + } + } else if (matchTime > 55) { + // Shift 3 + + if (shift1Active) { + return Optional.of(matchTime - 55.0); + } else { + return Optional.empty(); + } + } else if (matchTime > 30) { + // Shift 4 + + if (!shift1Active) { + return Optional.of(matchTime - 30.0); + } else { + return Optional.empty(); + } + } else { + // End game, hub always active. + return Optional.of(0.0); + } + } +} diff --git a/src/main/java/lib/controllers/PS5Controller.java b/src/main/java/lib/controllers/PS5Controller.java index 8f45a52..ea65f05 100644 --- a/src/main/java/lib/controllers/PS5Controller.java +++ b/src/main/java/lib/controllers/PS5Controller.java @@ -1,7 +1,6 @@ package lib.controllers; import edu.wpi.first.wpilibj.Joystick; -import edu.wpi.first.wpilibj.GenericHID.RumbleType; import edu.wpi.first.wpilibj2.command.button.Trigger; import java.util.function.BooleanSupplier; @@ -57,11 +56,13 @@ public class PS5Controller extends Controller { LEFT_Y(1), RIGHT_X(2), /** - * note: ps5 controller trigger goes from -1 when unpressed, to 1 when fully pressed + * note: ps5 controller trigger goes from -1 when unpressed, to 1 when fully + * pressed */ LEFT_TRIGGER(3), /** - * note: ps5 controller trigger goes from -1 when unpressed, to 1 when fully pressed + * note: ps5 controller trigger goes from -1 when unpressed, to 1 when fully + * pressed */ RIGHT_TRIGGER(4), RIGHT_Y(5); @@ -106,10 +107,4 @@ public class PS5Controller extends Controller { public Joystick get() { return controller; } - public void rumbleOn(){ - controller.setRumble(RumbleType.kBothRumble,0.1); - } - public void rumbleOff(){ - controller.setRumble(RumbleType.kBothRumble,0); - } } \ No newline at end of file diff --git a/vendordeps/AdvantageKit.json b/vendordeps/AdvantageKit.json index 162ad66..868ae9d 100644 --- a/vendordeps/AdvantageKit.json +++ b/vendordeps/AdvantageKit.json @@ -1,7 +1,7 @@ { "fileName": "AdvantageKit.json", "name": "AdvantageKit", - "version": "26.0.0", + "version": "26.0.1", "uuid": "d820cc26-74e3-11ec-90d6-0242ac120003", "frcYear": "2026", "mavenUrls": [ @@ -12,14 +12,14 @@ { "groupId": "org.littletonrobotics.akit", "artifactId": "akit-java", - "version": "26.0.0" + "version": "26.0.1" } ], "jniDependencies": [ { "groupId": "org.littletonrobotics.akit", "artifactId": "akit-wpilibio", - "version": "26.0.0", + "version": "26.0.1", "skipInvalidPlatforms": false, "isJar": false, "validPlatforms": [ diff --git a/vendordeps/ChoreoLib2026.json b/vendordeps/ChoreoLib2026.json index a07c40d..4875107 100644 --- a/vendordeps/ChoreoLib2026.json +++ b/vendordeps/ChoreoLib2026.json @@ -1,44 +1,44 @@ { - "fileName": "ChoreoLib2026.json", - "name": "ChoreoLib", - "version": "2026.0.1", - "uuid": "b5e23f0a-dac9-4ad2-8dd6-02767c520aca", - "frcYear": "2026", - "mavenUrls": [ - "https://frcmaven.wpi.edu/artifactory/sleipnirgroup-mvn-release/", - "https://repo1.maven.org/maven2" - ], - "jsonUrl": "https://choreo.autos/lib/ChoreoLib2026.json", - "javaDependencies": [ - { - "groupId": "choreo", - "artifactId": "ChoreoLib-java", - "version": "2026.0.1" - }, - { - "groupId": "com.google.code.gson", - "artifactId": "gson", - "version": "2.11.0" - } - ], - "jniDependencies": [], - "cppDependencies": [ - { - "groupId": "choreo", - "artifactId": "ChoreoLib-cpp", - "version": "2026.0.1", - "libName": "ChoreoLib", - "headerClassifier": "headers", - "sharedLibrary": false, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal", - "linuxathena", - "linuxarm32", - "linuxarm64" - ] - } - ] + "fileName": "ChoreoLib2026.json", + "name": "ChoreoLib", + "version": "2026.0.2", + "uuid": "b5e23f0a-dac9-4ad2-8dd6-02767c520aca", + "frcYear": "2026", + "mavenUrls": [ + "https://frcmaven.wpi.edu/artifactory/sleipnirgroup-mvn-release/", + "https://repo1.maven.org/maven2" + ], + "jsonUrl": "https://choreo.autos/lib/ChoreoLib2026.json", + "javaDependencies": [ + { + "groupId": "choreo", + "artifactId": "ChoreoLib-java", + "version": "2026.0.2" + }, + { + "groupId": "com.google.code.gson", + "artifactId": "gson", + "version": "2.11.0" + } + ], + "jniDependencies": [], + "cppDependencies": [ + { + "groupId": "choreo", + "artifactId": "ChoreoLib-cpp", + "version": "2026.0.2", + "libName": "ChoreoLib", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal", + "linuxathena", + "linuxarm32", + "linuxarm64" + ] + } + ] } \ No newline at end of file diff --git a/vendordeps/REVLib.json b/vendordeps/REVLib.json index d8ba7ce..e8196c3 100644 --- a/vendordeps/REVLib.json +++ b/vendordeps/REVLib.json @@ -1,7 +1,7 @@ { "fileName": "REVLib.json", "name": "REVLib", - "version": "2026.0.2", + "version": "2026.0.4", "frcYear": "2026", "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", "mavenUrls": [ @@ -12,14 +12,14 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-java", - "version": "2026.0.2" + "version": "2026.0.4" } ], "jniDependencies": [ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2026.0.2", + "version": "2026.0.4", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ @@ -34,7 +34,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "RevLibBackendDriver", - "version": "2026.0.2", + "version": "2026.0.4", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ @@ -49,7 +49,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "RevLibWpiBackendDriver", - "version": "2026.0.2", + "version": "2026.0.4", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ @@ -66,7 +66,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-cpp", - "version": "2026.0.2", + "version": "2026.0.4", "libName": "REVLib", "headerClassifier": "headers", "sharedLibrary": false, @@ -83,7 +83,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2026.0.2", + "version": "2026.0.4", "libName": "REVLibDriver", "headerClassifier": "headers", "sharedLibrary": false, @@ -100,7 +100,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "RevLibBackendDriver", - "version": "2026.0.2", + "version": "2026.0.4", "libName": "BackendDriver", "sharedLibrary": true, "skipInvalidPlatforms": true, @@ -116,7 +116,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "RevLibWpiBackendDriver", - "version": "2026.0.2", + "version": "2026.0.4", "libName": "REVLibWpi", "sharedLibrary": true, "skipInvalidPlatforms": true, diff --git a/vendordeps/StudicaLib.json b/vendordeps/StudicaLib.json index 0fdd1d4..52228bd 100644 --- a/vendordeps/StudicaLib.json +++ b/vendordeps/StudicaLib.json @@ -1,13 +1,13 @@ { "fileName": "StudicaLib.json", "name": "StudicaLib", - "version": "2026.0.1", + "version": "2026.0.2", "frcYear": "2026", "uuid": "963ef341-8abd-4981-a969-c8ae3f592e82", "mavenUrls": [ "https://dev.studica.com/maven/release/2026/" ], - "jsonUrl": "https://dev.studica.com/maven/release/2026/json/StudicaLib-2026.0.1.json", + "jsonUrl": "https://dev.studica.com/maven/release/2026/json/StudicaLib-2026.0.2.json", "conflictsWith": [ { "uuid": "cb311d09-36e9-4143-a032-55bb2b94443b", @@ -19,14 +19,14 @@ { "groupId": "com.studica.frc", "artifactId": "StudicaLib-java", - "version": "2026.0.1" + "version": "2026.0.2" } ], "jniDependencies": [ { "groupId": "com.studica.frc", "artifactId": "StudicaLib-driver", - "version": "2026.0.1", + "version": "2026.0.2", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ @@ -43,7 +43,7 @@ { "groupId": "com.studica.frc", "artifactId": "StudicaLib-cpp", - "version": "2026.0.1", + "version": "2026.0.2", "libName": "StudicaLib", "headerClassifier": "headers", "sharedLibrary": false, @@ -60,7 +60,7 @@ { "groupId": "com.studica.frc", "artifactId": "StudicaLib-driver", - "version": "2026.0.1", + "version": "2026.0.2", "libName": "StudicaLibDriver", "headerClassifier": "headers", "sharedLibrary": false, diff --git a/vendordeps/photonlib.json b/vendordeps/photonlib.json index fbb5c80..62f135c 100644 --- a/vendordeps/photonlib.json +++ b/vendordeps/photonlib.json @@ -1,7 +1,7 @@ { "fileName": "photonlib.json", "name": "photonlib", - "version": "v2026.2.2", + "version": "v2026.3.1", "uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004", "frcYear": "2026", "mavenUrls": [ @@ -13,7 +13,7 @@ { "groupId": "org.photonvision", "artifactId": "photontargeting-cpp", - "version": "v2026.2.2", + "version": "v2026.3.1", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ @@ -28,7 +28,7 @@ { "groupId": "org.photonvision", "artifactId": "photonlib-cpp", - "version": "v2026.2.2", + "version": "v2026.3.1", "libName": "photonlib", "headerClassifier": "headers", "sharedLibrary": true, @@ -43,7 +43,7 @@ { "groupId": "org.photonvision", "artifactId": "photontargeting-cpp", - "version": "v2026.2.2", + "version": "v2026.3.1", "libName": "photontargeting", "headerClassifier": "headers", "sharedLibrary": true, @@ -60,12 +60,12 @@ { "groupId": "org.photonvision", "artifactId": "photonlib-java", - "version": "v2026.2.2" + "version": "v2026.3.1" }, { "groupId": "org.photonvision", "artifactId": "photontargeting-java", - "version": "v2026.2.2" + "version": "v2026.3.1" } ] } \ No newline at end of file diff --git a/vendordeps/yams.json b/vendordeps/yams.json index 9557c14..8266af7 100644 --- a/vendordeps/yams.json +++ b/vendordeps/yams.json @@ -1,7 +1,7 @@ { "fileName": "yams.json", "name": "Yet Another Mechanism System", - "version": "2026.2.3", + "version": "2026.2.23", "frcYear": "2026", "uuid": "a1051e86-a979-4880-a28b-a0d5362d1d96", "mavenUrls": [ @@ -12,7 +12,7 @@ { "groupId": "yams", "artifactId": "YAMS-java", - "version": "2026.2.3" + "version": "2026.2.23" } ], "cppDependencies": [],