From 85f2a96646ec2e2dc755ffb33d9fd9da1422463c Mon Sep 17 00:00:00 2001 From: sbx-work Date: Mon, 12 Jan 2026 09:01:20 -0700 Subject: [PATCH 1/4] Fix YAGSL Swerve Configurator link in INSTALL.md (#100) Updated link for YAGSL Swerve Configurator in INSTALL.md. --- INSTALL.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/INSTALL.md b/INSTALL.md index 18d6a57..c9ba218 100644 --- a/INSTALL.md +++ b/INSTALL.md @@ -94,7 +94,7 @@ steps you need to complete: **NOTE:** If you have any other combination of hardware (including REV NEOs, NavX IMU, etc.) you will need to use the [YAGSL Swerve Configurator]( -https://broncbotz3481.github.io/YAGSL-Example/) to configure the inputs for +https://yet-another-software-suite.github.io/YAGSL/config_generator/) to configure the inputs for your robot. **Since the reference build recommends an all-CTRE swerve base**, this functionality has not been extensively tested. Any teams that adopt this method are encouraged to submit bug reports and code fixes to the [Az-RBSI From 38868958bfa9c1144b71eff366d8bd46a6ee50b0 Mon Sep 17 00:00:00 2001 From: Timothy Ellsworth Bowers Date: Tue, 13 Jan 2026 08:33:33 -0700 Subject: [PATCH 2/4] Read GameData from the FMS for when a robot's HUB will be active (#104) Read randomization data from FMS The status of both HUBS during the ALLIANCE SHIFTS is based on the results of AUTO. The ALLIANCE that scores the most FUEL during AUTO will have their HUB set to inactive for SHIFT 1 while their opponent's HUB will be active This commit adds the basic machinery to read the FMS data and provides a boolean function that returns whether the robot's alliance HUB is active at the present moment in the form of `FieldState.isHubActive()`. --- src/main/java/frc/robot/FieldState.java | 111 ++++++++++++++++++++++++ src/main/java/frc/robot/Robot.java | 32 ++++++- 2 files changed, 142 insertions(+), 1 deletion(-) create mode 100644 src/main/java/frc/robot/FieldState.java diff --git a/src/main/java/frc/robot/FieldState.java b/src/main/java/frc/robot/FieldState.java new file mode 100644 index 0000000..0a3f40e --- /dev/null +++ b/src/main/java/frc/robot/FieldState.java @@ -0,0 +1,111 @@ +// Copyright (c) 2026 Az-FIRST +// http://github.com/AZ-First +// +// This program is free software; you can redistribute it and/or +// modify it under the terms of the GNU General Public License +// version 3 as published by the Free Software Foundation or +// available in the root directory of this project. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot; + +import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.wpilibj.DriverStation.Alliance; +import frc.robot.util.Alert; + +public class FieldState { + + /** + * FOR 2026 - REBUILT, store the data from the FMS about the TeleOp shifts here + * + *

Once the FMS chooses an alliance, this value will become either 'B' or 'R' for which + * alliance's HUB is INACTIVE first. + * + *

If this variable is 'B', then BLUE is ACTIVE during Shift 2 and Shift 4 (and RED is ACTIVE + * during Shift 1 and Shift 3). + * + *

If this variable is 'R', then RED is ACTIVE during Shift 2 and Shift 4 (and BLUE is ACTIVE + * during Shift 1 and Shift 3). + * + *

========== TESTING ========== + * + *

You can test your Game Specific Data code without FMS by using the Driver Station. Click on + * the Setup tab of the Driver Station, then enter the desired test string into the Game Data text + * field. The data will be transmitted to the robot in one of two conditions: Enable the robot in + * Teleop mode, or when the DS reaches the End Game time in a Practice Match (times are + * configurable on the Setup tab). It is recommended to run at least one match using the Practice + * functionality to verify that your code works correctly in a full match flow. + */ + public static Alliance wonAuto = null; + + /** + * Check whether the HUB is active right now + * + * @return Whether the team's alliance's HUB is active right now + */ + public static boolean isHubActive() { + + // The HUB is active for both alliances in AUTO + if (DriverStation.isAutonomous()) { + return true; + } + + // The HUB is not active when not in AUTO or TELEOP + if (!DriverStation.isTeleop()) { + return false; + } + + // Read in the current match time & get alliance + // TODO: Since the ``DriverStation.getMatchTime()`` returns INT:: + // Return the approximate match time. The FMS does not send an + // official match time to the robots, but does send an approximate + // match time. The value will count down the time remaining in the + // current period (auto or teleop). Warning: This is not an official + // time (so it cannot be used to dispute ref calls or guarantee that + // a function will trigger before the match ends). + double timeRemaining = DriverStation.getMatchTime(); + Alliance alliance = DriverStation.getAlliance().orElse(Alliance.Blue); + + // If the FMS has not provided an alliance yet, set to TRUE and kick an Alert! + if (timeRemaining < 130.0 && wonAuto == null) { + new Alert( + "No HUB data from FMS! HUB is listed as ACTIVE! Driver BEWARE!", + Alert.AlertType.WARNING) + .set(true); + return true; + } + + if (timeRemaining >= 130.0) { + // TRANSITION SHIFT -- Both HUBs active + return true; + + } else if (timeRemaining >= 105.0) { + // SHIFT 1 -- Non-winning alliance gets a first go + return !(wonAuto == alliance); + + } else if (timeRemaining >= 80.0) { + // SHIFT 2 -- Winning alliance gets a chance + return (wonAuto == alliance); + + } else if (timeRemaining >= 55.0) { + // SHIFT 3 -- Trade off + return !(wonAuto == alliance); + + } else if (timeRemaining >= 30.0) { + // SHIFT 4 -- Trade off again + return (wonAuto == alliance); + + } else { + // ENDGAME -- Both HUBs active + return true; + } + } +} diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index 5b56661..54dfc56 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -18,6 +18,7 @@ package frc.robot; import com.revrobotics.util.StatusLogger; +import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.Threads; import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj2.command.Command; @@ -191,7 +192,36 @@ public void teleopInit() { /** This function is called periodically during operator control. */ @Override - public void teleopPeriodic() {} + public void teleopPeriodic() { + + // For 2026 - REBUILT, the alliance will be provided as a single character + // representing the color of the alliance whose goal will go inactive + // first (i.e. ‘R’ = red, ‘B’ = blue). This alliance’s goal will be + // active in Shifts 2 and 4. + // + // https://docs.wpilib.org/en/stable/docs/yearly-overview/2026-game-data.html + if (FieldState.wonAuto == null) { + // Only call this code block if the signal from FMS has not yet arrived + String gameData = DriverStation.getGameSpecificMessage(); + if (gameData.length() > 0) { + switch (gameData.charAt(0)) { + case 'B': + // Blue case code + FieldState.wonAuto = DriverStation.Alliance.Blue; + break; + case 'R': + // Red case code + FieldState.wonAuto = DriverStation.Alliance.Red; + break; + default: + // This is corrupt data, do nothing + break; + } + } + } + // Anything else for the teleopPeriodic() function + + } /** This function is called once when test mode is enabled. */ @Override From 51b0c754dc95fb5ff43357dc4b961812d79edfdf Mon Sep 17 00:00:00 2001 From: Timothy Ellsworth Bowers Date: Tue, 13 Jan 2026 14:49:26 -0700 Subject: [PATCH 3/4] Improve current smoothing for drivebase and example flywheel (#106) * Add more current smoothing to the swerve modules -- This commit focuses on the CTRE / TalonFX(S) controllers. Still need to do the same for the REV SPARK controllers. * Add current smoothing to SPARK drivebase motors * Add current smoothing to Example Flywheel * Move hardcoded values to ``Constants.java`` --- src/main/java/frc/robot/Constants.java | 14 ++ .../subsystems/drive/ModuleIOBlended.java | 162 ++++++++++++++---- .../robot/subsystems/drive/ModuleIOSpark.java | 112 +++++++++--- .../drive/ModuleIOSparkCANcoder.java | 114 +++++++++--- .../subsystems/drive/ModuleIOTalonFX.java | 115 +++++++++++-- .../subsystems/drive/ModuleIOTalonFXS.java | 113 ++++++++++-- .../subsystems/drive/SwerveConstants.java | 3 - .../subsystems/flywheel_example/Flywheel.java | 2 + .../flywheel_example/FlywheelIO.java | 6 + .../flywheel_example/FlywheelIOSpark.java | 26 ++- .../flywheel_example/FlywheelIOTalonFX.java | 63 ++++++- 11 files changed, 599 insertions(+), 131 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index c0829ec..797d8bd 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -274,6 +274,14 @@ public static final class DrivebaseConstants { public static final double kQuasiTimeout = 5.0; // seconds public static final double kDynamicTimeout = 3.0; // seconds + // Drive motor open-loop and closed-loop ramp periods for current smoothing + // Time from from 0 -> full duty + public static final double kDriveClosedLoopRampPeriod = 0.15; // seconds + public static final double kDriveOpenLoopRampPeriod = 0.25; // seconds + + public static final double kOptimalVoltage = 12.0; // Volts + public static final double kNominalFFVolts = 2.0; // Volts + // Default TalonFX Gains (Replaces what's in Phoenix X's Tuner Constants) // NOTE: Default values from 6328's 2025 Public Code // @@ -282,6 +290,7 @@ public static final class DrivebaseConstants { public static final double kDriveP = 40.0; public static final double kDriveD = 0.03; public static final double kDriveV = 0.83; + public static final double kDriveA = 0.0; public static final double kDriveS = 0.21; public static final double kDriveT = SwerveConstants.kDriveGearRatio / DCMotor.getKrakenX60Foc(1).KtNMPerAmp; @@ -299,6 +308,11 @@ public static final class FlywheelConstants { // Mechanism motor gear ratio public static final double kFlywheelGearRatio = 1.5; + // Flywheel motor open-loop and closed-loop ramp periods for current smoothing + // Time from from 0 -> full duty + public static final double kFlywheelClosedLoopRampPeriod = 0.15; // seconds + public static final double kFlywheelOpenLoopRampPeriod = 0.25; // seconds + // MODE == REAL / REPLAY // Feedforward constants public static final double kStaticGainReal = 0.1; diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOBlended.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOBlended.java index b8d66f1..614b9f3 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOBlended.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOBlended.java @@ -9,11 +9,15 @@ package frc.robot.subsystems.drive; +import static edu.wpi.first.units.Units.RotationsPerSecond; import static frc.robot.subsystems.drive.SwerveConstants.*; import com.ctre.phoenix6.BaseStatusSignal; import com.ctre.phoenix6.StatusSignal; import com.ctre.phoenix6.configs.CANcoderConfiguration; +import com.ctre.phoenix6.configs.ClosedLoopRampsConfigs; +import com.ctre.phoenix6.configs.OpenLoopRampsConfigs; +import com.ctre.phoenix6.configs.Slot0Configs; import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.ctre.phoenix6.controls.TorqueCurrentFOC; import com.ctre.phoenix6.controls.VelocityTorqueCurrentFOC; @@ -46,11 +50,13 @@ import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.units.measure.Current; import edu.wpi.first.units.measure.Voltage; +import edu.wpi.first.wpilibj.RobotController; import frc.robot.Constants; -import frc.robot.Constants.AutoConstants; +import frc.robot.Constants.DrivebaseConstants; import frc.robot.util.PhoenixUtil; import frc.robot.util.SparkUtil; import java.util.Queue; +import org.littletonrobotics.junction.Logger; /** * Module IO implementation for blended TalonFX drive motor controller, SparkMax turn motor @@ -66,10 +72,15 @@ public class ModuleIOBlended implements ModuleIO { TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> constants; - // CAN Devices + // Hardware Objects private final TalonFX driveTalon; private final SparkBase turnSpark; private final CANcoder cancoder; + private final ClosedLoopOutputType m_DriveMotorClosedLoopOutput = + switch (Constants.getPhoenixPro()) { + case LICENSED -> ClosedLoopOutputType.TorqueCurrentFOC; + case UNLICENSED -> ClosedLoopOutputType.Voltage; + }; // Closed loop controllers private final SparkClosedLoopController turnController; @@ -100,9 +111,20 @@ public class ModuleIOBlended implements ModuleIO { private final StatusSignal turnVelocity; // Connection debouncers - private final Debouncer driveConnectedDebounce = new Debouncer(0.5); - private final Debouncer turnConnectedDebounce = new Debouncer(0.5); - private final Debouncer turnEncoderConnectedDebounce = new Debouncer(0.5); + private final Debouncer driveConnectedDebounce = + new Debouncer(0.5, Debouncer.DebounceType.kFalling); + private final Debouncer turnConnectedDebounce = + new Debouncer(0.5, Debouncer.DebounceType.kFalling); + private final Debouncer turnEncoderConnectedDebounce = + new Debouncer(0.5, Debouncer.DebounceType.kFalling); + + // Config + private final TalonFXConfiguration driveConfig = new TalonFXConfiguration(); + private final SparkMaxConfig turnConfig = new SparkMaxConfig(); + + // Values used for calculating feedforward from kS, kV, and kA + private double lastVelocityRotPerSec = 0.0; + private long lastTimestampNano = System.nanoTime(); /* * Blended Module I/O, using Falcon drive and NEO steer motors @@ -167,26 +189,43 @@ public ModuleIOBlended(int module) { turnController = turnSpark.getClosedLoopController(); // Configure drive motor - var driveConfig = constants.DriveMotorInitialConfigs; driveConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; - driveConfig.Slot0 = constants.DriveMotorGains; + driveConfig.Slot0 = + new Slot0Configs() + .withKP(DrivebaseConstants.kDriveP) + .withKI(0.0) + .withKD(DrivebaseConstants.kDriveD) + .withKS(DrivebaseConstants.kDriveS) + .withKV(DrivebaseConstants.kDriveV) + .withKA(DrivebaseConstants.kDriveA); driveConfig.Feedback.SensorToMechanismRatio = SwerveConstants.kDriveGearRatio; driveConfig.TorqueCurrent.PeakForwardTorqueCurrent = SwerveConstants.kDriveSlipCurrent; driveConfig.TorqueCurrent.PeakReverseTorqueCurrent = -SwerveConstants.kDriveSlipCurrent; driveConfig.CurrentLimits.StatorCurrentLimit = SwerveConstants.kDriveCurrentLimit; driveConfig.CurrentLimits.StatorCurrentLimitEnable = true; + // Build the OpenLoopRampsConfigs and ClosedLoopRampsConfigs for current smoothing + OpenLoopRampsConfigs openRamps = new OpenLoopRampsConfigs(); + openRamps.DutyCycleOpenLoopRampPeriod = DrivebaseConstants.kDriveOpenLoopRampPeriod; + openRamps.VoltageOpenLoopRampPeriod = DrivebaseConstants.kDriveOpenLoopRampPeriod; + openRamps.TorqueOpenLoopRampPeriod = DrivebaseConstants.kDriveOpenLoopRampPeriod; + ClosedLoopRampsConfigs closedRamps = new ClosedLoopRampsConfigs(); + closedRamps.DutyCycleClosedLoopRampPeriod = DrivebaseConstants.kDriveClosedLoopRampPeriod; + closedRamps.VoltageClosedLoopRampPeriod = DrivebaseConstants.kDriveClosedLoopRampPeriod; + closedRamps.TorqueClosedLoopRampPeriod = DrivebaseConstants.kDriveClosedLoopRampPeriod; + // Apply the open- and closed-loop ramp configuration for current smoothing + driveConfig.withClosedLoopRamps(closedRamps).withOpenLoopRamps(openRamps); + // Set motor inversions driveConfig.MotorOutput.Inverted = constants.DriveMotorInverted ? InvertedValue.Clockwise_Positive : InvertedValue.CounterClockwise_Positive; // Configure turn motor - var turnConfig = new SparkMaxConfig(); turnConfig .inverted(constants.SteerMotorInverted) .idleMode(IdleMode.kBrake) .smartCurrentLimit((int) SwerveConstants.kSteerCurrentLimit) - .voltageCompensation(12.0); + .voltageCompensation(DrivebaseConstants.kOptimalVoltage); turnConfig .absoluteEncoder .inverted(constants.EncoderInverted) @@ -198,10 +237,7 @@ public ModuleIOBlended(int module) { .feedbackSensor(FeedbackSensor.kAbsoluteEncoder) .positionWrappingEnabled(true) .positionWrappingInputRange(turnPIDMinInput, turnPIDMaxInput) - .pid( - AutoConstants.kPPsteerPID.kP, - AutoConstants.kPPsteerPID.kI, - AutoConstants.kPPsteerPID.kD) + .pid(DrivebaseConstants.kSteerP, 0.0, DrivebaseConstants.kSteerD) .feedForward .kV(0.0); turnConfig @@ -209,16 +245,13 @@ public ModuleIOBlended(int module) { .absoluteEncoderPositionAlwaysOn(true) .absoluteEncoderPositionPeriodMs((int) (1000.0 / kOdometryFrequency)) .absoluteEncoderVelocityAlwaysOn(true) - .absoluteEncoderVelocityPeriodMs(20) - .appliedOutputPeriodMs(20) - .busVoltagePeriodMs(20) - .outputCurrentPeriodMs(20); - SparkUtil.tryUntilOk( - turnSpark, - 5, - () -> - turnSpark.configure( - turnConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters)); + .absoluteEncoderVelocityPeriodMs((int) (Constants.loopPeriodSecs * 1000.)) + .appliedOutputPeriodMs((int) (Constants.loopPeriodSecs * 1000.)) + .busVoltagePeriodMs((int) (Constants.loopPeriodSecs * 1000.)) + .outputCurrentPeriodMs((int) (Constants.loopPeriodSecs * 1000.)); + turnConfig + .openLoopRampRate(DrivebaseConstants.kDriveOpenLoopRampPeriod) + .closedLoopRampRate(DrivebaseConstants.kDriveClosedLoopRampPeriod); // Configure CANCoder CANcoderConfiguration cancoderConfig = constants.EncoderInitialConfigs; @@ -238,6 +271,12 @@ public ModuleIOBlended(int module) { // Finally, apply the configs to the motor controllers PhoenixUtil.tryUntilOk(5, () -> driveTalon.getConfigurator().apply(driveConfig, 0.25)); PhoenixUtil.tryUntilOk(5, () -> driveTalon.setPosition(0.0, 0.25)); + SparkUtil.tryUntilOk( + turnSpark, + 5, + () -> + turnSpark.configure( + turnConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters)); cancoder.getConfigurator().apply(cancoderConfig); // Create timestamp queue @@ -303,30 +342,93 @@ public void updateInputs(ModuleIOInputs inputs) { turnPositionQueue.clear(); } + /** + * Set the drive motor to an open-loop voltage, scaled to battery voltage + * + * @param output Specified open-loop voltage requested + */ @Override public void setDriveOpenLoop(double output) { + // Scale by actual battery voltage to keep full output consistent + double busVoltage = RobotController.getBatteryVoltage(); + double scaledOutput = output * DrivebaseConstants.kOptimalVoltage / busVoltage; + driveTalon.setControl( - switch (constants.DriveMotorClosedLoopOutput) { - case Voltage -> voltageRequest.withOutput(output); - case TorqueCurrentFOC -> torqueCurrentRequest.withOutput(output); + switch (m_DriveMotorClosedLoopOutput) { + case Voltage -> voltageRequest.withOutput(scaledOutput); + case TorqueCurrentFOC -> torqueCurrentRequest.withOutput(scaledOutput); }); + + // Log output and battery + Logger.recordOutput("Swerve/Drive/OpenLoopOutput", scaledOutput); + Logger.recordOutput("Robot/BatteryVoltage", busVoltage); } + /** + * Set the turn motor to an open-loop voltage, scaled to battery voltage + * + * @param output Specified open-loop voltage requested + */ @Override public void setTurnOpenLoop(double output) { - turnSpark.setVoltage(output); + double busVoltage = RobotController.getBatteryVoltage(); + double scaledOutput = output * DrivebaseConstants.kOptimalVoltage / busVoltage; + turnSpark.setVoltage(scaledOutput); + + // Log output and battery + Logger.recordOutput("Swerve/Turn/OpenLoopOutput", scaledOutput); + Logger.recordOutput("Robot/BatteryVoltage", busVoltage); } + /** + * Set the velocity of the module + * + * @param velocityRadPerSec Requested module drive velocity in radians per second + */ @Override public void setDriveVelocity(double velocityRadPerSec) { double velocityRotPerSec = Units.radiansToRotations(velocityRadPerSec); + double busVoltage = RobotController.getBatteryVoltage(); + + // Compute the Feedforward voltage for CTRE UNLICENSED operation ***** + // Compute acceleration + long currentTimeNano = System.nanoTime(); + double deltaTimeSec = (currentTimeNano - lastTimestampNano) * 1e-9; + double accelerationRotPerSec2 = + deltaTimeSec > 0 ? (velocityRotPerSec - lastVelocityRotPerSec) / deltaTimeSec : 0.0; + // Update last values for next loop + lastVelocityRotPerSec = velocityRotPerSec; + lastTimestampNano = currentTimeNano; + // Compute feedforward voltage: kS + kV*v + kA*a + double nominalFFVolts = + Math.signum(velocityRotPerSec) * DrivebaseConstants.kDriveS + + DrivebaseConstants.kDriveV * velocityRotPerSec + + DrivebaseConstants.kDriveA * accelerationRotPerSec2; + double scaledFFVolts = nominalFFVolts * DrivebaseConstants.kOptimalVoltage / busVoltage; + + // Set the drive motor control based on CTRE LICENSED status driveTalon.setControl( - switch (constants.DriveMotorClosedLoopOutput) { - case Voltage -> velocityVoltageRequest.withVelocity(velocityRotPerSec); - case TorqueCurrentFOC -> velocityTorqueCurrentRequest.withVelocity(velocityRotPerSec); + switch (m_DriveMotorClosedLoopOutput) { + case Voltage -> + velocityVoltageRequest.withVelocity(velocityRotPerSec).withFeedForward(scaledFFVolts); + case TorqueCurrentFOC -> + velocityTorqueCurrentRequest.withVelocity(RotationsPerSecond.of(velocityRotPerSec)); }); + + // AdvantageKit logging + Logger.recordOutput("Swerve/Drive/VelocityRadPerSec", velocityRadPerSec); + Logger.recordOutput("Swerve/Drive/VelocityRotPerSec", velocityRotPerSec); + Logger.recordOutput("Swerve/Drive/AccelerationRotPerSec2", accelerationRotPerSec2); + Logger.recordOutput("Swerve/Drive/FeedForwardVolts", scaledFFVolts); + Logger.recordOutput("Robot/BatteryVoltage", busVoltage); + Logger.recordOutput("Swerve/Drive/ClosedLoopMode", m_DriveMotorClosedLoopOutput); } + /** + * Set the turn position of the module + * + * @param rotation Requested module Rotation2d position + */ @Override public void setTurnPosition(Rotation2d rotation) { double setpoint = diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java index 4c59c5f..996194c 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java @@ -30,10 +30,13 @@ import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.filter.Debouncer; import edu.wpi.first.math.geometry.Rotation2d; -import frc.robot.Constants.AutoConstants; +import edu.wpi.first.wpilibj.RobotController; +import frc.robot.Constants; +import frc.robot.Constants.DrivebaseConstants; import frc.robot.util.SparkUtil; import java.util.Queue; import java.util.function.DoubleSupplier; +import org.littletonrobotics.junction.Logger; /** * Module IO implementation for Spark Flex drive motor controller, Spark Max turn motor controller, @@ -60,9 +63,18 @@ public class ModuleIOSpark implements ModuleIO { private final Queue turnPositionQueue; // Connection debouncers - private final Debouncer driveConnectedDebounce = new Debouncer(0.5); - private final Debouncer turnConnectedDebounce = new Debouncer(0.5); + private final Debouncer driveConnectedDebounce = + new Debouncer(0.5, Debouncer.DebounceType.kFalling); + private final Debouncer turnConnectedDebounce = + new Debouncer(0.5, Debouncer.DebounceType.kFalling); + // Values used for calculating feedforward from kS, kV, and kA + private double lastVelocityRotPerSec = 0.0; + private long lastTimestampNano = System.nanoTime(); + + /* + * SparkI/O + */ public ModuleIOSpark(int module) { zeroRotation = switch (module) { @@ -118,7 +130,7 @@ public ModuleIOSpark(int module) { driveConfig .idleMode(IdleMode.kBrake) .smartCurrentLimit((int) kDriveCurrentLimit) - .voltageCompensation(12.0); + .voltageCompensation(DrivebaseConstants.kOptimalVoltage); driveConfig .encoder .positionConversionFactor(driveEncoderPositionFactor) @@ -128,21 +140,22 @@ public ModuleIOSpark(int module) { driveConfig .closedLoop .feedbackSensor(FeedbackSensor.kPrimaryEncoder) - .pid( - AutoConstants.kPPdrivePID.kP, - AutoConstants.kPPdrivePID.kI, - AutoConstants.kPPdrivePID.kD) + .pid(DrivebaseConstants.kDriveP, 0.0, DrivebaseConstants.kDriveD) .feedForward - .kV(0.0); + .kV(DrivebaseConstants.kDriveV) + .kS(DrivebaseConstants.kDriveS); driveConfig .signals .primaryEncoderPositionAlwaysOn(true) .primaryEncoderPositionPeriodMs((int) (1000.0 / kOdometryFrequency)) .primaryEncoderVelocityAlwaysOn(true) - .primaryEncoderVelocityPeriodMs(20) - .appliedOutputPeriodMs(20) - .busVoltagePeriodMs(20) - .outputCurrentPeriodMs(20); + .primaryEncoderVelocityPeriodMs((int) (Constants.loopPeriodSecs * 1000.)) + .appliedOutputPeriodMs((int) (Constants.loopPeriodSecs * 1000.)) + .busVoltagePeriodMs((int) (Constants.loopPeriodSecs * 1000.)) + .outputCurrentPeriodMs((int) (Constants.loopPeriodSecs * 1000.)); + driveConfig + .openLoopRampRate(DrivebaseConstants.kDriveOpenLoopRampPeriod) + .closedLoopRampRate(DrivebaseConstants.kDriveClosedLoopRampPeriod); SparkUtil.tryUntilOk( driveSpark, 5, @@ -157,7 +170,7 @@ public ModuleIOSpark(int module) { .inverted(turnInverted) .idleMode(IdleMode.kBrake) .smartCurrentLimit((int) SwerveConstants.kSteerCurrentLimit) - .voltageCompensation(12.0); + .voltageCompensation(DrivebaseConstants.kOptimalVoltage); turnConfig .absoluteEncoder .inverted(turnEncoderInverted) @@ -169,10 +182,7 @@ public ModuleIOSpark(int module) { .feedbackSensor(FeedbackSensor.kAbsoluteEncoder) .positionWrappingEnabled(true) .positionWrappingInputRange(turnPIDMinInput, turnPIDMaxInput) - .pid( - AutoConstants.kPPsteerPID.kP, - AutoConstants.kPPsteerPID.kI, - AutoConstants.kPPsteerPID.kD) + .pid(DrivebaseConstants.kSteerP, 0.0, DrivebaseConstants.kSteerD) .feedForward .kV(0.0); turnConfig @@ -180,10 +190,13 @@ public ModuleIOSpark(int module) { .absoluteEncoderPositionAlwaysOn(true) .absoluteEncoderPositionPeriodMs((int) (1000.0 / kOdometryFrequency)) .absoluteEncoderVelocityAlwaysOn(true) - .absoluteEncoderVelocityPeriodMs(20) - .appliedOutputPeriodMs(20) - .busVoltagePeriodMs(20) - .outputCurrentPeriodMs(20); + .absoluteEncoderVelocityPeriodMs((int) (Constants.loopPeriodSecs * 1000.)) + .appliedOutputPeriodMs((int) (Constants.loopPeriodSecs * 1000.)) + .busVoltagePeriodMs((int) (Constants.loopPeriodSecs * 1000.)) + .outputCurrentPeriodMs((int) (Constants.loopPeriodSecs * 1000.)); + turnConfig + .openLoopRampRate(DrivebaseConstants.kDriveOpenLoopRampPeriod) + .closedLoopRampRate(DrivebaseConstants.kDriveClosedLoopRampPeriod); SparkUtil.tryUntilOk( turnSpark, 5, @@ -245,29 +258,76 @@ public void updateInputs(ModuleIOInputs inputs) { turnPositionQueue.clear(); } + /** + * Set the drive motor to an open-loop voltage, scaled to battery voltage + * + * @param output Specified open-loop voltage requested + */ @Override public void setDriveOpenLoop(double output) { driveSpark.setVoltage(output); + + // Log output and battery + Logger.recordOutput("Swerve/Drive/OpenLoopOutput", output); } + /** + * Set the turn motor to an open-loop voltage, scaled to battery voltage + * + * @param output Specified open-loop voltage requested + */ @Override public void setTurnOpenLoop(double output) { turnSpark.setVoltage(output); + + // Log output and battery + Logger.recordOutput("Swerve/Turn/OpenLoopOutput", output); } + /** + * Set the velocity of the module + * + * @param velocityRadPerSec Requested module drive velocity in radians per second + */ @Override public void setDriveVelocity(double velocityRadPerSec) { - double ffVolts = - SwerveConstants.kDriveFrictionVoltage * Math.signum(velocityRadPerSec) - + driveKv * velocityRadPerSec; + // Compute acceleration for feedforward + long currentTimeNano = System.nanoTime(); + double deltaTimeSec = (currentTimeNano - lastTimestampNano) * 1e-9; + double accelerationRadPerSec2 = + deltaTimeSec > 0 ? (velocityRadPerSec - lastVelocityRotPerSec) / deltaTimeSec : 0.0; + + lastVelocityRotPerSec = velocityRadPerSec; + lastTimestampNano = currentTimeNano; + + // Feedforward using kS, kV, kA + double nominalFFVolts = + Math.signum(velocityRadPerSec) * DrivebaseConstants.kDriveS + + DrivebaseConstants.kDriveV * velocityRadPerSec + + DrivebaseConstants.kDriveA * accelerationRadPerSec2; + + double busVoltage = RobotController.getBatteryVoltage(); + double scaledFFVolts = nominalFFVolts * DrivebaseConstants.kOptimalVoltage / busVoltage; + driveController.setSetpoint( velocityRadPerSec, ControlType.kVelocity, ClosedLoopSlot.kSlot0, - ffVolts, + scaledFFVolts, ArbFFUnits.kVoltage); + + // Logging + Logger.recordOutput("Swerve/Drive/ClosedLoopVelocityRadPerSec", velocityRadPerSec); + Logger.recordOutput("Swerve/Drive/ClosedLoopAccelRadPerSec2", accelerationRadPerSec2); + Logger.recordOutput("Swerve/Drive/ClosedLoopFFVolts", scaledFFVolts); + Logger.recordOutput("Robot/BatteryVoltage", busVoltage); } + /** + * Set the turn position of the module + * + * @param rotation Requested module Rotation2d position + */ @Override public void setTurnPosition(Rotation2d rotation) { double setpoint = diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkCANcoder.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkCANcoder.java index 6ebdd07..a79837e 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkCANcoder.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkCANcoder.java @@ -35,10 +35,13 @@ import edu.wpi.first.math.util.Units; import edu.wpi.first.units.measure.Angle; import edu.wpi.first.units.measure.AngularVelocity; -import frc.robot.Constants.AutoConstants; +import edu.wpi.first.wpilibj.RobotController; +import frc.robot.Constants; +import frc.robot.Constants.DrivebaseConstants; import frc.robot.util.SparkUtil; import java.util.Queue; import java.util.function.DoubleSupplier; +import org.littletonrobotics.junction.Logger; /** * Module IO implementation for Spark Flex drive motor controller, Spark Max turn motor controller, @@ -70,10 +73,20 @@ public class ModuleIOSparkCANcoder implements ModuleIO { private final Queue turnPositionQueue; // Connection debouncers - private final Debouncer driveConnectedDebounce = new Debouncer(0.5); - private final Debouncer turnConnectedDebounce = new Debouncer(0.5); - private final Debouncer turnEncoderConnectedDebounce = new Debouncer(0.5); + private final Debouncer driveConnectedDebounce = + new Debouncer(0.5, Debouncer.DebounceType.kFalling); + private final Debouncer turnConnectedDebounce = + new Debouncer(0.5, Debouncer.DebounceType.kFalling); + private final Debouncer turnEncoderConnectedDebounce = + new Debouncer(0.5, Debouncer.DebounceType.kFalling); + // Values used for calculating feedforward from kS, kV, and kA + private double lastVelocityRotPerSec = 0.0; + private long lastTimestampNano = System.nanoTime(); + + /* + * Spark I/O w/ CANcoders + */ public ModuleIOSparkCANcoder(int module) { zeroRotation = switch (module) { @@ -138,7 +151,7 @@ public ModuleIOSparkCANcoder(int module) { driveConfig .idleMode(IdleMode.kBrake) .smartCurrentLimit((int) kDriveCurrentLimit) - .voltageCompensation(12.0); + .voltageCompensation(DrivebaseConstants.kOptimalVoltage); driveConfig .encoder .positionConversionFactor(driveEncoderPositionFactor) @@ -148,12 +161,10 @@ public ModuleIOSparkCANcoder(int module) { driveConfig .closedLoop .feedbackSensor(FeedbackSensor.kPrimaryEncoder) - .pid( - AutoConstants.kPPdrivePID.kP, - AutoConstants.kPPdrivePID.kI, - AutoConstants.kPPdrivePID.kD) + .pid(DrivebaseConstants.kDriveP, 0.0, DrivebaseConstants.kDriveD) .feedForward - .kV(0.0); + .kV(DrivebaseConstants.kDriveV) + .kS(DrivebaseConstants.kDriveS); driveConfig .signals .primaryEncoderPositionAlwaysOn(true) @@ -177,7 +188,7 @@ public ModuleIOSparkCANcoder(int module) { .inverted(turnInverted) .idleMode(IdleMode.kBrake) .smartCurrentLimit((int) SwerveConstants.kSteerCurrentLimit) - .voltageCompensation(12.0); + .voltageCompensation(DrivebaseConstants.kOptimalVoltage); turnConfig .absoluteEncoder .inverted(turnEncoderInverted) @@ -189,10 +200,7 @@ public ModuleIOSparkCANcoder(int module) { .feedbackSensor(FeedbackSensor.kAbsoluteEncoder) .positionWrappingEnabled(true) .positionWrappingInputRange(turnPIDMinInput, turnPIDMaxInput) - .pid( - AutoConstants.kPPsteerPID.kP, - AutoConstants.kPPsteerPID.kI, - AutoConstants.kPPsteerPID.kD) + .pid(DrivebaseConstants.kSteerP, 0.0, DrivebaseConstants.kSteerD) .feedForward .kV(0.0); turnConfig @@ -200,10 +208,13 @@ public ModuleIOSparkCANcoder(int module) { .absoluteEncoderPositionAlwaysOn(true) .absoluteEncoderPositionPeriodMs((int) (1000.0 / kOdometryFrequency)) .absoluteEncoderVelocityAlwaysOn(true) - .absoluteEncoderVelocityPeriodMs(20) - .appliedOutputPeriodMs(20) - .busVoltagePeriodMs(20) - .outputCurrentPeriodMs(20); + .absoluteEncoderVelocityPeriodMs((int) (Constants.loopPeriodSecs * 1000.)) + .appliedOutputPeriodMs((int) (Constants.loopPeriodSecs * 1000.)) + .busVoltagePeriodMs((int) (Constants.loopPeriodSecs * 1000.)) + .outputCurrentPeriodMs((int) (Constants.loopPeriodSecs * 1000.)); + turnConfig + .openLoopRampRate(DrivebaseConstants.kDriveOpenLoopRampPeriod) + .closedLoopRampRate(DrivebaseConstants.kDriveClosedLoopRampPeriod); SparkUtil.tryUntilOk( turnSpark, 5, @@ -271,29 +282,82 @@ public void updateInputs(ModuleIOInputs inputs) { turnPositionQueue.clear(); } + /** + * Set the drive motor to an open-loop voltage, scaled to battery voltage + * + * @param output Specified open-loop voltage requested + */ @Override public void setDriveOpenLoop(double output) { - driveSpark.setVoltage(output); + double busVoltage = RobotController.getBatteryVoltage(); + double scaledOutput = output * DrivebaseConstants.kOptimalVoltage / busVoltage; + driveSpark.setVoltage(scaledOutput); + + // Log output and battery + Logger.recordOutput("Swerve/Drive/OpenLoopOutput", scaledOutput); + Logger.recordOutput("Robot/BatteryVoltage", busVoltage); } + /** + * Set the turn motor to an open-loop voltage, scaled to battery voltage + * + * @param output Specified open-loop voltage requested + */ @Override public void setTurnOpenLoop(double output) { - turnSpark.setVoltage(output); + double busVoltage = RobotController.getBatteryVoltage(); + double scaledOutput = output * DrivebaseConstants.kOptimalVoltage / busVoltage; + turnSpark.setVoltage(scaledOutput); + + // Log output and battery + Logger.recordOutput("Swerve/Turn/OpenLoopOutput", scaledOutput); + Logger.recordOutput("Robot/BatteryVoltage", busVoltage); } + /** + * Set the velocity of the module + * + * @param velocityRadPerSec Requested module drive velocity in radians per second + */ @Override public void setDriveVelocity(double velocityRadPerSec) { - double ffVolts = - SwerveConstants.kDriveFrictionVoltage * Math.signum(velocityRadPerSec) - + driveKv * velocityRadPerSec; + // Compute acceleration for feedforward + long currentTimeNano = System.nanoTime(); + double deltaTimeSec = (currentTimeNano - lastTimestampNano) * 1e-9; + double accelerationRadPerSec2 = + deltaTimeSec > 0 ? (velocityRadPerSec - lastVelocityRotPerSec) / deltaTimeSec : 0.0; + + lastVelocityRotPerSec = velocityRadPerSec; + lastTimestampNano = currentTimeNano; + + // Feedforward using kS, kV, kA + double nominalFFVolts = + Math.signum(velocityRadPerSec) * DrivebaseConstants.kDriveS + + DrivebaseConstants.kDriveV * velocityRadPerSec + + DrivebaseConstants.kDriveA * accelerationRadPerSec2; + + double busVoltage = RobotController.getBatteryVoltage(); + double scaledFFVolts = nominalFFVolts * DrivebaseConstants.kOptimalVoltage / busVoltage; + driveController.setSetpoint( velocityRadPerSec, ControlType.kVelocity, ClosedLoopSlot.kSlot0, - ffVolts, + scaledFFVolts, ArbFFUnits.kVoltage); + + // Logging + Logger.recordOutput("Swerve/Drive/ClosedLoopVelocityRadPerSec", velocityRadPerSec); + Logger.recordOutput("Swerve/Drive/ClosedLoopAccelRadPerSec2", accelerationRadPerSec2); + Logger.recordOutput("Swerve/Drive/ClosedLoopFFVolts", scaledFFVolts); + Logger.recordOutput("Robot/BatteryVoltage", busVoltage); } + /** + * Set the turn position of the module + * + * @param rotation Requested module Rotation2d position + */ @Override public void setTurnPosition(Rotation2d rotation) { double setpoint = diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java index 6783a55..a8470d8 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java @@ -15,6 +15,8 @@ import com.ctre.phoenix6.BaseStatusSignal; import com.ctre.phoenix6.StatusSignal; import com.ctre.phoenix6.configs.CANcoderConfiguration; +import com.ctre.phoenix6.configs.ClosedLoopRampsConfigs; +import com.ctre.phoenix6.configs.OpenLoopRampsConfigs; import com.ctre.phoenix6.configs.Slot0Configs; import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.ctre.phoenix6.controls.PositionTorqueCurrentFOC; @@ -40,6 +42,7 @@ import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.units.measure.Current; import edu.wpi.first.units.measure.Voltage; +import edu.wpi.first.wpilibj.RobotController; import frc.robot.Constants; import frc.robot.Constants.DrivebaseConstants; import frc.robot.generated.TunerConstants; @@ -115,6 +118,10 @@ public class ModuleIOTalonFX implements ModuleIO { private final TalonFXConfiguration driveConfig = new TalonFXConfiguration(); private final TalonFXConfiguration turnConfig = new TalonFXConfiguration(); + // Values used for calculating feedforward from kS, kV, and kA + private double lastVelocityRotPerSec = 0.0; + private long lastTimestampNano = System.nanoTime(); + /* * TalonFX I/O */ @@ -140,17 +147,30 @@ public ModuleIOTalonFX(int module) { .withKI(0.0) .withKD(DrivebaseConstants.kDriveD) .withKS(DrivebaseConstants.kDriveS) - .withKV(DrivebaseConstants.kDriveV); + .withKV(DrivebaseConstants.kDriveV) + .withKA(DrivebaseConstants.kDriveA); driveConfig.Feedback.SensorToMechanismRatio = SwerveConstants.kDriveGearRatio; driveConfig.TorqueCurrent.PeakForwardTorqueCurrent = SwerveConstants.kDriveSlipCurrent; driveConfig.TorqueCurrent.PeakReverseTorqueCurrent = -SwerveConstants.kDriveSlipCurrent; driveConfig.CurrentLimits.StatorCurrentLimit = SwerveConstants.kDriveCurrentLimit; driveConfig.CurrentLimits.StatorCurrentLimitEnable = true; - driveConfig.ClosedLoopRamps.TorqueClosedLoopRampPeriod = Constants.loopPeriodSecs; + // Build the OpenLoopRampsConfigs and ClosedLoopRampsConfigs for current smoothing + OpenLoopRampsConfigs openRamps = new OpenLoopRampsConfigs(); + openRamps.DutyCycleOpenLoopRampPeriod = DrivebaseConstants.kDriveOpenLoopRampPeriod; + openRamps.VoltageOpenLoopRampPeriod = DrivebaseConstants.kDriveOpenLoopRampPeriod; + openRamps.TorqueOpenLoopRampPeriod = DrivebaseConstants.kDriveOpenLoopRampPeriod; + ClosedLoopRampsConfigs closedRamps = new ClosedLoopRampsConfigs(); + closedRamps.DutyCycleClosedLoopRampPeriod = DrivebaseConstants.kDriveClosedLoopRampPeriod; + closedRamps.VoltageClosedLoopRampPeriod = DrivebaseConstants.kDriveClosedLoopRampPeriod; + closedRamps.TorqueClosedLoopRampPeriod = DrivebaseConstants.kDriveClosedLoopRampPeriod; + // Apply the open- and closed-loop ramp configuration for current smoothing + driveConfig.withClosedLoopRamps(closedRamps).withOpenLoopRamps(openRamps); + // Set motor inversions driveConfig.MotorOutput.Inverted = constants.DriveMotorInverted ? InvertedValue.Clockwise_Positive : InvertedValue.CounterClockwise_Positive; + // Apply everything to the motor controllers PhoenixUtil.tryUntilOk(5, () -> driveTalon.getConfigurator().apply(driveConfig, 0.25)); PhoenixUtil.tryUntilOk(5, () -> driveTalon.setPosition(0.0, 0.25)); @@ -265,22 +285,47 @@ public void updateInputs(ModuleIOInputs inputs) { turnPositionQueue.clear(); } + /** + * Set the drive motor to an open-loop voltage, scaled to battery voltage + * + * @param output Specified open-loop voltage requested + */ @Override public void setDriveOpenLoop(double output) { + // Scale by actual battery voltage to keep full output consistent + double busVoltage = RobotController.getBatteryVoltage(); + double scaledOutput = output * DrivebaseConstants.kOptimalVoltage / busVoltage; + driveTalon.setControl( switch (m_DriveMotorClosedLoopOutput) { - case Voltage -> voltageRequest.withOutput(output); - case TorqueCurrentFOC -> torqueCurrentRequest.withOutput(output); + case Voltage -> voltageRequest.withOutput(scaledOutput); + case TorqueCurrentFOC -> torqueCurrentRequest.withOutput(scaledOutput); }); + + // Log output and battery + Logger.recordOutput("Swerve/Drive/OpenLoopOutput", scaledOutput); + Logger.recordOutput("Robot/BatteryVoltage", busVoltage); } + /** + * Set the turn motor to an open-loop voltage, scaled to battery voltage + * + * @param output Specified open-loop voltage requested + */ @Override public void setTurnOpenLoop(double output) { + double busVoltage = RobotController.getBatteryVoltage(); + double scaledOutput = output * DrivebaseConstants.kOptimalVoltage / busVoltage; + turnTalon.setControl( switch (m_SteerMotorClosedLoopOutput) { - case Voltage -> voltageRequest.withOutput(output); - case TorqueCurrentFOC -> torqueCurrentRequest.withOutput(output); + case Voltage -> voltageRequest.withOutput(scaledOutput); + case TorqueCurrentFOC -> torqueCurrentRequest.withOutput(scaledOutput); }); + + // Log output and battery + Logger.recordOutput("Swerve/Turn/OpenLoopOutput", scaledOutput); + Logger.recordOutput("Robot/BatteryVoltage", busVoltage); } /** @@ -291,31 +336,67 @@ public void setTurnOpenLoop(double output) { @Override public void setDriveVelocity(double velocityRadPerSec) { double velocityRotPerSec = Units.radiansToRotations(velocityRadPerSec); - Logger.recordOutput("DriveBaseTuning/closedloop", m_DriveMotorClosedLoopOutput); - Logger.recordOutput("DriveBaseTuning/wheelradius_inches", SwerveConstants.kWheelRadiusInches); - Logger.recordOutput("DriveBaseTuning/talon_vradpersec", velocityRadPerSec); - Logger.recordOutput("DriveBaseTuning/talon_vrotpersec", velocityRotPerSec); - Logger.recordOutput("DriveBaseTuning/kDriveP", driveConfig.Slot0.kP); - Logger.recordOutput("DriveBaseTuning/kDriveD", driveConfig.Slot0.kD); - Logger.recordOutput("DriveBaseTuning/kSteerP", turnConfig.Slot0.kP); - Logger.recordOutput("DriveBaseTuning/kSteerD", turnConfig.Slot0.kD); - + double busVoltage = RobotController.getBatteryVoltage(); + + // Compute the Feedforward voltage for CTRE UNLICENSED operation ***** + // Compute acceleration + long currentTimeNano = System.nanoTime(); + double deltaTimeSec = (currentTimeNano - lastTimestampNano) * 1e-9; + double accelerationRotPerSec2 = + deltaTimeSec > 0 ? (velocityRotPerSec - lastVelocityRotPerSec) / deltaTimeSec : 0.0; + // Update last values for next loop + lastVelocityRotPerSec = velocityRotPerSec; + lastTimestampNano = currentTimeNano; + // Compute feedforward voltage: kS + kV*v + kA*a + double nominalFFVolts = + Math.signum(velocityRotPerSec) * DrivebaseConstants.kDriveS + + DrivebaseConstants.kDriveV * velocityRotPerSec + + DrivebaseConstants.kDriveA * accelerationRotPerSec2; + double scaledFFVolts = nominalFFVolts * DrivebaseConstants.kOptimalVoltage / busVoltage; + + // Set the drive motor control based on CTRE LICENSED status driveTalon.setControl( switch (m_DriveMotorClosedLoopOutput) { - case Voltage -> velocityVoltageRequest.withVelocity(velocityRotPerSec); + case Voltage -> + velocityVoltageRequest.withVelocity(velocityRotPerSec).withFeedForward(scaledFFVolts); case TorqueCurrentFOC -> velocityTorqueCurrentRequest.withVelocity(RotationsPerSecond.of(velocityRotPerSec)); }); + + // AdvantageKit logging + Logger.recordOutput("Swerve/Drive/VelocityRadPerSec", velocityRadPerSec); + Logger.recordOutput("Swerve/Drive/VelocityRotPerSec", velocityRotPerSec); + Logger.recordOutput("Swerve/Drive/AccelerationRotPerSec2", accelerationRotPerSec2); + Logger.recordOutput("Swerve/Drive/FeedForwardVolts", scaledFFVolts); + Logger.recordOutput("Robot/BatteryVoltage", busVoltage); + Logger.recordOutput("Swerve/Drive/ClosedLoopMode", m_DriveMotorClosedLoopOutput); } + /** + * Set the turn position of the module + * + * @param rotation Requested module Rotation2d position + */ @Override public void setTurnPosition(Rotation2d rotation) { + double busVoltage = RobotController.getBatteryVoltage(); + + // Scale feedforward voltage by battery voltage + double nominalFFVolts = DrivebaseConstants.kNominalFFVolts; + double scaledFFVolts = nominalFFVolts * DrivebaseConstants.kOptimalVoltage / busVoltage; + turnTalon.setControl( switch (m_SteerMotorClosedLoopOutput) { - case Voltage -> positionVoltageRequest.withPosition(rotation.getRotations()); + case Voltage -> + positionVoltageRequest + .withPosition(rotation.getRotations()) + .withFeedForward(scaledFFVolts); case TorqueCurrentFOC -> positionTorqueCurrentRequest.withPosition(rotation.getRotations()); }); + + Logger.recordOutput("Swerve/Turn/TargetRotations", rotation.getRotations()); + Logger.recordOutput("Robot/BatteryVoltage", busVoltage); } @Override diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFXS.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFXS.java index ab1ce93..9e101cd 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFXS.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFXS.java @@ -15,6 +15,8 @@ import com.ctre.phoenix6.BaseStatusSignal; import com.ctre.phoenix6.StatusSignal; import com.ctre.phoenix6.configs.CANdiConfiguration; +import com.ctre.phoenix6.configs.ClosedLoopRampsConfigs; +import com.ctre.phoenix6.configs.OpenLoopRampsConfigs; import com.ctre.phoenix6.configs.Slot0Configs; import com.ctre.phoenix6.configs.TalonFXSConfiguration; import com.ctre.phoenix6.controls.PositionTorqueCurrentFOC; @@ -41,6 +43,7 @@ import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.units.measure.Current; import edu.wpi.first.units.measure.Voltage; +import edu.wpi.first.wpilibj.RobotController; import frc.robot.Constants; import frc.robot.Constants.DrivebaseConstants; import frc.robot.util.PhoenixUtil; @@ -111,6 +114,10 @@ public class ModuleIOTalonFXS implements ModuleIO { private final TalonFXSConfiguration driveConfig = new TalonFXSConfiguration(); private final TalonFXSConfiguration turnConfig = new TalonFXSConfiguration(); + // Values used for calculating feedforward from kS, kV, and kA + private double lastVelocityRotPerSec = 0.0; + private long lastTimestampNano = System.nanoTime(); + /* * TalonFXS I/O */ @@ -129,7 +136,8 @@ public ModuleIOTalonFXS( .withKI(0.0) .withKD(DrivebaseConstants.kDriveD) .withKS(DrivebaseConstants.kDriveS) - .withKV(DrivebaseConstants.kDriveV); + .withKV(DrivebaseConstants.kDriveV) + .withKA(DrivebaseConstants.kDriveA); driveConfig.Commutation.MotorArrangement = switch (constants.DriveMotorType) { case TalonFXS_NEO_JST -> MotorArrangementValue.NEO_JST; @@ -141,11 +149,23 @@ public ModuleIOTalonFXS( driveConfig.ExternalFeedback.SensorToMechanismRatio = constants.DriveMotorGearRatio; driveConfig.CurrentLimits.StatorCurrentLimit = constants.SlipCurrent; driveConfig.CurrentLimits.StatorCurrentLimitEnable = true; - driveConfig.ClosedLoopRamps.TorqueClosedLoopRampPeriod = Constants.loopPeriodSecs; + // Build the OpenLoopRampsConfigs and ClosedLoopRampsConfigs for current smoothing + OpenLoopRampsConfigs openRamps = new OpenLoopRampsConfigs(); + openRamps.DutyCycleOpenLoopRampPeriod = DrivebaseConstants.kDriveOpenLoopRampPeriod; + openRamps.VoltageOpenLoopRampPeriod = DrivebaseConstants.kDriveOpenLoopRampPeriod; + openRamps.TorqueOpenLoopRampPeriod = DrivebaseConstants.kDriveOpenLoopRampPeriod; + ClosedLoopRampsConfigs closedRamps = new ClosedLoopRampsConfigs(); + closedRamps.DutyCycleClosedLoopRampPeriod = DrivebaseConstants.kDriveClosedLoopRampPeriod; + closedRamps.VoltageClosedLoopRampPeriod = DrivebaseConstants.kDriveClosedLoopRampPeriod; + closedRamps.TorqueClosedLoopRampPeriod = DrivebaseConstants.kDriveClosedLoopRampPeriod; + // Apply the open- and closed-loop ramp configuration for current smoothing + driveConfig.withClosedLoopRamps(closedRamps).withOpenLoopRamps(openRamps); + // Set motor inversions driveConfig.MotorOutput.Inverted = constants.DriveMotorInverted ? InvertedValue.Clockwise_Positive : InvertedValue.CounterClockwise_Positive; + // Apply everything to the motor controllers PhoenixUtil.tryUntilOk(5, () -> driveTalon.getConfigurator().apply(driveConfig, 0.25)); PhoenixUtil.tryUntilOk(5, () -> driveTalon.setPosition(0.0, 0.25)); @@ -281,22 +301,46 @@ public void updateInputs(ModuleIOInputs inputs) { turnPositionQueue.clear(); } + /** + * Set the drive motor to an open-loop voltage, scaled to battery voltage + * + * @param output Specified open-loop voltage requested + */ @Override public void setDriveOpenLoop(double output) { + // Scale by actual battery voltage to keep full output consistent + double busVoltage = RobotController.getBatteryVoltage(); + double scaledOutput = output * DrivebaseConstants.kOptimalVoltage / busVoltage; + driveTalon.setControl( switch (m_DriveMotorClosedLoopOutput) { - case Voltage -> voltageRequest.withOutput(output); - case TorqueCurrentFOC -> torqueCurrentRequest.withOutput(output); + case Voltage -> voltageRequest.withOutput(scaledOutput); + case TorqueCurrentFOC -> torqueCurrentRequest.withOutput(scaledOutput); }); + + // Log output and battery + Logger.recordOutput("Swerve/Drive/OpenLoopOutput", scaledOutput); + Logger.recordOutput("Robot/BatteryVoltage", busVoltage); } + /** + * Set the turn motor to an open-loop voltage, scaled to battery voltage + * + * @param output Specified open-loop voltage requested + */ @Override public void setTurnOpenLoop(double output) { + double busVoltage = RobotController.getBatteryVoltage(); + double scaledOutput = output * DrivebaseConstants.kOptimalVoltage / busVoltage; + turnTalon.setControl( switch (m_SteerMotorClosedLoopOutput) { - case Voltage -> voltageRequest.withOutput(output); - case TorqueCurrentFOC -> torqueCurrentRequest.withOutput(output); + case Voltage -> voltageRequest.withOutput(scaledOutput); + case TorqueCurrentFOC -> torqueCurrentRequest.withOutput(scaledOutput); }); + + Logger.recordOutput("Swerve/Turn/OpenLoopOutput", scaledOutput); + Logger.recordOutput("Robot/BatteryVoltage", busVoltage); } /** @@ -307,31 +351,68 @@ public void setTurnOpenLoop(double output) { @Override public void setDriveVelocity(double velocityRadPerSec) { double velocityRotPerSec = Units.radiansToRotations(velocityRadPerSec); - Logger.recordOutput("DriveBaseTuning/closedloop", m_DriveMotorClosedLoopOutput); - Logger.recordOutput("DriveBaseTuning/wheelradius_inches", SwerveConstants.kWheelRadiusInches); - Logger.recordOutput("DriveBaseTuning/talon_vradpersec", velocityRadPerSec); - Logger.recordOutput("DriveBaseTuning/talon_vrotpersec", velocityRotPerSec); - Logger.recordOutput("DriveBaseTuning/kDriveP", driveConfig.Slot0.kP); - Logger.recordOutput("DriveBaseTuning/kDriveD", driveConfig.Slot0.kD); - Logger.recordOutput("DriveBaseTuning/kSteerP", turnConfig.Slot0.kP); - Logger.recordOutput("DriveBaseTuning/kSteerD", turnConfig.Slot0.kD); + double busVoltage = RobotController.getBatteryVoltage(); + + // Compute the Feedforward voltage for CTRE UNLICENSED operation ***** + // Compute acceleration + long currentTimeNano = System.nanoTime(); + double deltaTimeSec = (currentTimeNano - lastTimestampNano) * 1e-9; + double accelerationRotPerSec2 = + deltaTimeSec > 0 ? (velocityRotPerSec - lastVelocityRotPerSec) / deltaTimeSec : 0.0; + // Update last values for next loop + lastVelocityRotPerSec = velocityRotPerSec; + lastTimestampNano = currentTimeNano; + // Compute feedforward voltage: kS + kV*v + kA*a + double nominalFFVolts = + Math.signum(velocityRotPerSec) * DrivebaseConstants.kDriveS + + DrivebaseConstants.kDriveV * velocityRotPerSec + + DrivebaseConstants.kDriveA * accelerationRotPerSec2; + double scaledFFVolts = nominalFFVolts * DrivebaseConstants.kOptimalVoltage / busVoltage; + // Set the drive motor control based on CTRE LICENSED status driveTalon.setControl( switch (m_DriveMotorClosedLoopOutput) { - case Voltage -> velocityVoltageRequest.withVelocity(velocityRotPerSec); + case Voltage -> + velocityVoltageRequest.withVelocity(velocityRotPerSec).withFeedForward(scaledFFVolts); case TorqueCurrentFOC -> velocityTorqueCurrentRequest.withVelocity(RotationsPerSecond.of(velocityRotPerSec)); }); + + // AdvantageKit logging + Logger.recordOutput("Swerve/Drive/VelocityRadPerSec", velocityRadPerSec); + Logger.recordOutput("Swerve/Drive/VelocityRotPerSec", velocityRotPerSec); + Logger.recordOutput("Swerve/Drive/AccelerationRotPerSec2", accelerationRotPerSec2); + Logger.recordOutput("Swerve/Drive/FeedForwardVolts", scaledFFVolts); + Logger.recordOutput("Robot/BatteryVoltage", busVoltage); + Logger.recordOutput("Swerve/Drive/ClosedLoopMode", m_DriveMotorClosedLoopOutput); } + /** + * Set the turn position of the module + * + * @param rotation Requested module Rotation2d position + */ @Override public void setTurnPosition(Rotation2d rotation) { + double busVoltage = RobotController.getBatteryVoltage(); + + // Scale feedforward voltage by battery voltage + double nominalFFVolts = + DrivebaseConstants.kNominalFFVolts; // replace with your feedforward calculation if needed + double scaledFFVolts = nominalFFVolts * DrivebaseConstants.kOptimalVoltage / busVoltage; + turnTalon.setControl( switch (m_SteerMotorClosedLoopOutput) { - case Voltage -> positionVoltageRequest.withPosition(rotation.getRotations()); + case Voltage -> + positionVoltageRequest + .withPosition(rotation.getRotations()) + .withFeedForward(scaledFFVolts); case TorqueCurrentFOC -> positionTorqueCurrentRequest.withPosition(rotation.getRotations()); }); + + Logger.recordOutput("Swerve/Turn/TargetRotations", rotation.getRotations()); + Logger.recordOutput("Robot/BatteryVoltage", busVoltage); } @Override diff --git a/src/main/java/frc/robot/subsystems/drive/SwerveConstants.java b/src/main/java/frc/robot/subsystems/drive/SwerveConstants.java index 6616e81..61201dd 100644 --- a/src/main/java/frc/robot/subsystems/drive/SwerveConstants.java +++ b/src/main/java/frc/robot/subsystems/drive/SwerveConstants.java @@ -44,7 +44,6 @@ public class SwerveConstants { public static final double kSteerCurrentLimit; public static final double kDriveCurrentLimit; public static final double kDriveSlipCurrent; - public static final double kOptimalVoltage; public static final int kFLDriveMotorId; public static final int kFLSteerMotorId; public static final int kFLEncoderId; @@ -126,7 +125,6 @@ public class SwerveConstants { kSteerCurrentLimit = 40.0; // Example from CTRE documentation kDriveCurrentLimit = 120.0; // Example from CTRE documentation kDriveSlipCurrent = TunerConstants.FrontLeft.SlipCurrent; - kOptimalVoltage = 12.0; // Assumed Ideal // Front Left kFLDriveMotorId = TunerConstants.FrontLeft.DriveMotorId; kFLSteerMotorId = TunerConstants.FrontLeft.SteerMotorId; @@ -212,7 +210,6 @@ public class SwerveConstants { kSteerCurrentLimit = YagslConstants.kSteerCurrentLimit; kDriveCurrentLimit = YagslConstants.kDriveCurrentLimit; kDriveSlipCurrent = 120.0; - kOptimalVoltage = YagslConstants.kOptimalVoltage; // Front Left kFLDriveMotorId = YagslConstants.kFrontLeftDriveMotorId; kFLSteerMotorId = YagslConstants.kFrontLeftSteerMotorId; diff --git a/src/main/java/frc/robot/subsystems/flywheel_example/Flywheel.java b/src/main/java/frc/robot/subsystems/flywheel_example/Flywheel.java index 8061ef4..be7ab97 100644 --- a/src/main/java/frc/robot/subsystems/flywheel_example/Flywheel.java +++ b/src/main/java/frc/robot/subsystems/flywheel_example/Flywheel.java @@ -38,10 +38,12 @@ public Flywheel(FlywheelIO io) { case REPLAY: ffModel = new SimpleMotorFeedforward(kStaticGainReal, kVelocityGainReal); io.configurePID(pidReal.kP, pidReal.kI, pidReal.kD); + io.configureFF(kStaticGainReal, kVelocityGainReal); break; case SIM: ffModel = new SimpleMotorFeedforward(kStaticGainSim, kVelocityGainSim); io.configurePID(pidSim.kP, pidSim.kI, pidSim.kD); + io.configureFF(kStaticGainSim, kVelocityGainSim); break; default: ffModel = new SimpleMotorFeedforward(0.0, 0.0); diff --git a/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIO.java b/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIO.java index 5dc4953..c1b6901 100644 --- a/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIO.java +++ b/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIO.java @@ -30,4 +30,10 @@ public default void setVelocity(double velocityRadPerSec, double ffVolts) {} /** Set velocity PID constants. */ public default void configurePID(double kP, double kI, double kD) {} + + /** Set velocity FeedForward constants. */ + public default void configureFF(double kS, double kV) {} + + /** Set velocity FeedForward constants. */ + public default void configureFF(double kS, double kV, double kA) {} } diff --git a/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIOSpark.java b/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIOSpark.java index 14437d7..be66917 100644 --- a/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIOSpark.java +++ b/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIOSpark.java @@ -26,6 +26,8 @@ import com.revrobotics.spark.config.SparkBaseConfig.IdleMode; import com.revrobotics.spark.config.SparkFlexConfig; import edu.wpi.first.math.util.Units; +import frc.robot.Constants; +import frc.robot.Constants.DrivebaseConstants; import frc.robot.subsystems.drive.SwerveConstants; import frc.robot.util.SparkUtil; @@ -58,23 +60,27 @@ public FlywheelIOSpark() { case BRAKE -> IdleMode.kBrake; }) .smartCurrentLimit((int) SwerveConstants.kDriveCurrentLimit) - .voltageCompensation(12.0); + .voltageCompensation(DrivebaseConstants.kOptimalVoltage); leaderConfig.encoder.uvwMeasurementPeriod(10).uvwAverageDepth(2); leaderConfig .closedLoop .feedbackSensor(FeedbackSensor.kPrimaryEncoder) - .pid(0.0, 0.0, 0.0) + .pid(pidReal.kP, pidReal.kI, pidReal.kD) .feedForward - .kV(0.0); + .kS(kStaticGainReal) + .kV(kVelocityGainReal); leaderConfig .signals .primaryEncoderPositionAlwaysOn(true) .primaryEncoderPositionPeriodMs((int) (1000.0 / SwerveConstants.kOdometryFrequency)) .primaryEncoderVelocityAlwaysOn(true) - .primaryEncoderVelocityPeriodMs(20) - .appliedOutputPeriodMs(20) - .busVoltagePeriodMs(20) - .outputCurrentPeriodMs(20); + .primaryEncoderVelocityPeriodMs((int) (Constants.loopPeriodSecs * 1000.)) + .appliedOutputPeriodMs((int) (Constants.loopPeriodSecs * 1000.)) + .busVoltagePeriodMs((int) (Constants.loopPeriodSecs * 1000.)) + .outputCurrentPeriodMs((int) (Constants.loopPeriodSecs * 1000.)); + leaderConfig + .openLoopRampRate(DrivebaseConstants.kDriveOpenLoopRampPeriod) + .closedLoopRampRate(DrivebaseConstants.kDriveClosedLoopRampPeriod); SparkUtil.tryUntilOk( leader, 5, @@ -127,4 +133,10 @@ public void configurePID(double kP, double kI, double kD) { // pid.setD(kD, 0); // pid.setFF(0, 0); } + + @Override + public void configureFF(double kS, double kV) {} + + @Override + public void configureFF(double kS, double kV, double kA) {} } diff --git a/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIOTalonFX.java b/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIOTalonFX.java index 161b456..04391d6 100644 --- a/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIOTalonFX.java @@ -14,7 +14,8 @@ import com.ctre.phoenix6.BaseStatusSignal; import com.ctre.phoenix6.StatusSignal; -import com.ctre.phoenix6.configs.Slot0Configs; +import com.ctre.phoenix6.configs.ClosedLoopRampsConfigs; +import com.ctre.phoenix6.configs.OpenLoopRampsConfigs; import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.ctre.phoenix6.controls.Follower; import com.ctre.phoenix6.controls.VelocityVoltage; @@ -27,6 +28,7 @@ import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.units.measure.Current; import edu.wpi.first.units.measure.Voltage; +import frc.robot.util.PhoenixUtil; public class FlywheelIOTalonFX implements FlywheelIO { @@ -46,8 +48,9 @@ public class FlywheelIOTalonFX implements FlywheelIO { private final StatusSignal leaderCurrent = leader.getSupplyCurrent(); private final StatusSignal followerCurrent = follower.getSupplyCurrent(); + private final TalonFXConfiguration config = new TalonFXConfiguration(); + public FlywheelIOTalonFX() { - var config = new TalonFXConfiguration(); config.CurrentLimits.SupplyCurrentLimit = 30.0; config.CurrentLimits.SupplyCurrentLimitEnable = true; config.MotorOutput.NeutralMode = @@ -55,6 +58,19 @@ public FlywheelIOTalonFX() { case COAST -> NeutralModeValue.Coast; case BRAKE -> NeutralModeValue.Brake; }; + // Build the OpenLoopRampsConfigs and ClosedLoopRampsConfigs for current smoothing + OpenLoopRampsConfigs openRamps = new OpenLoopRampsConfigs(); + openRamps.DutyCycleOpenLoopRampPeriod = kFlywheelOpenLoopRampPeriod; + openRamps.VoltageOpenLoopRampPeriod = kFlywheelOpenLoopRampPeriod; + openRamps.TorqueOpenLoopRampPeriod = kFlywheelOpenLoopRampPeriod; + ClosedLoopRampsConfigs closedRamps = new ClosedLoopRampsConfigs(); + closedRamps.DutyCycleClosedLoopRampPeriod = kFlywheelClosedLoopRampPeriod; + closedRamps.VoltageClosedLoopRampPeriod = kFlywheelClosedLoopRampPeriod; + closedRamps.TorqueClosedLoopRampPeriod = kFlywheelClosedLoopRampPeriod; + // Apply the open- and closed-loop ramp configuration for current smoothing + config.withClosedLoopRamps(closedRamps).withOpenLoopRamps(openRamps); + + // Apply the configurations to the flywheel motors leader.getConfigurator().apply(config); follower.getConfigurator().apply(config); // If follower rotates in the opposite direction, set "MotorAlignmentValue" to Opposed @@ -94,12 +110,45 @@ public void stop() { leader.stopMotor(); } + /** + * Set the PID portion of the Slot0 closed-loop configuration + * + * @param kP Proportional gain + * @param kI Integral gain + * @param kD Differential gain + */ @Override public void configurePID(double kP, double kI, double kD) { - var config = new Slot0Configs(); - config.kP = kP; - config.kI = kI; - config.kD = kD; - leader.getConfigurator().apply(config); + config.Slot0.kP = kP; + config.Slot0.kI = kI; + config.Slot0.kD = kD; + PhoenixUtil.tryUntilOk(5, () -> leader.getConfigurator().apply(config, 0.25)); + } + + /** + * Set the FeedForward portion of the Slot0 closed-loop configuration + * + * @param kS Static gain + * @param kV Velocity gain + */ + @Override + public void configureFF(double kS, double kV) { + config.Slot0.kS = kS; + config.Slot0.kV = kV; + PhoenixUtil.tryUntilOk(5, () -> leader.getConfigurator().apply(config, 0.25)); + } + + /** + * Set the FeedForward portion of the Slot0 closed-loop configuration + * + * @param kS Static gain + * @param kV Velocity gain + * @param kA Acceleration gain + */ + public void configureFF(double kS, double kV, double kA) { + config.Slot0.kS = kS; + config.Slot0.kV = kV; + config.Slot0.kA = kA; + PhoenixUtil.tryUntilOk(5, () -> leader.getConfigurator().apply(config, 0.25)); } } From 571e45553a2d0595b38dfd0d1beabc8cde9f1d18 Mon Sep 17 00:00:00 2001 From: Timothy Ellsworth Bowers Date: Tue, 13 Jan 2026 15:49:07 -0700 Subject: [PATCH 4/4] Update Libraries & Documentation for Kickoff 2026 Release (#103) * Update WPILib & Vendordeps to 2026 kickoff * Rename AprilTagLayout -> FieldConstants * Update FieldConstants to match 2026 / FRC-6328 * Fix deprecation warnings from REVLib 2026 * PhotonLib updated to 26-rc1 * Update the README's in ``src/main/java/frc/robot`` -- Including subsystem README files * PhotonLib updated to 26-rc2 * Fix power logging instantiator * Update REVLib --- .wpilib/wpilib_preferences.json | 2 +- build.gradle | 2 +- src/main/java/frc/robot/Constants.java | 4 +- ...prilTagLayout.java => FieldConstants.java} | 55 ++++++++-------- src/main/java/frc/robot/README | 24 ++++--- src/main/java/frc/robot/Robot.java | 2 - src/main/java/frc/robot/RobotContainer.java | 2 +- .../subsystems/drive/ModuleIOBlended.java | 4 +- .../robot/subsystems/drive/ModuleIOSpark.java | 4 +- .../drive/ModuleIOSparkCANcoder.java | 4 +- .../java/frc/robot/subsystems/drive/README | 16 ++--- .../flywheel_example/FlywheelIOSpark.java | 33 +++++++--- src/main/java/frc/robot/subsystems/imu/README | 14 ++++ .../frc/robot/subsystems/vision/Vision.java | 8 +-- .../vision/VisionIOPhotonVision.java | 2 +- .../vision/VisionIOPhotonVisionSim.java | 4 +- vendordeps/AdvantageKit.json | 8 +-- vendordeps/Autopilot.json | 6 +- ...{ChoreoLib2025.json => ChoreoLib2026.json} | 14 ++-- ...rLib.json => PathplannerLib-2026.1.2.json} | 10 +-- ....36.0-beta-1.json => Phoenix5-5.36.0.json} | 36 +++++------ ...6.0.0-beta-1.json => Phoenix6-26.1.0.json} | 64 +++++++++---------- vendordeps/REVLib.json | 20 +++--- ...b-2025.0.1.json => ReduxLib-2026.1.1.json} | 25 ++++---- ...tudica-2026.0.0-beta.json => Studica.json} | 16 ++--- ...riftyLib.json => ThriftyLib-2026.0.0.json} | 10 +-- vendordeps/URCL.json | 2 +- vendordeps/WPILibNewCommands.json | 2 +- vendordeps/maple-sim.json | 2 +- vendordeps/photonlib.json | 14 ++-- vendordeps/yagsl-2025.8.0.json | 2 +- 31 files changed, 221 insertions(+), 190 deletions(-) rename src/main/java/frc/robot/{AprilTagLayout.java => FieldConstants.java} (58%) create mode 100644 src/main/java/frc/robot/subsystems/imu/README rename vendordeps/{ChoreoLib2025.json => ChoreoLib2026.json} (74%) rename vendordeps/{PathplannerLib.json => PathplannerLib-2026.1.2.json} (84%) rename vendordeps/{Phoenix5-5.36.0-beta-1.json => Phoenix5-5.36.0.json} (84%) rename vendordeps/{Phoenix6-26.0.0-beta-1.json => Phoenix6-26.1.0.json} (90%) rename vendordeps/{ReduxLib-2025.0.1.json => ReduxLib-2026.1.1.json} (74%) rename vendordeps/{Studica-2026.0.0-beta.json => Studica.json} (85%) rename vendordeps/{ThriftyLib.json => ThriftyLib-2026.0.0.json} (72%) diff --git a/.wpilib/wpilib_preferences.json b/.wpilib/wpilib_preferences.json index acbd59a..ae81d97 100644 --- a/.wpilib/wpilib_preferences.json +++ b/.wpilib/wpilib_preferences.json @@ -1,6 +1,6 @@ { "enableCppIntellisense": false, "currentLanguage": "java", - "projectYear": "2026beta", + "projectYear": "2026", "teamNumber": 0 } diff --git a/build.gradle b/build.gradle index 05d5b58..731859d 100644 --- a/build.gradle +++ b/build.gradle @@ -1,6 +1,6 @@ plugins { id "java" - id "edu.wpi.first.GradleRIO" version "2026.1.1-beta-1" + id "edu.wpi.first.GradleRIO" version "2026.1.1" id "com.peterabeles.gversion" version "1.10.3" id "com.diffplug.spotless" version "8.0.+" id "io.freefair.lombok" version "9.1.+" diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 797d8bd..9b81736 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -34,7 +34,7 @@ import edu.wpi.first.units.measure.Mass; import edu.wpi.first.wpilibj.PowerDistribution; import edu.wpi.first.wpilibj.RobotBase; -import frc.robot.AprilTagLayout.AprilTagLayoutType; +import frc.robot.FieldConstants.AprilTagLayoutType; import frc.robot.subsystems.drive.Drive; import frc.robot.subsystems.drive.SwerveConstants; import frc.robot.util.Alert; @@ -487,6 +487,6 @@ public static CTREPro getPhoenixPro() { /** Get the current AprilTag layout type. */ public static AprilTagLayoutType getAprilTagLayoutType() { - return AprilTagLayout.defaultAprilTagType; + return FieldConstants.defaultAprilTagType; } } diff --git a/src/main/java/frc/robot/AprilTagLayout.java b/src/main/java/frc/robot/FieldConstants.java similarity index 58% rename from src/main/java/frc/robot/AprilTagLayout.java rename to src/main/java/frc/robot/FieldConstants.java index e8ae31c..729b45f 100644 --- a/src/main/java/frc/robot/AprilTagLayout.java +++ b/src/main/java/frc/robot/FieldConstants.java @@ -1,5 +1,7 @@ // Copyright (c) 2024-2026 Az-FIRST // http://github.com/AZ-First +// Copyright (c) 2025-2026 Littleton Robotics +// http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or // modify it under the terms of the GNU General Public License @@ -28,12 +30,21 @@ import java.nio.file.Path; import lombok.Getter; -public class AprilTagLayout { +/** + * Contains various field dimensions and useful reference points. All units are in meters and poses + * have a blue alliance origin. + */ +public class FieldConstants { /** AprilTag Field Layout ************************************************ */ public static final double aprilTagWidth = Inches.of(6.50).in(Meters); public static final String aprilTagFamily = "36h11"; + + public static final double fieldLength = AprilTagLayoutType.OFFICIAL.getLayout().getFieldLength(); + public static final double fieldWidth = AprilTagLayoutType.OFFICIAL.getLayout().getFieldWidth(); + + public static final int aprilTagCount = AprilTagLayoutType.OFFICIAL.getLayout().getTags().size(); public static final AprilTagLayoutType defaultAprilTagType = AprilTagLayoutType.OFFICIAL; public static final AprilTagFieldLayout aprilTagLayout = @@ -42,34 +53,26 @@ public class AprilTagLayout { @Getter public enum AprilTagLayoutType { OFFICIAL("2026-official"), - + NONE("2026-none"), REEFSCAPE("2025-official"); - // SPEAKERS_ONLY("2024-speakers"), - // AMPS_ONLY("2024-amps"), - // WPI("2024-wpi"); - - private AprilTagLayoutType(String name) { - if (Constants.disableHAL) { - layout = null; - } else { - try { - layout = - new AprilTagFieldLayout( - Path.of(Filesystem.getDeployDirectory().getPath(), "apriltags", name + ".json")); - } catch (IOException e) { - throw new RuntimeException(e); - } + AprilTagLayoutType(String name) { + try { + layout = + new AprilTagFieldLayout( + Constants.disableHAL + ? Path.of("src", "main", "deploy", "apriltags", name + ".json") + : Path.of( + Filesystem.getDeployDirectory().getPath(), "apriltags", name + ".json")); + } catch (IOException e) { + throw new RuntimeException(e); } - if (layout == null) { - layoutString = ""; - } else { - try { - layoutString = new ObjectMapper().writeValueAsString(layout); - } catch (JsonProcessingException e) { - throw new RuntimeException( - "Failed to serialize AprilTag layout JSON " + toString() + "for PhotonVision"); - } + + try { + layoutString = new ObjectMapper().writeValueAsString(layout); + } catch (JsonProcessingException e) { + throw new RuntimeException( + "Failed to serialize AprilTag layout JSON " + toString() + "for PhotonVision"); } } diff --git a/src/main/java/frc/robot/README b/src/main/java/frc/robot/README index b559e04..0d5dc59 100644 --- a/src/main/java/frc/robot/README +++ b/src/main/java/frc/robot/README @@ -6,10 +6,6 @@ robot. The files that should exist in this directory are listed below, along with a brief description of their contents and which files MUST be edited to include information about the specific robot being controlled. -AprilTagLayout.java - The year-specific AprilTag and field layout file. Teams may modify this - file to include additional information specific for their needs. - BuildConstants.java Not tracked by git, used by the build system to record information about the latest build of the code. This file should NOT be altered, and will be @@ -22,12 +18,24 @@ Constants.java importing only the constants needed for a particular software module. This file MUST be modified to include the proper robot constants in the code. +FieldConstants.java + The year-specific AprilTag and field layout file. Teams may modify the + file to include additional information specific for their needs. + +FieldState.java + For 2026 - REBUILT, the field produces information that affects gameplay, + namely which HUB is active at different times during the match. The file + converts data from the FMS into data that can be used by teams for scoring + control. + Main.java - This is the file run by the RoboRIO virtual machine. Do NOT alter this - file. + The file run by the RoboRIO virtual machine. Do NOT alter this file. + +README + This file. Robot.java - This file is called by ``Main.java`` and directs the operation of the robot + The file called by ``Main.java`` and which directs the operation of the robot according to the currently commanded mode (disabled, autonomous, teleop, test, and simulation). Care must be taken when modifying this module to ensure proper operation of the robot. One section that would be useful to @@ -76,4 +84,4 @@ util/ -------------------- -Last Modified: 06 Jan 2026, TPEB +Last Modified: 12 Jan 2026, TPEB diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index 54dfc56..ccfc193 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -90,8 +90,6 @@ public Robot() { // Initialize URCL Logger.registerURCL(URCL.startExternal()); StatusLogger.disableAutoLogging(); // Disable REVLib's built-in logging - - // TODO: Uncomment this upon next release of AKit // LoggedPowerDistribution.getInstance(PowerConstants.kPDMCANid, PowerConstants.kPDMType); // Start AdvantageKit logger diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 7e92296..faf29dd 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -33,8 +33,8 @@ import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import edu.wpi.first.wpilibj2.command.button.RobotModeTriggers; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; -import frc.robot.AprilTagLayout.AprilTagLayoutType; import frc.robot.Constants.OperatorConstants; +import frc.robot.FieldConstants.AprilTagLayoutType; import frc.robot.commands.AutopilotCommands; import frc.robot.commands.DriveCommands; import frc.robot.subsystems.accelerometer.Accelerometer; diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOBlended.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOBlended.java index 614b9f3..10ff019 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOBlended.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOBlended.java @@ -32,11 +32,11 @@ import com.ctre.phoenix6.swerve.SwerveModuleConstants; import com.ctre.phoenix6.swerve.SwerveModuleConstants.ClosedLoopOutputType; import com.ctre.phoenix6.swerve.SwerveModuleConstantsFactory; +import com.revrobotics.PersistMode; +import com.revrobotics.ResetMode; import com.revrobotics.spark.FeedbackSensor; import com.revrobotics.spark.SparkBase; import com.revrobotics.spark.SparkBase.ControlType; -import com.revrobotics.spark.SparkBase.PersistMode; -import com.revrobotics.spark.SparkBase.ResetMode; import com.revrobotics.spark.SparkClosedLoopController; import com.revrobotics.spark.SparkLowLevel.MotorType; import com.revrobotics.spark.SparkMax; diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java index 996194c..c2fdc35 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java @@ -12,13 +12,13 @@ import static frc.robot.subsystems.drive.SwerveConstants.*; import com.revrobotics.AbsoluteEncoder; +import com.revrobotics.PersistMode; import com.revrobotics.RelativeEncoder; +import com.revrobotics.ResetMode; import com.revrobotics.spark.ClosedLoopSlot; import com.revrobotics.spark.FeedbackSensor; import com.revrobotics.spark.SparkBase; import com.revrobotics.spark.SparkBase.ControlType; -import com.revrobotics.spark.SparkBase.PersistMode; -import com.revrobotics.spark.SparkBase.ResetMode; import com.revrobotics.spark.SparkClosedLoopController; import com.revrobotics.spark.SparkClosedLoopController.ArbFFUnits; import com.revrobotics.spark.SparkFlex; diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkCANcoder.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkCANcoder.java index a79837e..8f47a65 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkCANcoder.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkCANcoder.java @@ -14,13 +14,13 @@ import com.ctre.phoenix6.BaseStatusSignal; import com.ctre.phoenix6.StatusSignal; import com.ctre.phoenix6.hardware.CANcoder; +import com.revrobotics.PersistMode; import com.revrobotics.RelativeEncoder; +import com.revrobotics.ResetMode; import com.revrobotics.spark.ClosedLoopSlot; import com.revrobotics.spark.FeedbackSensor; import com.revrobotics.spark.SparkBase; import com.revrobotics.spark.SparkBase.ControlType; -import com.revrobotics.spark.SparkBase.PersistMode; -import com.revrobotics.spark.SparkBase.ResetMode; import com.revrobotics.spark.SparkClosedLoopController; import com.revrobotics.spark.SparkClosedLoopController.ArbFFUnits; import com.revrobotics.spark.SparkFlex; diff --git a/src/main/java/frc/robot/subsystems/drive/README b/src/main/java/frc/robot/subsystems/drive/README index 2b45714..fb25df4 100644 --- a/src/main/java/frc/robot/subsystems/drive/README +++ b/src/main/java/frc/robot/subsystems/drive/README @@ -1,21 +1,19 @@ The hardware-specific IO files included here are a baseline for what we expect teams to use. If, however, you are using a different combination of hardware, -you will need to create a new ``ModuleIO*.java`` or ``GyroIO*.java`` file. We -encourage you to submit a PR to the Az-RBSI repositiory with your new hardware -file if you feel other teams may benefit from its inclusion. Additionally, the -instantiation logic in ``Drive.java`` will need to be extended to include the -new module type. +you will need to create a new ``ModuleIO*.java`` file. We encourage you to +submit a PR to the Az-RBSI repositiory with your new hardware file if you feel +other teams may benefit from its inclusion. Additionally, the instantiation +logic in ``Drive.java`` will need to be extended to include the new module +type. Existing IO files: - - ``GyroIOPigeon2.java``: CTRE Pigeon2 as the swerve IMU - - ``GyroIONavX.java``: NavX as the swerve IMU, connected via SPI - - ``ModuleIOTalonFX.java``: 2x TalonFX motors + CANcoder + - ``ModuleIOTalonFXS.java``: 2x TalonFXS motors + CANcoder - ``ModuleIOSpark.java``: 2x Rev NEO motors + analog absolute encoder connected to the RIO - ``ModuleIOSparkCANcoder.java``: 2x Rv NEO motors + CANcoder - ``ModuleIOBlended.java``: TalonFX drive, Rev NEO steer motors + CANcoder -------------------- -Last Modified: 2 Jan 2025, TPEB +Last Modified: 12 Jan 2026, TPEB diff --git a/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIOSpark.java b/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIOSpark.java index be66917..cef38ce 100644 --- a/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIOSpark.java +++ b/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIOSpark.java @@ -3,22 +3,27 @@ // Copyright (c) 2021-2026 Littleton Robotics // http://github.com/Mechanical-Advantage // -// Use of this source code is governed by a BSD -// license that can be found in the AdvantageKit-License.md file -// at the root directory of this project. +// This program is free software; you can redistribute it and/or +// modify it under the terms of the GNU General Public License +// version 3 as published by the Free Software Foundation or +// available in the root directory of this project. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. package frc.robot.subsystems.flywheel_example; import static frc.robot.Constants.FlywheelConstants.*; import static frc.robot.Constants.RobotDevices.*; +import com.revrobotics.PersistMode; import com.revrobotics.RelativeEncoder; +import com.revrobotics.ResetMode; import com.revrobotics.spark.ClosedLoopSlot; import com.revrobotics.spark.FeedbackSensor; -import com.revrobotics.spark.SparkBase; import com.revrobotics.spark.SparkBase.ControlType; -import com.revrobotics.spark.SparkBase.PersistMode; -import com.revrobotics.spark.SparkBase.ResetMode; import com.revrobotics.spark.SparkClosedLoopController; import com.revrobotics.spark.SparkClosedLoopController.ArbFFUnits; import com.revrobotics.spark.SparkLowLevel.MotorType; @@ -30,6 +35,7 @@ import frc.robot.Constants.DrivebaseConstants; import frc.robot.subsystems.drive.SwerveConstants; import frc.robot.util.SparkUtil; +import org.littletonrobotics.junction.Logger; /** * NOTE: To use the Spark Flex / NEO Vortex, replace all instances of "CANSparkMax" with @@ -37,11 +43,11 @@ */ public class FlywheelIOSpark implements FlywheelIO { - // Define the leader / follower motors from the Ports section of RobotContainer - private final SparkBase leader = - new SparkMax(FLYWHEEL_LEADER.getDeviceNumber(), MotorType.kBrushless); - private final SparkBase follower = + // Define the leader / follower motors from the RobotDevices section of RobotContainer + private final SparkMax leader = new SparkMax(FLYWHEEL_LEADER.getDeviceNumber(), MotorType.kBrushless); + private final SparkMax follower = + new SparkMax(FLYWHEEL_FOLLOWER.getDeviceNumber(), MotorType.kBrushless); private final RelativeEncoder encoder = leader.getEncoder(); private final SparkClosedLoopController pid = leader.getClosedLoopController(); // IMPORTANT: Include here all devices listed above that are part of this mechanism! @@ -97,6 +103,13 @@ public void updateInputs(FlywheelIOInputs inputs) { Units.rotationsPerMinuteToRadiansPerSecond(encoder.getVelocity() / kFlywheelGearRatio); inputs.appliedVolts = leader.getAppliedOutput() * leader.getBusVoltage(); inputs.currentAmps = new double[] {leader.getOutputCurrent(), follower.getOutputCurrent()}; + + // AdvantageKit logging + Logger.recordOutput("Flywheel/PositionRad", inputs.positionRad); + Logger.recordOutput("Flywheel/VelocityRadPerSec", inputs.velocityRadPerSec); + Logger.recordOutput("Flywheel/AppliedVolts", inputs.appliedVolts); + Logger.recordOutput("Flywheel/LeaderCurrent", inputs.currentAmps[0]); + Logger.recordOutput("Flywheel/FollowerCurrent", inputs.currentAmps[1]); } @Override diff --git a/src/main/java/frc/robot/subsystems/imu/README b/src/main/java/frc/robot/subsystems/imu/README new file mode 100644 index 0000000..95d0465 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/imu/README @@ -0,0 +1,14 @@ +The hardware-specific IO files included here are a baseline for what we expect +teams to use. If, however, you are using a different combination of hardware, +you will need to create a new ``GyroIO*.java`` file. We encourage you to +submit a PR to the Az-RBSI repositiory with your new hardware file if you feel +other teams may benefit from its inclusion. + +Existing IO files: + + - ``GyroIOPigeon2.java``: CTRE Pigeon2 as the swerve IMU + - ``GyroIONavX.java``: NavX as the swerve IMU, connected via SPI + + +-------------------- +Last Modified: 12 Jan 2026, TPEB diff --git a/src/main/java/frc/robot/subsystems/vision/Vision.java b/src/main/java/frc/robot/subsystems/vision/Vision.java index c7e172e..cb55b42 100644 --- a/src/main/java/frc/robot/subsystems/vision/Vision.java +++ b/src/main/java/frc/robot/subsystems/vision/Vision.java @@ -24,7 +24,7 @@ import edu.wpi.first.wpilibj.Alert; import edu.wpi.first.wpilibj.Alert.AlertType; import edu.wpi.first.wpilibj2.command.SubsystemBase; -import frc.robot.AprilTagLayout; +import frc.robot.FieldConstants; import frc.robot.subsystems.vision.VisionIO.PoseObservationType; import java.util.LinkedList; import java.util.List; @@ -90,7 +90,7 @@ public void periodic() { // Add tag poses for (int tagId : inputs[cameraIndex].tagIds) { - var tagPose = AprilTagLayout.aprilTagLayout.getTagPose(tagId); + var tagPose = FieldConstants.aprilTagLayout.getTagPose(tagId); if (tagPose.isPresent()) { tagPoses.add(tagPose.get()); } @@ -108,9 +108,9 @@ public void periodic() { // Must be within the field boundaries || observation.pose().getX() < 0.0 - || observation.pose().getX() > AprilTagLayout.aprilTagLayout.getFieldLength() + || observation.pose().getX() > FieldConstants.aprilTagLayout.getFieldLength() || observation.pose().getY() < 0.0 - || observation.pose().getY() > AprilTagLayout.aprilTagLayout.getFieldWidth(); + || observation.pose().getY() > FieldConstants.aprilTagLayout.getFieldWidth(); // Add pose to log robotPoses.add(observation.pose()); diff --git a/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVision.java b/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVision.java index 13ab7aa..13f93b3 100644 --- a/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVision.java +++ b/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVision.java @@ -9,7 +9,7 @@ package frc.robot.subsystems.vision; -import static frc.robot.AprilTagLayout.*; +import static frc.robot.FieldConstants.*; import edu.wpi.first.math.geometry.Pose3d; import edu.wpi.first.math.geometry.Rotation2d; diff --git a/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVisionSim.java b/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVisionSim.java index ce5302b..fd4525b 100644 --- a/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVisionSim.java +++ b/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVisionSim.java @@ -11,7 +11,7 @@ import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Transform3d; -import frc.robot.AprilTagLayout; +import frc.robot.FieldConstants; import java.util.function.Supplier; import org.photonvision.simulation.PhotonCameraSim; import org.photonvision.simulation.SimCameraProperties; @@ -38,7 +38,7 @@ public VisionIOPhotonVisionSim( // Initialize vision sim if (visionSim == null) { visionSim = new VisionSystemSim("main"); - visionSim.addAprilTags(AprilTagLayout.aprilTagLayout); + visionSim.addAprilTags(FieldConstants.aprilTagLayout); } // Add sim camera diff --git a/vendordeps/AdvantageKit.json b/vendordeps/AdvantageKit.json index 849af71..2faa4db 100644 --- a/vendordeps/AdvantageKit.json +++ b/vendordeps/AdvantageKit.json @@ -1,9 +1,9 @@ { "fileName": "AdvantageKit.json", "name": "AdvantageKit", - "version": "26.0.0-beta-1", + "version": "26.0.0", "uuid": "d820cc26-74e3-11ec-90d6-0242ac120003", - "frcYear": "2026beta", + "frcYear": "2026", "mavenUrls": [ "https://frcmaven.wpi.edu/artifactory/littletonrobotics-mvn-release/" ], @@ -12,14 +12,14 @@ { "groupId": "org.littletonrobotics.akit", "artifactId": "akit-java", - "version": "26.0.0-beta-1" + "version": "26.0.0" } ], "jniDependencies": [ { "groupId": "org.littletonrobotics.akit", "artifactId": "akit-wpilibio", - "version": "26.0.0-beta-1", + "version": "26.0.0", "skipInvalidPlatforms": false, "isJar": false, "validPlatforms": [ diff --git a/vendordeps/Autopilot.json b/vendordeps/Autopilot.json index 7e33127..3575aeb 100644 --- a/vendordeps/Autopilot.json +++ b/vendordeps/Autopilot.json @@ -2,8 +2,8 @@ "name": "Autopilot", "uuid": "4e922d47-9954-4db5-929f-c708cc62e152", "fileName": "Autopilot.json", - "version": "1.4.0", - "frcYear": "2026beta", + "version": "1.5.0", + "frcYear": "2026", "jsonUrl": "https://therekrab.github.io/autopilot/vendordep.json", "mavenUrls": [ "https://jitpack.io" @@ -12,7 +12,7 @@ { "groupId": "com.github.therekrab", "artifactId": "autopilot", - "version": "1.4.0" + "version": "1.5.0" } ], "cppDependencies": [], diff --git a/vendordeps/ChoreoLib2025.json b/vendordeps/ChoreoLib2026.json similarity index 74% rename from vendordeps/ChoreoLib2025.json rename to vendordeps/ChoreoLib2026.json index 5259ca8..cf7e7cf 100644 --- a/vendordeps/ChoreoLib2025.json +++ b/vendordeps/ChoreoLib2026.json @@ -1,19 +1,19 @@ { - "fileName": "ChoreoLib2025.json", + "fileName": "ChoreoLib2026.json", "name": "ChoreoLib", - "version": "2025.0.3", + "version": "2026.0.1", "uuid": "b5e23f0a-dac9-4ad2-8dd6-02767c520aca", - "frcYear": "2026beta", + "frcYear": "2026", "mavenUrls": [ - "https://lib.choreo.autos/dep", + "https://frcmaven.wpi.edu/artifactory/sleipnirgroup-mvn-release/", "https://repo1.maven.org/maven2" ], - "jsonUrl": "https://lib.choreo.autos/dep/ChoreoLib2025.json", + "jsonUrl": "https://choreo.autos/lib/ChoreoLib2026.json", "javaDependencies": [ { "groupId": "choreo", "artifactId": "ChoreoLib-java", - "version": "2025.0.3" + "version": "2026.0.1" }, { "groupId": "com.google.code.gson", @@ -26,7 +26,7 @@ { "groupId": "choreo", "artifactId": "ChoreoLib-cpp", - "version": "2025.0.3", + "version": "2026.0.1", "libName": "ChoreoLib", "headerClassifier": "headers", "sharedLibrary": false, diff --git a/vendordeps/PathplannerLib.json b/vendordeps/PathplannerLib-2026.1.2.json similarity index 84% rename from vendordeps/PathplannerLib.json rename to vendordeps/PathplannerLib-2026.1.2.json index 73ae375..5f04ffa 100644 --- a/vendordeps/PathplannerLib.json +++ b/vendordeps/PathplannerLib-2026.1.2.json @@ -1,9 +1,9 @@ { - "fileName": "PathplannerLib.json", + "fileName": "PathplannerLib-2026.1.2.json", "name": "PathplannerLib", - "version": "2025.2.7", + "version": "2026.1.2", "uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786", - "frcYear": "2026beta", + "frcYear": "2026", "mavenUrls": [ "https://3015rangerrobotics.github.io/pathplannerlib/repo" ], @@ -12,7 +12,7 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-java", - "version": "2025.2.7" + "version": "2026.1.2" } ], "jniDependencies": [], @@ -20,7 +20,7 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-cpp", - "version": "2025.2.7", + "version": "2026.1.2", "libName": "PathplannerLib", "headerClassifier": "headers", "sharedLibrary": false, diff --git a/vendordeps/Phoenix5-5.36.0-beta-1.json b/vendordeps/Phoenix5-5.36.0.json similarity index 84% rename from vendordeps/Phoenix5-5.36.0-beta-1.json rename to vendordeps/Phoenix5-5.36.0.json index c40f569..c60dd4c 100644 --- a/vendordeps/Phoenix5-5.36.0-beta-1.json +++ b/vendordeps/Phoenix5-5.36.0.json @@ -1,50 +1,50 @@ { - "fileName": "Phoenix5-5.36.0-beta-1.json", + "fileName": "Phoenix5-5.36.0.json", "name": "CTRE-Phoenix (v5)", - "version": "5.36.0-beta-1", - "frcYear": "2026beta", + "version": "5.36.0", + "frcYear": "2026", "uuid": "ab676553-b602-441f-a38d-f1296eff6537", "mavenUrls": [ "https://maven.ctr-electronics.com/release/" ], - "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2026-beta-latest.json", + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2026-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-frc2026-beta-latest.json", - "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2026-beta-latest.json" + "offlineFileName": "Phoenix6-frc2026-latest.json", + "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2026-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-frc2026-beta-latest.json" + "offlineFileName": "Phoenix6-replay-frc2026-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-frc2026-beta-latest.json" + "offlineFileName": "Phoenix5-replay-frc2026-latest.json" } ], "javaDependencies": [ { "groupId": "com.ctre.phoenix", "artifactId": "api-java", - "version": "5.36.0-beta-1" + "version": "5.36.0" }, { "groupId": "com.ctre.phoenix", "artifactId": "wpiapi-java", - "version": "5.36.0-beta-1" + "version": "5.36.0" } ], "jniDependencies": [ { "groupId": "com.ctre.phoenix", "artifactId": "cci", - "version": "5.36.0-beta-1", + "version": "5.36.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -58,7 +58,7 @@ { "groupId": "com.ctre.phoenix.sim", "artifactId": "cci-sim", - "version": "5.36.0-beta-1", + "version": "5.36.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -74,7 +74,7 @@ { "groupId": "com.ctre.phoenix", "artifactId": "wpiapi-cpp", - "version": "5.36.0-beta-1", + "version": "5.36.0", "libName": "CTRE_Phoenix_WPI", "headerClassifier": "headers", "sharedLibrary": true, @@ -90,7 +90,7 @@ { "groupId": "com.ctre.phoenix", "artifactId": "api-cpp", - "version": "5.36.0-beta-1", + "version": "5.36.0", "libName": "CTRE_Phoenix", "headerClassifier": "headers", "sharedLibrary": true, @@ -106,7 +106,7 @@ { "groupId": "com.ctre.phoenix", "artifactId": "cci", - "version": "5.36.0-beta-1", + "version": "5.36.0", "libName": "CTRE_PhoenixCCI", "headerClassifier": "headers", "sharedLibrary": true, @@ -122,7 +122,7 @@ { "groupId": "com.ctre.phoenix.sim", "artifactId": "wpiapi-cpp-sim", - "version": "5.36.0-beta-1", + "version": "5.36.0", "libName": "CTRE_Phoenix_WPISim", "headerClassifier": "headers", "sharedLibrary": true, @@ -138,7 +138,7 @@ { "groupId": "com.ctre.phoenix.sim", "artifactId": "api-cpp-sim", - "version": "5.36.0-beta-1", + "version": "5.36.0", "libName": "CTRE_PhoenixSim", "headerClassifier": "headers", "sharedLibrary": true, @@ -154,7 +154,7 @@ { "groupId": "com.ctre.phoenix.sim", "artifactId": "cci-sim", - "version": "5.36.0-beta-1", + "version": "5.36.0", "libName": "CTRE_PhoenixCCISim", "headerClassifier": "headers", "sharedLibrary": true, diff --git a/vendordeps/Phoenix6-26.0.0-beta-1.json b/vendordeps/Phoenix6-26.1.0.json similarity index 90% rename from vendordeps/Phoenix6-26.0.0-beta-1.json rename to vendordeps/Phoenix6-26.1.0.json index f4686ba..5d2d04d 100644 --- a/vendordeps/Phoenix6-26.0.0-beta-1.json +++ b/vendordeps/Phoenix6-26.1.0.json @@ -1,8 +1,8 @@ { - "fileName": "Phoenix6-26.0.0-beta-1.json", + "fileName": "Phoenix6-26.1.0.json", "name": "CTRE-Phoenix (v6)", - "version": "26.0.0-beta-1", - "frcYear": "2026beta", + "version": "26.1.0", + "frcYear": "2026", "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", "mavenUrls": [ "https://maven.ctr-electronics.com/release/" @@ -19,14 +19,14 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "wpiapi-java", - "version": "26.0.0-beta-1" + "version": "26.1.0" } ], "jniDependencies": [ { "groupId": "com.ctre.phoenix6", "artifactId": "api-cpp", - "version": "26.0.0-beta-1", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -40,7 +40,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "tools", - "version": "26.0.0-beta-1", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -54,7 +54,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "api-cpp-sim", - "version": "26.0.0-beta-1", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -68,7 +68,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "tools-sim", - "version": "26.0.0-beta-1", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -82,7 +82,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonSRX", - "version": "26.0.0-beta-1", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -96,7 +96,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simVictorSPX", - "version": "26.0.0-beta-1", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -110,7 +110,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simPigeonIMU", - "version": "26.0.0-beta-1", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -124,7 +124,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFX", - "version": "26.0.0-beta-1", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -138,7 +138,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFXS", - "version": "26.0.0-beta-1", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -152,7 +152,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANcoder", - "version": "26.0.0-beta-1", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -166,7 +166,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProPigeon2", - "version": "26.0.0-beta-1", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -180,7 +180,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANrange", - "version": "26.0.0-beta-1", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -194,7 +194,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANdi", - "version": "26.0.0-beta-1", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -208,7 +208,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANdle", - "version": "26.0.0-beta-1", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -224,7 +224,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "wpiapi-cpp", - "version": "26.0.0-beta-1", + "version": "26.1.0", "libName": "CTRE_Phoenix6_WPI", "headerClassifier": "headers", "sharedLibrary": true, @@ -240,7 +240,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "tools", - "version": "26.0.0-beta-1", + "version": "26.1.0", "libName": "CTRE_PhoenixTools", "headerClassifier": "headers", "sharedLibrary": true, @@ -256,7 +256,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "wpiapi-cpp-sim", - "version": "26.0.0-beta-1", + "version": "26.1.0", "libName": "CTRE_Phoenix6_WPISim", "headerClassifier": "headers", "sharedLibrary": true, @@ -272,7 +272,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "tools-sim", - "version": "26.0.0-beta-1", + "version": "26.1.0", "libName": "CTRE_PhoenixTools_Sim", "headerClassifier": "headers", "sharedLibrary": true, @@ -288,7 +288,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonSRX", - "version": "26.0.0-beta-1", + "version": "26.1.0", "libName": "CTRE_SimTalonSRX", "headerClassifier": "headers", "sharedLibrary": true, @@ -304,7 +304,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simVictorSPX", - "version": "26.0.0-beta-1", + "version": "26.1.0", "libName": "CTRE_SimVictorSPX", "headerClassifier": "headers", "sharedLibrary": true, @@ -320,7 +320,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simPigeonIMU", - "version": "26.0.0-beta-1", + "version": "26.1.0", "libName": "CTRE_SimPigeonIMU", "headerClassifier": "headers", "sharedLibrary": true, @@ -336,7 +336,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFX", - "version": "26.0.0-beta-1", + "version": "26.1.0", "libName": "CTRE_SimProTalonFX", "headerClassifier": "headers", "sharedLibrary": true, @@ -352,7 +352,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFXS", - "version": "26.0.0-beta-1", + "version": "26.1.0", "libName": "CTRE_SimProTalonFXS", "headerClassifier": "headers", "sharedLibrary": true, @@ -368,7 +368,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANcoder", - "version": "26.0.0-beta-1", + "version": "26.1.0", "libName": "CTRE_SimProCANcoder", "headerClassifier": "headers", "sharedLibrary": true, @@ -384,7 +384,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProPigeon2", - "version": "26.0.0-beta-1", + "version": "26.1.0", "libName": "CTRE_SimProPigeon2", "headerClassifier": "headers", "sharedLibrary": true, @@ -400,7 +400,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANrange", - "version": "26.0.0-beta-1", + "version": "26.1.0", "libName": "CTRE_SimProCANrange", "headerClassifier": "headers", "sharedLibrary": true, @@ -416,7 +416,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANdi", - "version": "26.0.0-beta-1", + "version": "26.1.0", "libName": "CTRE_SimProCANdi", "headerClassifier": "headers", "sharedLibrary": true, @@ -432,7 +432,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANdle", - "version": "26.0.0-beta-1", + "version": "26.1.0", "libName": "CTRE_SimProCANdle", "headerClassifier": "headers", "sharedLibrary": true, diff --git a/vendordeps/REVLib.json b/vendordeps/REVLib.json index a8f2648..bb613bf 100644 --- a/vendordeps/REVLib.json +++ b/vendordeps/REVLib.json @@ -1,8 +1,8 @@ { "fileName": "REVLib.json", "name": "REVLib", - "version": "2026.0.0-beta-1", - "frcYear": "2026beta", + "version": "2026.0.1", + "frcYear": "2026", "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", "mavenUrls": [ "https://maven.revrobotics.com/" @@ -12,14 +12,14 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-java", - "version": "2026.0.0-beta-1" + "version": "2026.0.1" } ], "jniDependencies": [ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2026.0.0-beta-1", + "version": "2026.0.1", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ @@ -34,7 +34,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "RevLibBackendDriver", - "version": "2026.0.0-beta-1", + "version": "2026.0.1", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ @@ -49,7 +49,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "RevLibWpiBackendDriver", - "version": "2026.0.0-beta-1", + "version": "2026.0.1", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ @@ -66,7 +66,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-cpp", - "version": "2026.0.0-beta-1", + "version": "2026.0.1", "libName": "REVLib", "headerClassifier": "headers", "sharedLibrary": false, @@ -83,7 +83,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2026.0.0-beta-1", + "version": "2026.0.1", "libName": "REVLibDriver", "headerClassifier": "headers", "sharedLibrary": false, @@ -100,7 +100,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "RevLibBackendDriver", - "version": "2026.0.0-beta-1", + "version": "2026.0.1", "libName": "BackendDriver", "sharedLibrary": true, "skipInvalidPlatforms": true, @@ -116,7 +116,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "RevLibWpiBackendDriver", - "version": "2026.0.0-beta-1", + "version": "2026.0.1", "libName": "REVLibWpi", "sharedLibrary": true, "skipInvalidPlatforms": true, diff --git a/vendordeps/ReduxLib-2025.0.1.json b/vendordeps/ReduxLib-2026.1.1.json similarity index 74% rename from vendordeps/ReduxLib-2025.0.1.json rename to vendordeps/ReduxLib-2026.1.1.json index 9aaec1c..9081f8b 100644 --- a/vendordeps/ReduxLib-2025.0.1.json +++ b/vendordeps/ReduxLib-2026.1.1.json @@ -1,31 +1,30 @@ { - "fileName": "ReduxLib-2025.0.1.json", + "fileName": "ReduxLib-2026.1.1.json", "name": "ReduxLib", - "version": "2025.0.1", - "frcYear": "2026beta", + "version": "2026.1.1", + "frcYear": "2026", "uuid": "151ecca8-670b-4026-8160-cdd2679ef2bd", "mavenUrls": [ "https://maven.reduxrobotics.com/" ], - "jsonUrl": "https://frcsdk.reduxrobotics.com/ReduxLib_2025.json", + "jsonUrl": "https://frcsdk.reduxrobotics.com/ReduxLib_2026.json", "javaDependencies": [ { "groupId": "com.reduxrobotics.frc", "artifactId": "ReduxLib-java", - "version": "2025.0.1" + "version": "2026.1.1" } ], "jniDependencies": [ { "groupId": "com.reduxrobotics.frc", - "artifactId": "ReduxLib-driver", - "version": "2025.0.1", + "artifactId": "ReduxLib-fifo", + "version": "2026.1.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "linuxathena", "linuxx86-64", - "linuxarm32", "linuxarm64", "osxuniversal", "windowsx86-64" @@ -36,7 +35,7 @@ { "groupId": "com.reduxrobotics.frc", "artifactId": "ReduxLib-cpp", - "version": "2025.0.1", + "version": "2026.1.1", "libName": "ReduxLib", "headerClassifier": "headers", "sourcesClassifier": "sources", @@ -45,7 +44,6 @@ "binaryPlatforms": [ "linuxathena", "linuxx86-64", - "linuxarm32", "linuxarm64", "osxuniversal", "windowsx86-64" @@ -53,16 +51,15 @@ }, { "groupId": "com.reduxrobotics.frc", - "artifactId": "ReduxLib-driver", - "version": "2025.0.1", - "libName": "ReduxCore", + "artifactId": "ReduxLib-fifo", + "version": "2026.1.1", + "libName": "reduxfifo", "headerClassifier": "headers", "sharedLibrary": true, "skipInvalidPlatforms": true, "binaryPlatforms": [ "linuxathena", "linuxx86-64", - "linuxarm32", "linuxarm64", "osxuniversal", "windowsx86-64" diff --git a/vendordeps/Studica-2026.0.0-beta.json b/vendordeps/Studica.json similarity index 85% rename from vendordeps/Studica-2026.0.0-beta.json rename to vendordeps/Studica.json index f664501..daf1434 100644 --- a/vendordeps/Studica-2026.0.0-beta.json +++ b/vendordeps/Studica.json @@ -1,25 +1,25 @@ { - "fileName": "Studica-2026.0.0-beta.json", + "fileName": "Studica.json", "name": "Studica", - "version": "2026.0.0-beta", - "frcYear": "2026beta", + "version": "2026.0.0", + "frcYear": "2026", "uuid": "cb311d09-36e9-4143-a032-55bb2b94443b", "mavenUrls": [ "https://dev.studica.com/maven/release/2026/" ], - "jsonUrl": "https://dev.studica.com/maven/release/2026/json/Studica-2026.0.0-beta.json", + "jsonUrl": "https://dev.studica.com/maven/release/2026/json/Studica-2026.0.0.json", "javaDependencies": [ { "groupId": "com.studica.frc", "artifactId": "Studica-java", - "version": "2026.0.0-beta" + "version": "2026.0.0" } ], "jniDependencies": [ { "groupId": "com.studica.frc", "artifactId": "Studica-driver", - "version": "2026.0.0-beta", + "version": "2026.0.0", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ @@ -36,7 +36,7 @@ { "groupId": "com.studica.frc", "artifactId": "Studica-cpp", - "version": "2026.0.0-beta", + "version": "2026.0.0", "libName": "Studica", "headerClassifier": "headers", "sharedLibrary": false, @@ -53,7 +53,7 @@ { "groupId": "com.studica.frc", "artifactId": "Studica-driver", - "version": "2026.0.0-beta", + "version": "2026.0.0", "libName": "StudicaDriver", "headerClassifier": "headers", "sharedLibrary": false, diff --git a/vendordeps/ThriftyLib.json b/vendordeps/ThriftyLib-2026.0.0.json similarity index 72% rename from vendordeps/ThriftyLib.json rename to vendordeps/ThriftyLib-2026.0.0.json index 795da9d..2ff6a4c 100644 --- a/vendordeps/ThriftyLib.json +++ b/vendordeps/ThriftyLib-2026.0.0.json @@ -1,18 +1,18 @@ { - "fileName": "ThriftyLib.json", + "fileName": "ThriftyLib-2026.0.0.json", "name": "ThriftyLib", - "version": "2026.0.0-beta-1", - "frcYear": "2026beta", + "version": "2026.0.0", + "frcYear": "2026", "uuid": "60b2694b-9e6e-4026-81ee-6f167946f4b0", "mavenUrls": [ "https://docs.home.thethriftybot.com" ], - "jsonUrl": "https://docs.home.thethriftybot.com/ThriftyLib-2026.0.0-beta-1.json", + "jsonUrl": "https://docs.home.thethriftybot.com/ThriftyLib-2026.json", "javaDependencies": [ { "groupId": "com.thethriftybot.frc", "artifactId": "ThriftyLib-java", - "version": "2026.0.0-beta-1" + "version": "2026.0.0" } ], "jniDependencies": [], diff --git a/vendordeps/URCL.json b/vendordeps/URCL.json index fb59513..f5b535e 100644 --- a/vendordeps/URCL.json +++ b/vendordeps/URCL.json @@ -2,7 +2,7 @@ "fileName": "URCL.json", "name": "URCL", "version": "2026.0.0", - "frcYear": "2026beta", + "frcYear": "2026", "uuid": "84246d17-a797-4d1e-bd9f-c59cd8d2477c", "mavenUrls": [ "https://frcmaven.wpi.edu/artifactory/littletonrobotics-mvn-release/" diff --git a/vendordeps/WPILibNewCommands.json b/vendordeps/WPILibNewCommands.json index 7ebc954..d90630e 100644 --- a/vendordeps/WPILibNewCommands.json +++ b/vendordeps/WPILibNewCommands.json @@ -3,7 +3,7 @@ "name": "WPILib-New-Commands", "version": "1.0.0", "uuid": "111e20f7-815e-48f8-9dd6-e675ce75b266", - "frcYear": "2026beta", + "frcYear": "2026", "mavenUrls": [], "jsonUrl": "", "javaDependencies": [ diff --git a/vendordeps/maple-sim.json b/vendordeps/maple-sim.json index 1975151..6596d65 100644 --- a/vendordeps/maple-sim.json +++ b/vendordeps/maple-sim.json @@ -2,7 +2,7 @@ "fileName": "maple-sim.json", "name": "maplesim", "version": "0.3.14", - "frcYear": "2026beta", + "frcYear": "2026", "uuid": "c39481e8-4a63-4a4c-9df6-48d91e4da37b", "mavenUrls": [ "https://shenzhen-robotics-alliance.github.io/maple-sim/vendordep/repos/releases", diff --git a/vendordeps/photonlib.json b/vendordeps/photonlib.json index dfbe6ed..16e6991 100644 --- a/vendordeps/photonlib.json +++ b/vendordeps/photonlib.json @@ -1,9 +1,9 @@ { "fileName": "photonlib.json", "name": "photonlib", - "version": "v2026.0.1-beta", + "version": "v2026.1.1-rc-2", "uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004", - "frcYear": "2026beta", + "frcYear": "2026", "mavenUrls": [ "https://maven.photonvision.org/repository/internal", "https://maven.photonvision.org/repository/snapshots" @@ -13,7 +13,7 @@ { "groupId": "org.photonvision", "artifactId": "photontargeting-cpp", - "version": "v2026.0.1-beta", + "version": "v2026.1.1-rc-2", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ @@ -28,7 +28,7 @@ { "groupId": "org.photonvision", "artifactId": "photonlib-cpp", - "version": "v2026.0.1-beta", + "version": "v2026.1.1-rc-2", "libName": "photonlib", "headerClassifier": "headers", "sharedLibrary": true, @@ -43,7 +43,7 @@ { "groupId": "org.photonvision", "artifactId": "photontargeting-cpp", - "version": "v2026.0.1-beta", + "version": "v2026.1.1-rc-2", "libName": "photontargeting", "headerClassifier": "headers", "sharedLibrary": true, @@ -60,12 +60,12 @@ { "groupId": "org.photonvision", "artifactId": "photonlib-java", - "version": "v2026.0.1-beta" + "version": "v2026.1.1-rc-2" }, { "groupId": "org.photonvision", "artifactId": "photontargeting-java", - "version": "v2026.0.1-beta" + "version": "v2026.1.1-rc-2" } ] } diff --git a/vendordeps/yagsl-2025.8.0.json b/vendordeps/yagsl-2025.8.0.json index 2cb0614..0c9ef4f 100644 --- a/vendordeps/yagsl-2025.8.0.json +++ b/vendordeps/yagsl-2025.8.0.json @@ -2,7 +2,7 @@ "fileName": "yagsl-2025.8.0.json", "name": "YAGSL", "version": "2025.8.0", - "frcYear": "2026beta", + "frcYear": "2026", "uuid": "1ccce5a4-acd2-4d18-bca3-4b8047188400", "mavenUrls": [ "https://broncbotz3481.github.io/YAGSL-Lib/yagsl/repos"