From 91013803b838641723a5e979f3e2eeac4aaa53cc Mon Sep 17 00:00:00 2001 From: Riley Brewer Date: Mon, 11 Mar 2024 17:21:19 -0700 Subject: [PATCH 1/2] Clean up command chaos --- .../control/ButtonAction.java | 10 +- .../com/cyberknights4911/drive/Drive.java | 7 - .../cyberknights4911/robot2024/Robot2024.java | 205 +----------------- .../robot2024/collect/Collect.java | 39 ++-- .../robot2024/control/ControllerBinding.java | 2 +- .../robot2024/indexer/Indexer.java | 10 +- .../robot2024/shooter/Shooter.java | 97 ++++----- .../java/com/cyberknights4911/wham/Wham.java | 6 - .../wham/WhamControllerBinding.java | 2 - 9 files changed, 82 insertions(+), 296 deletions(-) diff --git a/src/main/java/com/cyberknights4911/control/ButtonAction.java b/src/main/java/com/cyberknights4911/control/ButtonAction.java index fc88c02..fa97231 100644 --- a/src/main/java/com/cyberknights4911/control/ButtonAction.java +++ b/src/main/java/com/cyberknights4911/control/ButtonAction.java @@ -20,13 +20,7 @@ public enum ButtonAction { FireNote, StowClimber, ExtendClimber, - AimSpeaker, + AimSubwoofer, AimPodium, - AimAmp, - Test1, - Test2, - Test3, - Test4, - Test5, - Test6 + AimAmp } diff --git a/src/main/java/com/cyberknights4911/drive/Drive.java b/src/main/java/com/cyberknights4911/drive/Drive.java index 8674ec5..1464f77 100644 --- a/src/main/java/com/cyberknights4911/drive/Drive.java +++ b/src/main/java/com/cyberknights4911/drive/Drive.java @@ -278,12 +278,8 @@ ChassisSpeeds createChassisSpeeds( x = -x; y = -y; } - System.out.println("x: " + x); - System.out.println("y: " + y); double linearMagnitude = MathUtil.applyDeadband(Math.hypot(x, y), controlConstants.stickDeadband()); - System.out.println("linearMagnitude: " + linearMagnitude); - System.out.println("stickDeadband: " + controlConstants.stickDeadband()); Rotation2d linearDirection = new Rotation2d(x, y); double omega = applyOmegaDeadbandAndScaling @@ -300,15 +296,12 @@ ChassisSpeeds createChassisSpeeds( .transformBy(new Transform2d(linearMagnitude, 0.0, new Rotation2d())) .getTranslation(); - System.out.println("linearVelocity: " + linearVelocity); - // Convert to field relative speeds & send command return ChassisSpeeds.fromFieldRelativeSpeeds( linearVelocity.getX() * driveConstants.maxLinearSpeed(), linearVelocity.getY() * driveConstants.maxLinearSpeed(), omega * maxAngularSpeedMetersPerSecond, getRotation()); - // return new ChassisSpeeds(); } private ChassisSpeeds createChassisSpeeds( diff --git a/src/main/java/com/cyberknights4911/robot2024/Robot2024.java b/src/main/java/com/cyberknights4911/robot2024/Robot2024.java index 3c3faf9..a2fb83e 100644 --- a/src/main/java/com/cyberknights4911/robot2024/Robot2024.java +++ b/src/main/java/com/cyberknights4911/robot2024/Robot2024.java @@ -125,208 +125,27 @@ private void configureControls() { Units.inchesToMeters(x), Units.inchesToMeters(y))); - binding.triggersFor(ButtonAction.StowCollector).onTrue(stow()); + binding.triggersFor(ButtonAction.StowCollector).onTrue(stowEverything()); binding.triggersFor(ButtonAction.CollectNote).onTrue(collectNote()); - binding.triggersFor(ButtonAction.AimSpeaker).onTrue(aimSpeaker()); + binding.triggersFor(ButtonAction.AimSubwoofer).onTrue(shooter.aimSubwoofer()); - binding.triggersFor(ButtonAction.AimPodium).onTrue(aimPodium()); + binding.triggersFor(ButtonAction.AimPodium).onTrue(shooter.aimPodium()); - binding.triggersFor(ButtonAction.FireNote).onTrue(fire()); - - // binding - // .triggersFor(ButtonAction.Test1) - // .onTrue( - // Commands.runOnce( - // () -> { - // shooter.setAimerPostion(34); - // collect.extendCollecter(); - // collect.runCollectOutput(.4); - // indexer.runOutput(.2); - // shooter.runGuideOutput(.2); - // })); - - // binding - // .triggersFor(ButtonAction.Test2) - // .onTrue( - // Commands.runOnce( - // () -> { - // shooter.setAimerPostion(1); - // collect.retractCollecter(); - // collect.runCollectOutput(0); - // indexer.runOutput(0); - // shooter.runGuideOutput(0); - // })); - // binding - // .triggersFor(ButtonAction.Test3) - // .onTrue( - // Commands.runOnce(() -> shooter.setAimerPostion(54)) - // .andThen(() -> shooter.runGuideOutput(-.1)) - // .andThen(Commands.waitSeconds(.05)) - // .andThen(() -> shooter.runGuideOutput(0))); - // binding - // .triggersFor(ButtonAction.Test4) - // .onTrue( - // Commands.runOnce(() -> shooter.runShooterOutput(.4)) - // .andThen(Commands.waitSeconds(2)) - // .andThen(() -> shooter.runGuideOutput(.5)) - // .andThen(Commands.waitSeconds(2)) - // .andThen( - // () -> { - // shooter.runShooterOutput(0); - // shooter.runGuideOutput(0); - // shooter.setAimerPostion(1); - // })); - - // binding - // .triggersFor(ButtonAction.Test1) - // .onTrue(Commands.runOnce(() -> indexer.runOutput(.2), indexer)); - - // binding.triggersFor(ButtonAction.Test2).onTrue(Commands.runOnce(() -> indexer.runOutput(0))); - - // binding - // .triggersFor(ButtonAction.Test3) - // .onTrue(Commands.runOnce(() -> shooter.runGuideOutput(.1), shooter)); - - // binding - // .triggersFor(ButtonAction.Test4) - // .onTrue(Commands.runOnce(() -> shooter.runGuideOutput(0))); - - // binding - // .triggersFor(ButtonAction.Test5) - // .onTrue(Commands.runOnce(() -> collect.runCollectOutput(.6), collect)); - - // binding - // .triggersFor(ButtonAction.Test6) - // .onTrue(Commands.runOnce(() -> collect.runCollectOutput(0), collect)); - - // aimer test code - // binding - // .triggersFor(ButtonAction.Test1) - // .onTrue(Commands.runOnce(() -> shooter.setAimerPostion(1))); - - // binding - // .triggersFor(ButtonAction.Test2) - // .onTrue(Commands.runOnce(() -> shooter.setAimerPostion(54))); - - // binding - // .triggersFor(ButtonAction.Test3) - // .onTrue(Commands.runOnce(() -> shooter.setAimerPostion(45))); - - // binding - // .triggersFor(ButtonAction.Test3) - // .onTrue(Commands.runOnce(() -> shooter.runAimerOutput(0))); - - // collector test code - // binding - // .triggersFor(ButtonAction.Test1) - // .onTrue(Commands.runOnce(() -> collect.extendCollecter())); - - // binding - // .triggersFor(ButtonAction.Test2) - // .onTrue(Commands.runOnce(() -> collect.retractCollecter())); - - // binding - // .triggersFor(ButtonAction.Test1) - // .onTrue( - // Commands.runOnce( - // () -> { - // collect.extendCollecter(); - // collect.runCollectOutput(.6); - // indexer.runOutput(.2); - // shooter.runGuideOutput(.1); - // })); - - // binding - // .triggersFor(ButtonAction.Test2) - // .onTrue( - // Commands.runOnce( - // () -> { - // collect.retractCollecter(); - // collect.runCollectOutput(0); - // indexer.runOutput(0); - // shooter.runGuideOutput(0); - // })); + binding.triggersFor(ButtonAction.FireNote).onTrue(shooter.fire()); } private Command collectNote() { - return Commands.runOnce( - () -> { - shooter.stopShooter(); - collect.collectAtTunableOutput(); - collect.extendCollecter(); - indexer.runIndexAtTunableOutput(); - shooter.guideAtTunableOutput(); - shooter.setAimerForCollect(); - shooter.setAimerPostion(34); - }, - shooter, - collect, - indexer) - .andThen(Commands.waitUntil(() -> shooter.isBeamBreakBlocked())) - .andThen(stow()); - } - - private Command stow() { - return Commands.runOnce( - () -> { - collect.retractCollecter(); - collect.stopCollector(); - indexer.stop(); - shooter.stopGuide(); - shooter.stopShooter(); - shooter.setAimerForCollect(); - }, - collect, - indexer, - shooter); - } - - private Command backNoteFromShooter() { - // return Commands.runOnce( - // () -> { - // shooter.guideReverseAtTunableOutput(); - // shooter.setAimerForCollect(); - // }) - // .andThen(Commands.waitUntil(() -> !shooter.isBeamBreakBlocked())); - return Commands.runOnce( - () -> { - shooter.setAimerForCollect(); - }); - } - - private Command aimSpeaker() { - return backNoteFromShooter() - .andThen(() -> shooter.setAimerForSpeaker()) - .andThen(Commands.waitSeconds(shooter.aimTime())) - .andThen( - () -> { - shooter.runShooterAtTunableSpeed(); - shooter.stopGuide(); - }); - } - - private Command aimPodium() { - return backNoteFromShooter() - .andThen(() -> shooter.setAimerForPodium()) - .andThen(Commands.waitSeconds(shooter.aimTime())) - .andThen( - () -> { - shooter.runShooterAtTunableSpeed(); - shooter.stopGuide(); - }); + return collect + .extendCollecter() + .andThen(indexer.runIndexAtTunableOutput()) + .andThen(shooter.collectAndWaitForNote()) + .andThen(stowEverything()); } - private Command fire() { - return Commands.runOnce(() -> shooter.guideAtTunableOutput()) - .andThen(Commands.waitSeconds(shooter.feedTime())) - .andThen( - () -> { - shooter.stopShooter(); - shooter.stopGuide(); - shooter.setAimerForCollect(); - }); + private Command stowEverything() { + return shooter.stow().alongWith(indexer.stop()).alongWith(collect.retractCollecter()); } @Override @@ -346,7 +165,7 @@ public void onRobotPeriodic(LoggedRobot robot) { public void setupAutos(AutoCommandHandler handler) { Autos autos = new Autos(Robot2024Constants.DRIVE_CONSTANTS, climb, collect, shooter, drive); autos.addAllAutos(handler); - NamedCommands.registerCommand("SHOOT_SUB", aimSpeaker().andThen(fire())); + NamedCommands.registerCommand("SHOOT_SUB", shooter.aimSubwoofer().andThen(shooter.fire())); NamedCommands.registerCommand("COLLECT", collectNote()); } diff --git a/src/main/java/com/cyberknights4911/robot2024/collect/Collect.java b/src/main/java/com/cyberknights4911/robot2024/collect/Collect.java index 473153b..613f77e 100644 --- a/src/main/java/com/cyberknights4911/robot2024/collect/Collect.java +++ b/src/main/java/com/cyberknights4911/robot2024/collect/Collect.java @@ -16,6 +16,8 @@ import edu.wpi.first.wpilibj.smartdashboard.Mechanism2d; import edu.wpi.first.wpilibj.smartdashboard.MechanismLigament2d; import edu.wpi.first.wpilibj.smartdashboard.MechanismRoot2d; +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import org.littletonrobotics.junction.Logger; @@ -83,14 +85,6 @@ public Collect(CollectConstants constants, CollectIO collectIO) { (voltage) -> runCollectVolts(voltage.in(Volts)), null, this)); } - public boolean isBeamBreakBlocked() { - return inputs.beamBreakVoltage > beamThreshold.get(); - } - - public void runCollectOutput(double percent) { - collectIO.setCollectOutput(percent); - } - /** Run collector open loop at the specified voltage. */ public void runCollectVolts(double volts) { collectIO.setCollectVoltage(volts); @@ -104,14 +98,6 @@ public void runCollectVelocity(double velocityRpm) { Logger.recordOutput("Collect/SetpointRPM", velocityRpm); } - public void extendCollecter() { - collectIO.setCollecterPosition(true); - } - - public void retractCollecter() { - collectIO.setCollecterPosition(false); - } - @Override public void periodic() { collectIO.updateInputs(inputs); @@ -134,7 +120,7 @@ public void periodic() { // Logger.recordOutput("Collect/Mechanism", mechanism); if (DriverStation.isDisabled()) { - stopCollector(); + collectIO.stopCollector(); } } @@ -161,12 +147,21 @@ public double getCharacterizationVelocity() { return inputs.collectVelocityRadPerSec; } - /** Stops the collector. */ - public void stopCollector() { - collectIO.stopCollector(); + public Command extendCollecter() { + return Commands.runOnce( + () -> { + collectIO.setCollecterPosition(true); + collectIO.setCollectOutput(collectOutput.get()); + }, + this); } - public void collectAtTunableOutput() { - runCollectOutput(collectOutput.get()); + public Command retractCollecter() { + return Commands.runOnce( + () -> { + collectIO.stopCollector(); + collectIO.setCollecterPosition(false); + }, + this); } } diff --git a/src/main/java/com/cyberknights4911/robot2024/control/ControllerBinding.java b/src/main/java/com/cyberknights4911/robot2024/control/ControllerBinding.java index 6ec8cf5..6a93cd8 100644 --- a/src/main/java/com/cyberknights4911/robot2024/control/ControllerBinding.java +++ b/src/main/java/com/cyberknights4911/robot2024/control/ControllerBinding.java @@ -67,7 +67,7 @@ public Triggers triggersFor(ButtonAction action) { return new Triggers(operator.b()); case AimPodium: return new Triggers(operator.povLeft()); - case AimSpeaker: + case AimSubwoofer: return new Triggers(operator.povRight()); case FireNote: return new Triggers(operator.rightTrigger()); diff --git a/src/main/java/com/cyberknights4911/robot2024/indexer/Indexer.java b/src/main/java/com/cyberknights4911/robot2024/indexer/Indexer.java index 34cb21a..ddfa072 100644 --- a/src/main/java/com/cyberknights4911/robot2024/indexer/Indexer.java +++ b/src/main/java/com/cyberknights4911/robot2024/indexer/Indexer.java @@ -10,6 +10,8 @@ import com.cyberknights4911.logging.LoggedTunableNumber; import edu.wpi.first.math.util.Units; import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.SubsystemBase; import org.littletonrobotics.junction.Logger; @@ -73,11 +75,11 @@ public void runVelocity(double velocityRpm) { Logger.recordOutput("Indexer/SetpointRPM", velocityRpm); } - public void stop() { - indexerIO.stop(); + public Command runIndexAtTunableOutput() { + return Commands.runOnce(() -> runOutput(percent.get()), this); } - public void runIndexAtTunableOutput() { - runOutput(percent.get()); + public Command stop() { + return Commands.runOnce(() -> indexerIO.stop(), this); } } diff --git a/src/main/java/com/cyberknights4911/robot2024/shooter/Shooter.java b/src/main/java/com/cyberknights4911/robot2024/shooter/Shooter.java index fabb7bc..a605b18 100644 --- a/src/main/java/com/cyberknights4911/robot2024/shooter/Shooter.java +++ b/src/main/java/com/cyberknights4911/robot2024/shooter/Shooter.java @@ -18,6 +18,7 @@ import edu.wpi.first.wpilibj.smartdashboard.MechanismLigament2d; import edu.wpi.first.wpilibj.smartdashboard.MechanismRoot2d; import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import java.util.function.DoubleSupplier; @@ -49,12 +50,10 @@ public class Shooter extends SubsystemBase { new LoggedTunableNumber("Shooter/FireOutputPercent"); private static final LoggedTunableNumber aimerCollectPosition = new LoggedTunableNumber("Shooter/AimerCollectPositionDegrees"); - private static final LoggedTunableNumber aimerSpeakerPosition = - new LoggedTunableNumber("Shooter/AimerSpeakerPositionDegrees"); + private static final LoggedTunableNumber aimerSubwooferPosition = + new LoggedTunableNumber("Shooter/AimerSubwofferPositionDegrees"); private static final LoggedTunableNumber aimerPodiumPosition = new LoggedTunableNumber("Shooter/AimerPodiumPositionDegrees"); - private static final LoggedTunableNumber aimerAmpPosition = - new LoggedTunableNumber("Shooter/AimerAmpPositionDegrees"); private static final LoggedTunableNumber forwardLimit = new LoggedTunableNumber("Shooter/forwardLimit"); private static final LoggedTunableNumber backwardLimit = @@ -89,10 +88,9 @@ public Shooter(ShooterConstants constants, ShooterIO shooterIO) { guideOutput.initDefault(constants.guidePercentOutput()); guideReverseOutput.initDefault(constants.guideReversePercentOutput()); fireOutput.initDefault(constants.firePercentOutput()); - aimerSpeakerPosition.initDefault(constants.speakerPositionDegrees()); + aimerSubwooferPosition.initDefault(constants.speakerPositionDegrees()); aimerCollectPosition.initDefault(constants.collectPositionDegrees()); aimerPodiumPosition.initDefault(constants.podiumPositionDegrees()); - aimerAmpPosition.initDefault(constants.ampPositionDegrees()); forwardLimit.initDefault(constants.aimerForwardLimit()); backwardLimit.initDefault(constants.aimerBackwardLimit()); beamThreshold.initDefault(constants.beamThreshold()); @@ -123,7 +121,7 @@ public Shooter(ShooterConstants constants, ShooterIO shooterIO) { public void runShooterOutput(double percent) { shooterIO.setShooterOutput(percent); - Logger.recordOutput("Shooter/FlywheelPerent", percent); + Logger.recordOutput("Shooter/FlywheelPercent", percent); } /** Run shooter open loop at the specified voltage. */ @@ -149,17 +147,6 @@ public double getShooterVelocityRpm() { return velocityRpm; } - /** Stops the shooter. */ - public void stopShooter() { - shooterIO.stopShooter(); - } - - public void runAimerOutput(double percent) { - shooterIO.setAimerOutput(percent); - - Logger.recordOutput("Shooter/AimerPercent", percent); - } - public void runAimerVolts(double voltage) { shooterIO.setAimerVoltage(voltage); @@ -174,24 +161,16 @@ public void setAimerPostion(double positionDegrees) { Logger.recordOutput("Shooter/AimerSetpointDegrees", positionDegrees); } - public void setAimerForSpeaker() { - setAimerPostion(aimerSpeakerPosition.get()); - } - - public void setAimerForCollect() { - setAimerPostion(aimerCollectPosition.get()); - } - - public void setAimerForPodium() { - setAimerPostion(aimerPodiumPosition.get()); - } - - public void setAimerForAmp() { - setAimerPostion(aimerAmpPosition.get()); - } - - public void stopAimer() { - shooterIO.stopAimer(); + /** Will not complete until beam break is blocked! */ + public Command collectAndWaitForNote() { + return Commands.runOnce( + () -> { + shooterIO.stopShooter(); + setAimerPostion(aimerCollectPosition.get()); + runGuideOutput(guideOutput.get()); + }, + this) + .alongWith(Commands.waitUntil(() -> inputs.beamBreakValue > .1)); } public void runGuideOutput(double percent) { @@ -218,10 +197,6 @@ public void stopGuide() { shooterIO.stopGuide(); } - public boolean isBeamBreakBlocked() { - return inputs.beamBreakValue < .1; - } - @Override public void periodic() { shooterIO.updateInputs(inputs); @@ -245,11 +220,11 @@ public void periodic() { // TODO: convert this to the actual angle (correct for gear ratio) segment.setAngle(Math.toDegrees(inputs.aimerPositionRad)); - Logger.recordOutput("Shooter/Mechanism", mechanism); + // Logger.recordOutput("Shooter/Mechanism", mechanism); if (DriverStation.isDisabled()) { - stopShooter(); - stopGuide(); + shooterIO.stopShooter(); + shooterIO.stopGuide(); } } @@ -258,24 +233,40 @@ public SysIdRoutine getSysId() { return sysId; } - public void guideAtTunableOutput() { - runGuideOutput(guideOutput.get()); - } - - public void guideReverseAtTunableOutput() { + private void guideReverseAtTunableOutput() { runGuideOutput(guideReverseOutput.get()); } - public void runShooterAtTunableSpeed() { + private void runShooterAtTunableSpeed() { runShooterOutput(fireOutput.get()); } - public double feedTime() { - return feedTime.get(); + public Command stow() { + return Commands.runOnce( + () -> { + shooterIO.stopGuide(); + shooterIO.stopShooter(); + setAimerPostion(aimerCollectPosition.get()); + }, + this); + } + + public Command aimSubwoofer() { + return Commands.runOnce(() -> setAimerPostion(aimerSubwooferPosition.get()), this) + .andThen(this::runShooterAtTunableSpeed, this); + } + + public Command aimPodium() { + return Commands.runOnce(() -> setAimerPostion(aimerPodiumPosition.get()), this) + .andThen(this::runShooterAtTunableSpeed, this); } - public double aimTime() { - return aimTime.get(); + public Command fire() { + return Commands.runOnce(() -> runGuideOutput(guideOutput.get()), this) + .andThen(Commands.waitSeconds(feedTime.get())) + .andThen(shooterIO::stopShooter, this) + .andThen(shooterIO::stopGuide, this) + .andThen(this::collectAndWaitForNote); } /** diff --git a/src/main/java/com/cyberknights4911/wham/Wham.java b/src/main/java/com/cyberknights4911/wham/Wham.java index 109c6c9..e9dfffc 100644 --- a/src/main/java/com/cyberknights4911/wham/Wham.java +++ b/src/main/java/com/cyberknights4911/wham/Wham.java @@ -92,12 +92,6 @@ private void configureControls() { binding.supplierFor(StickAction.STRAFE), Math.PI / 2)); - Junk junk = new Junk(); - binding - .triggersFor(ButtonAction.Test2) - .onTrue(Commands.runOnce(() -> junk.setVoltage(-3.0))) - .onFalse(Commands.runOnce(() -> junk.stop())); - double speakerX = 0; double speakerY = 0; if (Alliance.isRed()) { diff --git a/src/main/java/com/cyberknights4911/wham/WhamControllerBinding.java b/src/main/java/com/cyberknights4911/wham/WhamControllerBinding.java index de69c2c..74337db 100644 --- a/src/main/java/com/cyberknights4911/wham/WhamControllerBinding.java +++ b/src/main/java/com/cyberknights4911/wham/WhamControllerBinding.java @@ -50,8 +50,6 @@ public Triggers triggersFor(ButtonAction action) { // return new Triggers(driver.leftTrigger()); // case SpeakerLockOn: // return new Triggers(driver.rightTrigger()); - case Test2: - return new Triggers(driver.a()); default: return new Triggers(ALWAYS_FALSE); } From b4628434e10113f79c4e49c7252f86ce2a12e271 Mon Sep 17 00:00:00 2001 From: Riley Brewer Date: Mon, 11 Mar 2024 17:28:42 -0700 Subject: [PATCH 2/2] Update everything --- build.gradle | 2 +- vendordeps/AdvantageKit.json | 10 +++++----- vendordeps/PathplannerLib.json | 6 +++--- vendordeps/photonlib.json | 10 +++++----- 4 files changed, 14 insertions(+), 14 deletions(-) diff --git a/build.gradle b/build.gradle index 8ac4013..7edc05a 100644 --- a/build.gradle +++ b/build.gradle @@ -1,6 +1,6 @@ plugins { id "java" - id "edu.wpi.first.GradleRIO" version "2024.2.1" + id "edu.wpi.first.GradleRIO" version "2024.3.1" id "com.peterabeles.gversion" version "1.10.2" id "com.diffplug.spotless" version "6.12.0" } diff --git a/vendordeps/AdvantageKit.json b/vendordeps/AdvantageKit.json index bdbd93d..d18e36d 100644 --- a/vendordeps/AdvantageKit.json +++ b/vendordeps/AdvantageKit.json @@ -1,7 +1,7 @@ { "fileName": "AdvantageKit.json", "name": "AdvantageKit", - "version": "3.0.2", + "version": "3.1.1", "uuid": "d820cc26-74e3-11ec-90d6-0242ac120003", "frcYear": "2024", "mavenUrls": [], @@ -10,24 +10,24 @@ { "groupId": "org.littletonrobotics.akit.junction", "artifactId": "wpilib-shim", - "version": "3.0.2" + "version": "3.1.1" }, { "groupId": "org.littletonrobotics.akit.junction", "artifactId": "junction-core", - "version": "3.0.2" + "version": "3.1.1" }, { "groupId": "org.littletonrobotics.akit.conduit", "artifactId": "conduit-api", - "version": "3.0.2" + "version": "3.1.1" } ], "jniDependencies": [ { "groupId": "org.littletonrobotics.akit.conduit", "artifactId": "conduit-wpilibio", - "version": "3.0.2", + "version": "3.1.1", "skipInvalidPlatforms": false, "isJar": false, "validPlatforms": [ diff --git a/vendordeps/PathplannerLib.json b/vendordeps/PathplannerLib.json index ff15fab..3ec4c12 100644 --- a/vendordeps/PathplannerLib.json +++ b/vendordeps/PathplannerLib.json @@ -1,7 +1,7 @@ { "fileName": "PathplannerLib.json", "name": "PathplannerLib", - "version": "2024.2.3", + "version": "2024.2.6", "uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786", "frcYear": "2024", "mavenUrls": [ @@ -12,7 +12,7 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-java", - "version": "2024.2.3" + "version": "2024.2.6" } ], "jniDependencies": [], @@ -20,7 +20,7 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-cpp", - "version": "2024.2.3", + "version": "2024.2.6", "libName": "PathplannerLib", "headerClassifier": "headers", "sharedLibrary": false, diff --git a/vendordeps/photonlib.json b/vendordeps/photonlib.json index 8b1044d..77641e4 100644 --- a/vendordeps/photonlib.json +++ b/vendordeps/photonlib.json @@ -1,7 +1,7 @@ { "fileName": "photonlib.json", "name": "photonlib", - "version": "v2024.2.6", + "version": "v2024.2.9", "uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004", "frcYear": "2024", "mavenUrls": [ @@ -14,7 +14,7 @@ { "groupId": "org.photonvision", "artifactId": "photonlib-cpp", - "version": "v2024.2.6", + "version": "v2024.2.9", "libName": "photonlib", "headerClassifier": "headers", "sharedLibrary": true, @@ -29,7 +29,7 @@ { "groupId": "org.photonvision", "artifactId": "photontargeting-cpp", - "version": "v2024.2.6", + "version": "v2024.2.9", "libName": "photontargeting", "headerClassifier": "headers", "sharedLibrary": true, @@ -46,12 +46,12 @@ { "groupId": "org.photonvision", "artifactId": "photonlib-java", - "version": "v2024.2.6" + "version": "v2024.2.9" }, { "groupId": "org.photonvision", "artifactId": "photontargeting-java", - "version": "v2024.2.6" + "version": "v2024.2.9" } ] } \ No newline at end of file