From 1477f997327d3b3e2ec6d4375e383c5b81ea148c Mon Sep 17 00:00:00 2001 From: Mihir Patankar Date: Tue, 26 Mar 2024 17:35:19 -0400 Subject: [PATCH] offboard shooter control --- src/main/java/frc/robot/Autos.java | 9 +-- src/main/java/frc/robot/Constants.java | 2 +- src/main/java/frc/robot/Robot.java | 2 +- src/main/java/frc/robot/arm/Arm.java | 25 +++--- src/main/java/frc/robot/arm/ArmIOTalonFX.java | 4 - .../frc/robot/drivetrain/ModuleIOTalonFX.java | 3 - src/main/java/frc/robot/shooter/Shooter.java | 81 ++++++------------- .../java/frc/robot/shooter/ShooterIOSim.java | 34 +++++++- .../frc/robot/shooter/ShooterIOTalonFX.java | 19 ++--- vendordeps/ChoreoLib.json | 4 +- vendordeps/PathplannerLib.json | 6 +- vendordeps/REVLib.json | 10 +-- vendordeps/photonlib.json | 10 +-- 13 files changed, 100 insertions(+), 109 deletions(-) diff --git a/src/main/java/frc/robot/Autos.java b/src/main/java/frc/robot/Autos.java index 6d9137d..4b39a01 100644 --- a/src/main/java/frc/robot/Autos.java +++ b/src/main/java/frc/robot/Autos.java @@ -2,9 +2,8 @@ import com.choreo.lib.Choreo; import com.choreo.lib.ChoreoControlFunction; -import com.pathplanner.lib.util.GeometryUtil; +import com.choreo.lib.ChoreoTrajectory; import edu.wpi.first.math.controller.PIDController; -import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Command.InterruptionBehavior; @@ -97,13 +96,13 @@ private Command getPathFollowingCommand(String trajectoryName) { } private Command resetPose(String trajectoryName) { - Pose2d startingPose = Choreo.getTrajectory(trajectoryName).getInitialPose(); + ChoreoTrajectory trajectory = Choreo.getTrajectory(trajectoryName); return Commands.runOnce( () -> m_drivetrain.resetPose.accept( Constants.onRedAllianceSupplier.getAsBoolean() - ? GeometryUtil.flipFieldPose(startingPose) - : startingPose)); + ? trajectory.getFlippedInitialPose() + : trajectory.getInitialPose())); } private Command intake() { diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index be2bc65..58164e4 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -12,7 +12,7 @@ import java.util.function.BooleanSupplier; public final class Constants { - public static final Mode kCurrentMode = Mode.kReal; + public static final Mode kCurrentMode = Mode.kSim; public static final RobotName kRobot = RobotName.kViper; public static final boolean kIsViper = kRobot.equals(RobotName.kViper); public static final boolean kIsSim = Constants.kCurrentMode.equals(Mode.kSim); diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index 60688f0..5a706b6 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -232,7 +232,7 @@ public Robot() { // m_driverController.x().onTrue(m_arm.goToSetpoint(ArmSetpoints.kTrap)); m_driverController.y().whileTrue(Commands.parallel(m_climber.windWinch())); - m_driverController.povRight().onTrue(m_shooter.trap()); + m_driverController.povRight().onTrue(m_shooter.trapShot()); m_driverController.leftBumper().whileTrue(Superstructure.sensorIntake(m_feeder, m_intake)); m_operatorController diff --git a/src/main/java/frc/robot/arm/Arm.java b/src/main/java/frc/robot/arm/Arm.java index c33a7b5..e04673c 100644 --- a/src/main/java/frc/robot/arm/Arm.java +++ b/src/main/java/frc/robot/arm/Arm.java @@ -46,8 +46,9 @@ public class Arm extends SubsystemBase { new LoggedTunableNumber("Arm/Wrist/MaxAcceleration"); private Vector m_initialAngles; - private boolean m_atGoal = false; - public Trigger atGoal = new Trigger(this::getJointsAtGoal).debounce(0.1, DebounceType.kBoth); + private Rotation2d m_lastElbowSetpoint; + private Rotation2d m_lastWristSetpoint; + public Trigger atGoal = new Trigger(this::jointsAtGoal).debounce(0.1, DebounceType.kBoth); public Supplier wristPoseSupplier; private final SysIdRoutine m_sysIdRoutineElbow, m_sysIdRoutineWrist; @@ -135,6 +136,8 @@ private void runSetpoint( throw new IllegalArgumentException("Only one joint can be delayed at a time."); if (elbowDelay < 0.0 || wristDelay < 0.0) throw new IllegalArgumentException("Percent delay can't be negative."); + m_lastElbowSetpoint = new Rotation2d(elbowAngleRad); + m_lastWristSetpoint = new Rotation2d(wristAngleRad); Logger.recordOutput("Arm/Goal Elbow Angle", Units.radiansToDegrees(elbowAngleRad)); Logger.recordOutput("Arm/Goal Wrist Angle", Units.radiansToDegrees(wristAngleRad)); m_goalVisualizer.update(elbowAngleRad, wristAngleRad); @@ -146,7 +149,6 @@ private void runSetpoint( / Math.abs(Units.degreesToRotations(wristAngleRad) - m_initialAngles.get(1, 0)); Logger.recordOutput("Arm/Elbow Progress", elbowProgress); Logger.recordOutput("Arm/Wrist Progress", wristProgress); - m_atGoal = anglesAtGoal(new Rotation2d(elbowAngleRad), new Rotation2d(wristAngleRad)); if (wristProgress < elbowDelay) m_io.setElbowRotations(m_inputs.elbowPositionRot); else m_io.setElbowRotations(Units.radiansToRotations(elbowAngleRad)); @@ -154,22 +156,22 @@ private void runSetpoint( else m_io.setWristRotations(Units.radiansToRotations(wristAngleRad)); } - private boolean anglesAtGoal(Rotation2d elbowGoal, Rotation2d wristGoal) { + @AutoLogOutput(key = "Arm/JointsAtGoal") + private boolean jointsAtGoal() { return (MathUtil.isNear( 0.0, - elbowGoal.minus(Rotation2d.fromRotations(m_inputs.elbowPositionRot)).getDegrees(), + m_lastElbowSetpoint + .minus(Rotation2d.fromRotations(m_inputs.elbowPositionRot)) + .getDegrees(), kJointTolerenceDegrees) && MathUtil.isNear( 0.0, - wristGoal.minus(Rotation2d.fromRotations(m_inputs.wristPositionRot)).getDegrees(), + m_lastWristSetpoint + .minus(Rotation2d.fromRotations(m_inputs.wristPositionRot)) + .getDegrees(), kJointTolerenceDegrees)); } - @AutoLogOutput(key = "Arm/JointsAtGoal") - private boolean getJointsAtGoal() { - return m_atGoal; - } - public Command storeInitialAngles() { return this.runOnce( () -> @@ -191,7 +193,6 @@ else if (jointIndexSupplier.getAsInt() == 1) ArmSetpoints.kStowed.elbowAngle, angleSupplier.getAsDouble(), 0.0, 0.0); else throw new IllegalArgumentException("Invalid joint index."); })) - .finallyDo(() -> m_atGoal = false) .withName("Aim (Arm)"); } diff --git a/src/main/java/frc/robot/arm/ArmIOTalonFX.java b/src/main/java/frc/robot/arm/ArmIOTalonFX.java index 9acfa8e..4dc2960 100644 --- a/src/main/java/frc/robot/arm/ArmIOTalonFX.java +++ b/src/main/java/frc/robot/arm/ArmIOTalonFX.java @@ -52,7 +52,6 @@ public ArmIOTalonFX() { currentLimitsConfig.StatorCurrentLimit = 60.0; currentLimitsConfig.StatorCurrentLimitEnable = true; final TalonFXConfiguration elbowLeftMotorConfig = new TalonFXConfiguration(); - m_elbowLeftMotor.getConfigurator().apply(elbowLeftMotorConfig); elbowLeftMotorConfig.CurrentLimits = currentLimitsConfig; elbowLeftMotorConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; elbowLeftMotorConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; @@ -72,7 +71,6 @@ public ArmIOTalonFX() { m_elbowLeftMotor.getConfigurator().apply(elbowLeftMotorConfig, 1.0); final TalonFXConfiguration wristLeftMotorConfig = new TalonFXConfiguration(); - m_wristLeftMotor.getConfigurator().apply(wristLeftMotorConfig); wristLeftMotorConfig.CurrentLimits = currentLimitsConfig; wristLeftMotorConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; wristLeftMotorConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; @@ -93,14 +91,12 @@ public ArmIOTalonFX() { m_wristLeftMotor.getConfigurator().apply(wristLeftMotorConfig, 1.0); final TalonFXConfiguration elbowRightMotorConfig = new TalonFXConfiguration(); - m_elbowRightFollowerMotor.getConfigurator().apply(elbowRightMotorConfig); elbowRightMotorConfig.CurrentLimits = currentLimitsConfig; elbowRightMotorConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; m_elbowRightFollowerMotor.getConfigurator().apply(elbowRightMotorConfig, 1.0); m_elbowRightFollowerMotor.setControl(new Follower(m_elbowLeftMotor.getDeviceID(), true)); final TalonFXConfiguration wristRightMotorConfig = new TalonFXConfiguration(); - m_wristRightFollowerMotor.getConfigurator().apply(wristRightMotorConfig); wristRightMotorConfig.CurrentLimits = currentLimitsConfig; wristRightMotorConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; m_wristRightFollowerMotor.getConfigurator().apply(wristRightMotorConfig, 1.0); diff --git a/src/main/java/frc/robot/drivetrain/ModuleIOTalonFX.java b/src/main/java/frc/robot/drivetrain/ModuleIOTalonFX.java index 5d218c5..d4d116e 100644 --- a/src/main/java/frc/robot/drivetrain/ModuleIOTalonFX.java +++ b/src/main/java/frc/robot/drivetrain/ModuleIOTalonFX.java @@ -94,7 +94,6 @@ public ModuleIOTalonFX(int index) { } final CANcoderConfiguration azimuthEncoderConfig = new CANcoderConfiguration(); - m_azimuthEncoder.getConfigurator().apply(azimuthEncoderConfig); // Factory Default azimuthEncoderConfig.MagnetSensor.AbsoluteSensorRange = AbsoluteSensorRangeValue.Signed_PlusMinusHalf; azimuthEncoderConfig.MagnetSensor.SensorDirection = @@ -103,7 +102,6 @@ public ModuleIOTalonFX(int index) { m_azimuthEncoder.getConfigurator().apply(azimuthEncoderConfig); final TalonFXConfiguration driveMotorConfig = new TalonFXConfiguration(); - m_driveMotor.getConfigurator().apply(driveMotorConfig); // Factory Default driveMotorConfig.MotorOutput.Inverted = InvertedValue.CounterClockwise_Positive; driveMotorConfig.Feedback.SensorToMechanismRatio = Module.kDriveRatio; driveMotorConfig.Slot0.kP = kDrivekP; @@ -116,7 +114,6 @@ public ModuleIOTalonFX(int index) { m_driveMotor.setPosition(0.0); final TalonFXConfiguration steerMotorConfig = new TalonFXConfiguration(); - m_steerMotor.getConfigurator().apply(steerMotorConfig); // Factory Default steerMotorConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; steerMotorConfig.Feedback.FeedbackRemoteSensorID = m_azimuthEncoder.getDeviceID(); steerMotorConfig.Feedback.FeedbackSensorSource = FeedbackSensorSourceValue.FusedCANcoder; diff --git a/src/main/java/frc/robot/shooter/Shooter.java b/src/main/java/frc/robot/shooter/Shooter.java index c8523f6..0f9c723 100644 --- a/src/main/java/frc/robot/shooter/Shooter.java +++ b/src/main/java/frc/robot/shooter/Shooter.java @@ -2,8 +2,7 @@ import static edu.wpi.first.units.Units.Volts; -import edu.wpi.first.math.controller.PIDController; -import edu.wpi.first.math.controller.SimpleMotorFeedforward; +import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.filter.Debouncer.DebounceType; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; @@ -16,8 +15,9 @@ public class Shooter extends SubsystemBase { - private final double kFarShotVelocityRpm = 5600.0; - private final double kAmpshot = 5000.0; + public static final double kFarShotVelocityRpm = 5600.0; + private final double kTrapShot = 400.0; + private final double kAmpShot = 5000.0; private final double kReadyToShootToleranceRps = 3.0; // Denominator for gains here are in rotations @@ -28,30 +28,21 @@ public class Shooter extends SubsystemBase { public static final double bottomRollerkV = 0.12041; public static final double bottomRollerkA = 0.0071461; - private final double topRollerkP = 0.13085; - private final double bottomRollerkP = 0.11992; + public static final double topRollerkP = 0.13085; + public static final double bottomRollerkP = 0.11992; - private final PIDController m_topRollerController, m_bottomRollerController; - private final SimpleMotorFeedforward m_topRollerFeedforward, m_bottomRollerFeedforward; private final SysIdRoutine m_sysIdRoutine; - private final ShooterIO m_io; private final ShooterIOInputsAutoLogged m_inputs = new ShooterIOInputsAutoLogged(); public final Trigger readyToShoot = - new Trigger(() -> getRollersAtSetpoint()).debounce(0.1, DebounceType.kBoth); + new Trigger(this::getRollersAtSetpoint).debounce(0.1, DebounceType.kBoth); + + private double m_lastSetpoint; public Shooter(ShooterIO io) { m_io = io; - m_topRollerFeedforward = new SimpleMotorFeedforward(topRollerkS, topRollerkV, topRollerkA); - m_topRollerController = new PIDController(topRollerkP, 0.0, 0.0); - m_bottomRollerFeedforward = - new SimpleMotorFeedforward(bottomRollerkS, bottomRollerkV, bottomRollerkA); - m_bottomRollerController = new PIDController(bottomRollerkP, 0.0, 0.0); - - m_topRollerController.setTolerance(kReadyToShootToleranceRps); - m_bottomRollerController.setTolerance(kReadyToShootToleranceRps); m_sysIdRoutine = new SysIdRoutine( new SysIdRoutine.Config( @@ -78,19 +69,17 @@ public void periodic() { private void setRollersSetpointRpm(double velocityRpm) { double goalVelocityRps = velocityRpm / 60.0; Logger.recordOutput("Shooter/Goal Roller RPS", goalVelocityRps); - double topRollerFeedforwardOutput = m_topRollerFeedforward.calculate(goalVelocityRps); - double bottomRollerFeedforwardOutput = m_bottomRollerFeedforward.calculate(goalVelocityRps); - double topRollerFeedbackOutput = - m_topRollerController.calculate(m_inputs.topRollerVelocityRps, goalVelocityRps); - double bottomRollerFeedbackOutput = - m_bottomRollerController.calculate(m_inputs.bottomRollerVelocityRps, goalVelocityRps); - m_io.setTopRollerVoltage(topRollerFeedforwardOutput + topRollerFeedbackOutput); - m_io.setBottomRollerVoltage(bottomRollerFeedforwardOutput + bottomRollerFeedbackOutput); + m_lastSetpoint = goalVelocityRps; + m_io.setTopRollerVelocity(goalVelocityRps); + m_io.setBottomRollerVelocity(goalVelocityRps); } @AutoLogOutput(key = "Shooter/RollersAtSetpoint") private boolean getRollersAtSetpoint() { - return m_bottomRollerController.atSetpoint() && m_topRollerController.atSetpoint(); + return MathUtil.isNear( + m_lastSetpoint, m_inputs.bottomRollerVelocityRps, kReadyToShootToleranceRps) + && MathUtil.isNear( + m_lastSetpoint, m_inputs.topRollerVelocityRps, kReadyToShootToleranceRps); } public Command sysId() { @@ -118,35 +107,19 @@ public Command stop() { } public Command runShooter() { - return this.run( - () -> { - setRollersSetpointRpm(kFarShotVelocityRpm); - }) - .finallyDo( - () -> { - Logger.recordOutput("Shooter/Goal Roller RPS", 0.0); - m_topRollerController.reset(); - m_bottomRollerController.reset(); - }) - .withName("Spin Up (Shooter)"); + return this.run(() -> setRollersSetpointRpm(kFarShotVelocityRpm)) + .finallyDo(() -> Logger.recordOutput("Shooter/Goal Roller RPS", 0.0)) + .withName("Run Shooter (Shooter)"); } - public Command trap() { - return this.run( - () -> { - setRollersSetpointRpm(2800); - }) - .finallyDo( - () -> { - Logger.recordOutput("Shooter/Goal Roller RPS", 0.0); - m_topRollerController.reset(); - m_bottomRollerController.reset(); - }) - .withName("Spin Up (Shooter)"); + public Command trapShot() { + return this.run(() -> setRollersSetpointRpm(kTrapShot)) + .finallyDo(() -> Logger.recordOutput("Shooter/Goal Roller RPS", 0.0)) + .withName("Trap Shot (Shooter)"); } public Command ampShot() { - return this.run(() -> setRollersSetpointRpm(kAmpshot)); + return this.run(() -> setRollersSetpointRpm(kAmpShot)); } public Command catchNote() { @@ -166,10 +139,4 @@ public Command spit() { }) .withName("Spit (Shooter)"); } - - public Command shootWithFeederDelay() { - return this.run(() -> setRollersSetpointRpm(kFarShotVelocityRpm)) - .until(() -> getRollersAtSetpoint()) - .andThen(runShooter()); - } } diff --git a/src/main/java/frc/robot/shooter/ShooterIOSim.java b/src/main/java/frc/robot/shooter/ShooterIOSim.java index 49d8521..ea5267b 100644 --- a/src/main/java/frc/robot/shooter/ShooterIOSim.java +++ b/src/main/java/frc/robot/shooter/ShooterIOSim.java @@ -1,6 +1,8 @@ package frc.robot.shooter; import edu.wpi.first.math.MathUtil; +import edu.wpi.first.math.controller.PIDController; +import edu.wpi.first.math.controller.SimpleMotorFeedforward; import edu.wpi.first.math.numbers.N1; import edu.wpi.first.math.numbers.N2; import edu.wpi.first.math.system.LinearSystem; @@ -20,13 +22,23 @@ public class ShooterIOSim implements ShooterIO { private final DCMotorSim m_bottomRollerSim = new DCMotorSim(m_bottomRollerPlant, m_rollerGearbox, 1.0); + private final SimpleMotorFeedforward m_topRollerFeedforward = + new SimpleMotorFeedforward(Shooter.topRollerkS, Shooter.topRollerkV, Shooter.topRollerkA); + private final PIDController m_topRollerController = + new PIDController(Shooter.topRollerkP, 0.0, 0.0); + private final SimpleMotorFeedforward m_bottomRollerFeedforward = + new SimpleMotorFeedforward( + Shooter.bottomRollerkS, Shooter.bottomRollerkV, Shooter.bottomRollerkA); + private final PIDController m_bottomRollerController = + new PIDController(Shooter.bottomRollerkP, 0.0, 0.0); + private double m_topRollerAppliedVolts = 0.0; private double m_bottomRollerAppliedVolts = 0.0; + public ShooterIOSim() {} + @Override public void updateInputs(ShooterIOInputs inputs) { - m_topRollerSim.setInputVoltage(m_topRollerAppliedVolts); - m_bottomRollerSim.setInputVoltage(m_bottomRollerAppliedVolts); m_topRollerSim.update(0.02); m_bottomRollerSim.update(0.02); @@ -57,11 +69,29 @@ public void updateInputs(ShooterIOInputs inputs) { @Override public void setTopRollerVoltage(double volts) { m_topRollerAppliedVolts = MathUtil.clamp(volts, -12.0, 12.0); + m_topRollerSim.setInputVoltage(m_topRollerAppliedVolts); } @Override public void setBottomRollerVoltage(double volts) { m_bottomRollerAppliedVolts = MathUtil.clamp(volts, -12.0, 12.0); + m_bottomRollerSim.setInputVoltage(m_bottomRollerAppliedVolts); + } + + @Override + public void setTopRollerVelocity(double velocityRps) { + setTopRollerVoltage( + m_topRollerFeedforward.calculate(velocityRps) + + m_topRollerController.calculate( + m_topRollerSim.getAngularVelocityRadPerSec(), velocityRps)); + } + + @Override + public void setBottomRollerVelocity(double velocityRps) { + setBottomRollerVoltage( + m_bottomRollerFeedforward.calculate(velocityRps) + + m_bottomRollerController.calculate( + m_bottomRollerSim.getAngularVelocityRadPerSec(), velocityRps)); } @Override diff --git a/src/main/java/frc/robot/shooter/ShooterIOTalonFX.java b/src/main/java/frc/robot/shooter/ShooterIOTalonFX.java index 82a6d27..c24d80f 100644 --- a/src/main/java/frc/robot/shooter/ShooterIOTalonFX.java +++ b/src/main/java/frc/robot/shooter/ShooterIOTalonFX.java @@ -28,19 +28,20 @@ public ShooterIOTalonFX() { m_bottomRoller = new TalonFX(21, Constants.kSuperstructureCanBus); final MotionMagicConfigs motionMagicConfigs = - new MotionMagicConfigs().withMotionMagicAcceleration(6000 * (1 / 0.25)); + new MotionMagicConfigs() + .withMotionMagicAcceleration(Shooter.kFarShotVelocityRpm * (1 / 0.25)); final TalonFXConfiguration topRollerMotorConfig = new TalonFXConfiguration(); - topRollerMotorConfig.Slot0.kS = 0.0; - topRollerMotorConfig.Slot0.kV = 0.0; - topRollerMotorConfig.Slot0.kA = 0.0; - topRollerMotorConfig.Slot0.kP = 0.0; + topRollerMotorConfig.Slot0.kS = Shooter.topRollerkS; + topRollerMotorConfig.Slot0.kV = Shooter.topRollerkV; + topRollerMotorConfig.Slot0.kA = Shooter.topRollerkA; + topRollerMotorConfig.Slot0.kP = Shooter.topRollerkP; topRollerMotorConfig.MotionMagic = motionMagicConfigs; m_topRoller.getConfigurator().apply(topRollerMotorConfig); final TalonFXConfiguration bottomRollerMotorConfig = new TalonFXConfiguration(); - bottomRollerMotorConfig.Slot0.kS = 0.0; - bottomRollerMotorConfig.Slot0.kV = 0.0; - bottomRollerMotorConfig.Slot0.kA = 0.0; - bottomRollerMotorConfig.Slot0.kP = 0.0; + bottomRollerMotorConfig.Slot0.kS = Shooter.bottomRollerkS; + bottomRollerMotorConfig.Slot0.kV = Shooter.bottomRollerkV; + bottomRollerMotorConfig.Slot0.kA = Shooter.bottomRollerkA; + bottomRollerMotorConfig.Slot0.kP = Shooter.bottomRollerkP; bottomRollerMotorConfig.MotionMagic = motionMagicConfigs; m_bottomRoller.getConfigurator().apply(bottomRollerMotorConfig); diff --git a/vendordeps/ChoreoLib.json b/vendordeps/ChoreoLib.json index 8fbf7ab..367682f 100644 --- a/vendordeps/ChoreoLib.json +++ b/vendordeps/ChoreoLib.json @@ -12,7 +12,7 @@ { "groupId": "com.choreo.lib", "artifactId": "ChoreoLib-java", - "version": "2024.1.3" + "version": "2024.2.2" }, { "groupId": "com.google.code.gson", @@ -25,7 +25,7 @@ { "groupId": "com.choreo.lib", "artifactId": "ChoreoLib-cpp", - "version": "2024.1.3", + "version": "2024.2.2", "libName": "ChoreoLib", "headerClassifier": "headers", "sharedLibrary": false, diff --git a/vendordeps/PathplannerLib.json b/vendordeps/PathplannerLib.json index 0cd337c..192e91d 100644 --- a/vendordeps/PathplannerLib.json +++ b/vendordeps/PathplannerLib.json @@ -1,7 +1,7 @@ { "fileName": "PathplannerLib.json", "name": "PathplannerLib", - "version": "2024.2.6", + "version": "2024.2.7", "uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786", "frcYear": "2024", "mavenUrls": [ @@ -12,7 +12,7 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-java", - "version": "2024.2.6" + "version": "2024.2.7" } ], "jniDependencies": [], @@ -20,7 +20,7 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-cpp", - "version": "2024.2.6", + "version": "2024.2.7", "libName": "PathplannerLib", "headerClassifier": "headers", "sharedLibrary": false, diff --git a/vendordeps/REVLib.json b/vendordeps/REVLib.json index 237b5e3..9eda5ac 100644 --- a/vendordeps/REVLib.json +++ b/vendordeps/REVLib.json @@ -1,7 +1,7 @@ { "fileName": "REVLib.json", "name": "REVLib", - "version": "2024.2.3", + "version": "2024.2.4", "frcYear": "2024", "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", "mavenUrls": [ @@ -12,14 +12,14 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-java", - "version": "2024.2.3" + "version": "2024.2.4" } ], "jniDependencies": [ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2024.2.3", + "version": "2024.2.4", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ @@ -37,7 +37,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-cpp", - "version": "2024.2.3", + "version": "2024.2.4", "libName": "REVLib", "headerClassifier": "headers", "sharedLibrary": false, @@ -55,7 +55,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2024.2.3", + "version": "2024.2.4", "libName": "REVLibDriver", "headerClassifier": "headers", "sharedLibrary": false, diff --git a/vendordeps/photonlib.json b/vendordeps/photonlib.json index cba2533..bef469e 100644 --- a/vendordeps/photonlib.json +++ b/vendordeps/photonlib.json @@ -1,7 +1,7 @@ { "fileName": "photonlib.json", "name": "photonlib", - "version": "v2024.2.10", + "version": "v2024.3.1", "uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004", "frcYear": "2024", "mavenUrls": [ @@ -14,7 +14,7 @@ { "groupId": "org.photonvision", "artifactId": "photonlib-cpp", - "version": "v2024.2.10", + "version": "v2024.3.1", "libName": "photonlib", "headerClassifier": "headers", "sharedLibrary": true, @@ -29,7 +29,7 @@ { "groupId": "org.photonvision", "artifactId": "photontargeting-cpp", - "version": "v2024.2.10", + "version": "v2024.3.1", "libName": "photontargeting", "headerClassifier": "headers", "sharedLibrary": true, @@ -46,12 +46,12 @@ { "groupId": "org.photonvision", "artifactId": "photonlib-java", - "version": "v2024.2.10" + "version": "v2024.3.1" }, { "groupId": "org.photonvision", "artifactId": "photontargeting-java", - "version": "v2024.2.10" + "version": "v2024.3.1" } ] }