yawTimestampQueue;
diff --git a/src/main/java/frc/robot/subsystems/drive/Module.java b/src/main/java/frc/robot/subsystems/drive/Module.java
index 10425f1..8b647bb 100644
--- a/src/main/java/frc/robot/subsystems/drive/Module.java
+++ b/src/main/java/frc/robot/subsystems/drive/Module.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
-// Copyright (c) 2021-2025 FRC 6328
+// Copyright (c) 2021-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
-// 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.
+// 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.
package frc.robot.subsystems.drive;
@@ -84,7 +78,7 @@ public void runSetpoint(SwerveModuleState state) {
/** Runs the module with the specified output while controlling to zero degrees. */
public void runCharacterization(double output) {
io.setDriveOpenLoop(output);
- io.setTurnPosition(new Rotation2d());
+ io.setTurnPosition(Rotation2d.kZero);
}
/** Disables all outputs to motors. */
diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIO.java b/src/main/java/frc/robot/subsystems/drive/ModuleIO.java
index bcd3bb3..51c8dc6 100644
--- a/src/main/java/frc/robot/subsystems/drive/ModuleIO.java
+++ b/src/main/java/frc/robot/subsystems/drive/ModuleIO.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
-// Copyright (c) 2021-2025 FRC 6328
+// Copyright (c) 2021-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
-// 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.
+// 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.
package frc.robot.subsystems.drive;
@@ -29,8 +23,8 @@ public static class ModuleIOInputs {
public boolean turnConnected = false;
public boolean turnEncoderConnected = false;
- public Rotation2d turnAbsolutePosition = new Rotation2d();
- public Rotation2d turnPosition = new Rotation2d();
+ public Rotation2d turnAbsolutePosition = Rotation2d.kZero;
+ public Rotation2d turnPosition = Rotation2d.kZero;
public double turnVelocityRadPerSec = 0.0;
public double turnAppliedVolts = 0.0;
public double turnCurrentAmps = 0.0;
diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOBlended.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOBlended.java
index 2ffe7fa..b8d66f1 100644
--- a/src/main/java/frc/robot/subsystems/drive/ModuleIOBlended.java
+++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOBlended.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
// Copyright 2024-2025 FRC 2486
// https://github.com/Coconuts2486-FRC
//
-// 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.
+// 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.
package frc.robot.subsystems.drive;
@@ -34,6 +28,7 @@
import com.ctre.phoenix6.swerve.SwerveModuleConstants;
import com.ctre.phoenix6.swerve.SwerveModuleConstants.ClosedLoopOutputType;
import com.ctre.phoenix6.swerve.SwerveModuleConstantsFactory;
+import com.revrobotics.spark.FeedbackSensor;
import com.revrobotics.spark.SparkBase;
import com.revrobotics.spark.SparkBase.ControlType;
import com.revrobotics.spark.SparkBase.PersistMode;
@@ -41,7 +36,6 @@
import com.revrobotics.spark.SparkClosedLoopController;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import com.revrobotics.spark.SparkMax;
-import com.revrobotics.spark.config.ClosedLoopConfig.FeedbackSensor;
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
import com.revrobotics.spark.config.SparkMaxConfig;
import edu.wpi.first.math.MathUtil;
@@ -166,9 +160,9 @@ public ModuleIOBlended(int module) {
default -> throw new IllegalArgumentException("Invalid module index");
};
- driveTalon = new TalonFX(constants.DriveMotorId, SwerveConstants.kCANbusName);
+ driveTalon = new TalonFX(constants.DriveMotorId, kCANBus);
turnSpark = new SparkMax(constants.SteerMotorId, MotorType.kBrushless);
- cancoder = new CANcoder(constants.EncoderId, SwerveConstants.kCANbusName);
+ cancoder = new CANcoder(constants.EncoderId, kCANBus);
turnController = turnSpark.getClosedLoopController();
@@ -204,11 +198,12 @@ public ModuleIOBlended(int module) {
.feedbackSensor(FeedbackSensor.kAbsoluteEncoder)
.positionWrappingEnabled(true)
.positionWrappingInputRange(turnPIDMinInput, turnPIDMaxInput)
- .pidf(
+ .pid(
AutoConstants.kPPsteerPID.kP,
AutoConstants.kPPsteerPID.kI,
- AutoConstants.kPPsteerPID.kD,
- 0.0);
+ AutoConstants.kPPsteerPID.kD)
+ .feedForward
+ .kV(0.0);
turnConfig
.signals
.absoluteEncoderPositionAlwaysOn(true)
@@ -339,7 +334,7 @@ public void setTurnPosition(Rotation2d rotation) {
rotation.plus(Rotation2d.fromRotations(constants.EncoderOffset)).getRadians(),
turnPIDMinInput,
turnPIDMaxInput);
- turnController.setReference(setpoint, ControlType.kPosition);
+ turnController.setSetpoint(setpoint, ControlType.kPosition);
}
private SwerveModuleConstantsFactory<
diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOSim.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOSim.java
index 52950e2..5dfa59b 100644
--- a/src/main/java/frc/robot/subsystems/drive/ModuleIOSim.java
+++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOSim.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
-// Copyright (c) 2021-2025 FRC 6328
+// Copyright (c) 2021-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
-// 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.
+// 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.
package frc.robot.subsystems.drive;
diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java
index 83d9d4a..f915abc 100644
--- a/src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java
+++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
-// Copyright (c) 2021-2025 FRC 6328
+// Copyright (c) 2021-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
-// 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.
+// 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.
package frc.robot.subsystems.drive;
@@ -21,6 +15,7 @@
import com.revrobotics.AbsoluteEncoder;
import com.revrobotics.RelativeEncoder;
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;
@@ -30,7 +25,6 @@
import com.revrobotics.spark.SparkFlex;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import com.revrobotics.spark.SparkMax;
-import com.revrobotics.spark.config.ClosedLoopConfig.FeedbackSensor;
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
import com.revrobotics.spark.config.SparkFlexConfig;
import com.revrobotics.spark.config.SparkMaxConfig;
@@ -76,7 +70,7 @@ public ModuleIOSpark(int module) {
case 1 -> new Rotation2d(kFREncoderOffset);
case 2 -> new Rotation2d(kBLEncoderOffset);
case 3 -> new Rotation2d(kBREncoderOffset);
- default -> new Rotation2d();
+ default -> Rotation2d.kZero;
};
driveSpark =
new SparkFlex(
@@ -134,11 +128,12 @@ public ModuleIOSpark(int module) {
driveConfig
.closedLoop
.feedbackSensor(FeedbackSensor.kPrimaryEncoder)
- .pidf(
+ .pid(
AutoConstants.kPPdrivePID.kP,
AutoConstants.kPPdrivePID.kI,
- AutoConstants.kPPdrivePID.kD,
- 0.0);
+ AutoConstants.kPPdrivePID.kD)
+ .feedForward
+ .kV(0.0);
driveConfig
.signals
.primaryEncoderPositionAlwaysOn(true)
@@ -174,11 +169,12 @@ public ModuleIOSpark(int module) {
.feedbackSensor(FeedbackSensor.kAbsoluteEncoder)
.positionWrappingEnabled(true)
.positionWrappingInputRange(turnPIDMinInput, turnPIDMaxInput)
- .pidf(
+ .pid(
AutoConstants.kPPsteerPID.kP,
AutoConstants.kPPsteerPID.kI,
- AutoConstants.kPPsteerPID.kD,
- 0.0);
+ AutoConstants.kPPsteerPID.kD)
+ .feedForward
+ .kV(0.0);
turnConfig
.signals
.absoluteEncoderPositionAlwaysOn(true)
@@ -259,7 +255,7 @@ public void setDriveVelocity(double velocityRadPerSec) {
double ffVolts =
SwerveConstants.kDriveFrictionVoltage * Math.signum(velocityRadPerSec)
+ driveKv * velocityRadPerSec;
- driveController.setReference(
+ driveController.setSetpoint(
velocityRadPerSec,
ControlType.kVelocity,
ClosedLoopSlot.kSlot0,
@@ -272,6 +268,6 @@ public void setTurnPosition(Rotation2d rotation) {
double setpoint =
MathUtil.inputModulus(
rotation.plus(zeroRotation).getRadians(), turnPIDMinInput, turnPIDMaxInput);
- turnController.setReference(setpoint, ControlType.kPosition);
+ turnController.setSetpoint(setpoint, ControlType.kPosition);
}
}
diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkCANcoder.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkCANcoder.java
index f248e2b..31f4cf7 100644
--- a/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkCANcoder.java
+++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkCANcoder.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
-// Copyright (c) 2021-2025 FRC 6328
+// Copyright (c) 2021-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
-// 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.
+// 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.
package frc.robot.subsystems.drive;
@@ -23,6 +17,7 @@
import com.ctre.phoenix6.hardware.CANcoder;
import com.revrobotics.RelativeEncoder;
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;
@@ -32,7 +27,6 @@
import com.revrobotics.spark.SparkFlex;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import com.revrobotics.spark.SparkMax;
-import com.revrobotics.spark.config.ClosedLoopConfig.FeedbackSensor;
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
import com.revrobotics.spark.config.SparkFlexConfig;
import com.revrobotics.spark.config.SparkMaxConfig;
@@ -87,7 +81,7 @@ public ModuleIOSparkCANcoder(int module) {
case 1 -> new Rotation2d(kFREncoderOffset);
case 2 -> new Rotation2d(kBLEncoderOffset);
case 3 -> new Rotation2d(kBREncoderOffset);
- default -> new Rotation2d();
+ default -> Rotation2d.kZero;
};
driveSpark =
new SparkFlex(
@@ -135,7 +129,7 @@ public ModuleIOSparkCANcoder(int module) {
case 3 -> kBREncoderId;
default -> 0;
},
- kCANbusName);
+ kCANBus);
driveController = driveSpark.getClosedLoopController();
turnController = turnSpark.getClosedLoopController();
@@ -154,11 +148,12 @@ public ModuleIOSparkCANcoder(int module) {
driveConfig
.closedLoop
.feedbackSensor(FeedbackSensor.kPrimaryEncoder)
- .pidf(
+ .pid(
AutoConstants.kPPdrivePID.kP,
AutoConstants.kPPdrivePID.kI,
- AutoConstants.kPPdrivePID.kD,
- 0.0);
+ AutoConstants.kPPdrivePID.kD)
+ .feedForward
+ .kV(0.0);
driveConfig
.signals
.primaryEncoderPositionAlwaysOn(true)
@@ -194,11 +189,12 @@ public ModuleIOSparkCANcoder(int module) {
.feedbackSensor(FeedbackSensor.kAbsoluteEncoder)
.positionWrappingEnabled(true)
.positionWrappingInputRange(turnPIDMinInput, turnPIDMaxInput)
- .pidf(
+ .pid(
AutoConstants.kPPsteerPID.kP,
AutoConstants.kPPsteerPID.kI,
- AutoConstants.kPPsteerPID.kD,
- 0.0);
+ AutoConstants.kPPsteerPID.kD)
+ .feedForward
+ .kV(0.0);
turnConfig
.signals
.absoluteEncoderPositionAlwaysOn(true)
@@ -286,7 +282,7 @@ public void setDriveVelocity(double velocityRadPerSec) {
double ffVolts =
SwerveConstants.kDriveFrictionVoltage * Math.signum(velocityRadPerSec)
+ driveKv * velocityRadPerSec;
- driveController.setReference(
+ driveController.setSetpoint(
velocityRadPerSec,
ControlType.kVelocity,
ClosedLoopSlot.kSlot0,
@@ -299,6 +295,6 @@ public void setTurnPosition(Rotation2d rotation) {
double setpoint =
MathUtil.inputModulus(
rotation.plus(zeroRotation).getRadians(), turnPIDMinInput, turnPIDMaxInput);
- turnController.setReference(setpoint, ControlType.kPosition);
+ turnController.setSetpoint(setpoint, ControlType.kPosition);
}
}
diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java
index 20d5db3..5dbcc06 100644
--- a/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java
+++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java
@@ -1,20 +1,15 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
-// Copyright (c) 2021-2025 FRC 6328
+// Copyright (c) 2021-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
-// 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.
+// 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.
package frc.robot.subsystems.drive;
+import static frc.robot.subsystems.drive.SwerveConstants.*;
import static frc.robot.util.PhoenixUtil.*;
import com.ctre.phoenix6.BaseStatusSignal;
@@ -111,9 +106,9 @@ public ModuleIOTalonFX(int module) {
default -> throw new IllegalArgumentException("Invalid module index");
};
- driveTalon = new TalonFX(constants.DriveMotorId, SwerveConstants.kCANbusName);
- turnTalon = new TalonFX(constants.SteerMotorId, SwerveConstants.kCANbusName);
- cancoder = new CANcoder(constants.EncoderId, SwerveConstants.kCANbusName);
+ driveTalon = new TalonFX(constants.DriveMotorId, kCANBus);
+ turnTalon = new TalonFX(constants.SteerMotorId, kCANBus);
+ cancoder = new CANcoder(constants.EncoderId, kCANBus);
// Configure drive motor
var driveConfig = constants.DriveMotorInitialConfigs;
diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFXS.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFXS.java
new file mode 100644
index 0000000..79a2109
--- /dev/null
+++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFXS.java
@@ -0,0 +1,253 @@
+// Copyright (c) 2024-2026 Az-FIRST
+// http://github.com/AZ-First
+// 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 LICENSE file
+// at the root directory of this project.
+
+package frc.robot.subsystems.drive;
+
+import static frc.robot.subsystems.drive.SwerveConstants.*;
+import static frc.robot.util.PhoenixUtil.*;
+
+import com.ctre.phoenix6.BaseStatusSignal;
+import com.ctre.phoenix6.StatusSignal;
+import com.ctre.phoenix6.configs.CANdiConfiguration;
+import com.ctre.phoenix6.configs.TalonFXSConfiguration;
+import com.ctre.phoenix6.controls.PositionVoltage;
+import com.ctre.phoenix6.controls.VelocityVoltage;
+import com.ctre.phoenix6.controls.VoltageOut;
+import com.ctre.phoenix6.hardware.CANdi;
+import com.ctre.phoenix6.hardware.ParentDevice;
+import com.ctre.phoenix6.hardware.TalonFXS;
+import com.ctre.phoenix6.signals.BrushedMotorWiringValue;
+import com.ctre.phoenix6.signals.ExternalFeedbackSensorSourceValue;
+import com.ctre.phoenix6.signals.InvertedValue;
+import com.ctre.phoenix6.signals.MotorArrangementValue;
+import com.ctre.phoenix6.signals.NeutralModeValue;
+import com.ctre.phoenix6.swerve.SwerveModuleConstants;
+import edu.wpi.first.math.filter.Debouncer;
+import edu.wpi.first.math.geometry.Rotation2d;
+import edu.wpi.first.math.util.Units;
+import edu.wpi.first.units.measure.Angle;
+import edu.wpi.first.units.measure.AngularVelocity;
+import edu.wpi.first.units.measure.Current;
+import edu.wpi.first.units.measure.Voltage;
+import java.util.Queue;
+
+/**
+ * Module IO implementation for Talon FXS drive motor controller, Talon FXS turn motor controller,
+ * and CANdi (PWM 1). Configured using a set of module constants from Phoenix.
+ *
+ * Device configuration and other behaviors not exposed by TunerConstants can be customized here.
+ */
+public class ModuleIOTalonFXS implements ModuleIO {
+ // Hardware objects
+ private final TalonFXS driveTalon;
+ private final TalonFXS turnTalon;
+ private final CANdi candi;
+
+ // Voltage control requests
+ private final VoltageOut voltageRequest = new VoltageOut(0);
+ private final PositionVoltage positionVoltageRequest = new PositionVoltage(0.0);
+ private final VelocityVoltage velocityVoltageRequest = new VelocityVoltage(0.0);
+
+ // Timestamp inputs from Phoenix thread
+ private final Queue timestampQueue;
+
+ // Inputs from drive motor
+ private final StatusSignal drivePosition;
+ private final Queue drivePositionQueue;
+ private final StatusSignal driveVelocity;
+ private final StatusSignal driveAppliedVolts;
+ private final StatusSignal driveCurrent;
+
+ // Inputs from turn motor
+ private final StatusSignal turnAbsolutePosition;
+ private final StatusSignal turnPosition;
+ private final Queue turnPositionQueue;
+ private final StatusSignal turnVelocity;
+ private final StatusSignal turnAppliedVolts;
+ private final StatusSignal turnCurrent;
+
+ // Connection debouncers
+ 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);
+
+ public ModuleIOTalonFXS(
+ SwerveModuleConstants
+ constants) {
+ driveTalon = new TalonFXS(constants.DriveMotorId, kCANBus);
+ turnTalon = new TalonFXS(constants.SteerMotorId, kCANBus);
+ candi = new CANdi(constants.EncoderId, kCANBus);
+
+ // Configure drive motor
+ var driveConfig = constants.DriveMotorInitialConfigs;
+ driveConfig.Commutation.MotorArrangement =
+ switch (constants.DriveMotorType) {
+ case TalonFXS_NEO_JST -> MotorArrangementValue.NEO_JST;
+ case TalonFXS_VORTEX_JST -> MotorArrangementValue.VORTEX_JST;
+ default -> MotorArrangementValue.Disabled;
+ };
+ driveConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake;
+ driveConfig.Slot0 = constants.DriveMotorGains;
+ driveConfig.ExternalFeedback.SensorToMechanismRatio = constants.DriveMotorGearRatio;
+ driveConfig.CurrentLimits.StatorCurrentLimit = constants.SlipCurrent;
+ driveConfig.CurrentLimits.StatorCurrentLimitEnable = true;
+ driveConfig.MotorOutput.Inverted =
+ constants.DriveMotorInverted
+ ? InvertedValue.Clockwise_Positive
+ : InvertedValue.CounterClockwise_Positive;
+ tryUntilOk(5, () -> driveTalon.getConfigurator().apply(driveConfig, 0.25));
+ tryUntilOk(5, () -> driveTalon.setPosition(0.0, 0.25));
+
+ // Configure turn motor
+ var turnConfig = new TalonFXSConfiguration();
+ turnConfig.Commutation.MotorArrangement =
+ switch (constants.SteerMotorType) {
+ case TalonFXS_Minion_JST -> MotorArrangementValue.Minion_JST;
+ case TalonFXS_NEO_JST -> MotorArrangementValue.NEO_JST;
+ case TalonFXS_VORTEX_JST -> MotorArrangementValue.VORTEX_JST;
+ case TalonFXS_NEO550_JST -> MotorArrangementValue.NEO550_JST;
+ case TalonFXS_Brushed_AB, TalonFXS_Brushed_AC, TalonFXS_Brushed_BC ->
+ MotorArrangementValue.Brushed_DC;
+ default -> MotorArrangementValue.Disabled;
+ };
+ turnConfig.Commutation.BrushedMotorWiring =
+ switch (constants.SteerMotorType) {
+ case TalonFXS_Brushed_AC -> BrushedMotorWiringValue.Leads_A_and_C;
+ case TalonFXS_Brushed_BC -> BrushedMotorWiringValue.Leads_B_and_C;
+ default -> BrushedMotorWiringValue.Leads_A_and_B;
+ };
+ turnConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake;
+ turnConfig.Slot0 = constants.SteerMotorGains;
+ turnConfig.ExternalFeedback.FeedbackRemoteSensorID = constants.EncoderId;
+ turnConfig.ExternalFeedback.ExternalFeedbackSensorSource =
+ switch (constants.FeedbackSource) {
+ case RemoteCANdiPWM1 -> ExternalFeedbackSensorSourceValue.RemoteCANdiPWM1;
+ case FusedCANdiPWM1 -> ExternalFeedbackSensorSourceValue.FusedCANdiPWM1;
+ case SyncCANdiPWM1 -> ExternalFeedbackSensorSourceValue.SyncCANdiPWM1;
+ default ->
+ throw new RuntimeException(
+ "You have selected a turn feedback source that is not supported by the default implementation of ModuleIOTalonFXS (CANdi PWM 1). Please check the AdvantageKit documentation for more information on alternative configurations: https://docs.advantagekit.org/getting-started/template-projects/talonfx-swerve-template#custom-module-implementations");
+ };
+ turnConfig.ExternalFeedback.RotorToSensorRatio = constants.SteerMotorGearRatio;
+ turnConfig.MotionMagic.MotionMagicCruiseVelocity = 100.0 / constants.SteerMotorGearRatio;
+ turnConfig.MotionMagic.MotionMagicAcceleration =
+ turnConfig.MotionMagic.MotionMagicCruiseVelocity / 0.100;
+ turnConfig.MotionMagic.MotionMagicExpo_kV = 0.12 * constants.SteerMotorGearRatio;
+ turnConfig.MotionMagic.MotionMagicExpo_kA = 0.1;
+ turnConfig.ClosedLoopGeneral.ContinuousWrap = true;
+ turnConfig.MotorOutput.Inverted =
+ constants.SteerMotorInverted
+ ? InvertedValue.Clockwise_Positive
+ : InvertedValue.CounterClockwise_Positive;
+ tryUntilOk(5, () -> turnTalon.getConfigurator().apply(turnConfig, 0.25));
+
+ // Configure CANdi
+ CANdiConfiguration candiConfig = constants.EncoderInitialConfigs;
+ candiConfig.PWM1.AbsoluteSensorOffset = constants.EncoderOffset;
+ candiConfig.PWM1.SensorDirection = constants.EncoderInverted;
+ candi.getConfigurator().apply(candiConfig);
+
+ // Create timestamp queue
+ timestampQueue = PhoenixOdometryThread.getInstance().makeTimestampQueue();
+
+ // Create drive status signals
+ drivePosition = driveTalon.getPosition();
+ drivePositionQueue = PhoenixOdometryThread.getInstance().registerSignal(drivePosition.clone());
+ driveVelocity = driveTalon.getVelocity();
+ driveAppliedVolts = driveTalon.getMotorVoltage();
+ driveCurrent = driveTalon.getStatorCurrent();
+
+ // Create turn status signals
+ turnAbsolutePosition = candi.getPWM1Position();
+ turnPosition = turnTalon.getPosition();
+ turnPositionQueue = PhoenixOdometryThread.getInstance().registerSignal(turnPosition.clone());
+ turnVelocity = turnTalon.getVelocity();
+ turnAppliedVolts = turnTalon.getMotorVoltage();
+ turnCurrent = turnTalon.getStatorCurrent();
+
+ // Configure periodic frames
+ BaseStatusSignal.setUpdateFrequencyForAll(
+ SwerveConstants.kOdometryFrequency, drivePosition, turnPosition);
+ BaseStatusSignal.setUpdateFrequencyForAll(
+ 50.0,
+ driveVelocity,
+ driveAppliedVolts,
+ driveCurrent,
+ turnAbsolutePosition,
+ turnVelocity,
+ turnAppliedVolts,
+ turnCurrent);
+ ParentDevice.optimizeBusUtilizationForAll(driveTalon, turnTalon);
+ }
+
+ @Override
+ public void updateInputs(ModuleIOInputs inputs) {
+ // Refresh all signals
+ var driveStatus =
+ BaseStatusSignal.refreshAll(drivePosition, driveVelocity, driveAppliedVolts, driveCurrent);
+ var turnStatus =
+ BaseStatusSignal.refreshAll(turnPosition, turnVelocity, turnAppliedVolts, turnCurrent);
+ var turnEncoderStatus = BaseStatusSignal.refreshAll(turnAbsolutePosition);
+
+ // Update drive inputs
+ inputs.driveConnected = driveConnectedDebounce.calculate(driveStatus.isOK());
+ inputs.drivePositionRad = Units.rotationsToRadians(drivePosition.getValueAsDouble());
+ inputs.driveVelocityRadPerSec = Units.rotationsToRadians(driveVelocity.getValueAsDouble());
+ inputs.driveAppliedVolts = driveAppliedVolts.getValueAsDouble();
+ inputs.driveCurrentAmps = driveCurrent.getValueAsDouble();
+
+ // Update turn inputs
+ inputs.turnConnected = turnConnectedDebounce.calculate(turnStatus.isOK());
+ inputs.turnEncoderConnected = turnEncoderConnectedDebounce.calculate(turnEncoderStatus.isOK());
+ inputs.turnAbsolutePosition = Rotation2d.fromRotations(turnAbsolutePosition.getValueAsDouble());
+ inputs.turnPosition = Rotation2d.fromRotations(turnPosition.getValueAsDouble());
+ inputs.turnVelocityRadPerSec = Units.rotationsToRadians(turnVelocity.getValueAsDouble());
+ inputs.turnAppliedVolts = turnAppliedVolts.getValueAsDouble();
+ inputs.turnCurrentAmps = turnCurrent.getValueAsDouble();
+
+ // Update odometry inputs
+ inputs.odometryTimestamps =
+ timestampQueue.stream().mapToDouble((Double value) -> value).toArray();
+ inputs.odometryDrivePositionsRad =
+ drivePositionQueue.stream()
+ .mapToDouble((Double value) -> Units.rotationsToRadians(value))
+ .toArray();
+ inputs.odometryTurnPositions =
+ turnPositionQueue.stream()
+ .map((Double value) -> Rotation2d.fromRotations(value))
+ .toArray(Rotation2d[]::new);
+ timestampQueue.clear();
+ drivePositionQueue.clear();
+ turnPositionQueue.clear();
+ }
+
+ @Override
+ public void setDriveOpenLoop(double output) {
+ driveTalon.setControl(voltageRequest.withOutput(output));
+ }
+
+ @Override
+ public void setTurnOpenLoop(double output) {
+ turnTalon.setControl(voltageRequest.withOutput(output));
+ }
+
+ @Override
+ public void setDriveVelocity(double velocityRadPerSec) {
+ double velocityRotPerSec = Units.radiansToRotations(velocityRadPerSec);
+ driveTalon.setControl(velocityVoltageRequest.withVelocity(velocityRotPerSec));
+ }
+
+ @Override
+ public void setTurnPosition(Rotation2d rotation) {
+ turnTalon.setControl(positionVoltageRequest.withPosition(rotation.getRotations()));
+ }
+}
diff --git a/src/main/java/frc/robot/subsystems/drive/PhoenixOdometryThread.java b/src/main/java/frc/robot/subsystems/drive/PhoenixOdometryThread.java
index 3b3a2e5..188f987 100644
--- a/src/main/java/frc/robot/subsystems/drive/PhoenixOdometryThread.java
+++ b/src/main/java/frc/robot/subsystems/drive/PhoenixOdometryThread.java
@@ -1,22 +1,15 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
-// Copyright (c) 2021-2025 FRC 6328
+// Copyright (c) 2021-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
-// 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.
+// 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.
package frc.robot.subsystems.drive;
import com.ctre.phoenix6.BaseStatusSignal;
-import com.ctre.phoenix6.CANBus;
import com.ctre.phoenix6.StatusSignal;
import edu.wpi.first.units.measure.Angle;
import edu.wpi.first.wpilibj.RobotController;
@@ -46,8 +39,7 @@ public class PhoenixOdometryThread extends Thread {
private final List> genericQueues = new ArrayList<>();
private final List> timestampQueues = new ArrayList<>();
- private static boolean isCANFD =
- new CANBus(TunerConstants.DrivetrainConstants.CANBusName).isNetworkFD();
+ private static boolean isCANFD = TunerConstants.kCANBus.isNetworkFD();
private static PhoenixOdometryThread instance = null;
public static PhoenixOdometryThread getInstance() {
diff --git a/src/main/java/frc/robot/subsystems/drive/SparkOdometryThread.java b/src/main/java/frc/robot/subsystems/drive/SparkOdometryThread.java
index 8ccb2ed..c97fc50 100644
--- a/src/main/java/frc/robot/subsystems/drive/SparkOdometryThread.java
+++ b/src/main/java/frc/robot/subsystems/drive/SparkOdometryThread.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
-// Copyright (c) 2021-2025 FRC 6328
+// Copyright (c) 2021-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
-// 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.
+// 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.
package frc.robot.subsystems.drive;
diff --git a/src/main/java/frc/robot/subsystems/drive/SwerveConstants.java b/src/main/java/frc/robot/subsystems/drive/SwerveConstants.java
index cffffbf..975083c 100644
--- a/src/main/java/frc/robot/subsystems/drive/SwerveConstants.java
+++ b/src/main/java/frc/robot/subsystems/drive/SwerveConstants.java
@@ -1,15 +1,9 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-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.
+// 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.
package frc.robot.subsystems.drive;
@@ -35,6 +29,7 @@ public class SwerveConstants {
public static final double kWheelRadiusInches;
public static final double kWheelRadiusMeters;
public static final String kCANbusName;
+ public static final CANBus kCANBus;
public static final int kPigeonId;
public static final double kSteerInertia;
public static final double kDriveInertia;
@@ -116,6 +111,7 @@ public class SwerveConstants {
kWheelRadiusMeters = TunerConstants.FrontLeft.WheelRadius;
kWheelRadiusInches = Units.metersToInches(kWheelRadiusMeters);
kCANbusName = TunerConstants.DrivetrainConstants.CANBusName;
+ kCANBus = new CANBus(TunerConstants.DrivetrainConstants.CANBusName);
kPigeonId = TunerConstants.DrivetrainConstants.Pigeon2Id;
kSteerInertia = TunerConstants.FrontLeft.SteerInertia;
kDriveInertia = TunerConstants.FrontLeft.DriveInertia;
@@ -201,6 +197,7 @@ public class SwerveConstants {
kWheelRadiusInches = YagslConstants.kWheelRadiusInches;
kWheelRadiusMeters = Units.inchesToMeters(kWheelRadiusInches);
kCANbusName = YagslConstants.kCANbusName;
+ kCANBus = new CANBus(YagslConstants.kCANbusName);
kPigeonId = YagslConstants.kPigeonId;
kSteerInertia = YagslConstants.kSteerInertia;
kDriveInertia = YagslConstants.kDriveInertia;
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 685d01e..071231d 100644
--- a/src/main/java/frc/robot/subsystems/flywheel_example/Flywheel.java
+++ b/src/main/java/frc/robot/subsystems/flywheel_example/Flywheel.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
-// Copyright (c) 2021-2025 FRC 6328
+// Copyright (c) 2021-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
-// 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.
+// 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.
package frc.robot.subsystems.flywheel_example;
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 261e1bc..5dc4953 100644
--- a/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIO.java
+++ b/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIO.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
-// Copyright (c) 2021-2025 FRC 6328
+// Copyright (c) 2021-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
-// 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.
+// 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.
package frc.robot.subsystems.flywheel_example;
diff --git a/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIOSim.java b/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIOSim.java
index a4a82cd..d65eade 100644
--- a/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIOSim.java
+++ b/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIOSim.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
-// Copyright (c) 2021-2025 FRC 6328
+// Copyright (c) 2021-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
-// 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.
+// 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.
package frc.robot.subsystems.flywheel_example;
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 871a9de..98c122b 100644
--- a/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIOSpark.java
+++ b/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIOSpark.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
-// Copyright (c) 2021-2025 FRC 6328
+// Copyright (c) 2021-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
-// 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.
+// 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.
package frc.robot.subsystems.flywheel_example;
@@ -20,6 +14,7 @@
import com.revrobotics.RelativeEncoder;
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;
@@ -28,7 +23,6 @@
import com.revrobotics.spark.SparkClosedLoopController.ArbFFUnits;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import com.revrobotics.spark.SparkMax;
-import com.revrobotics.spark.config.ClosedLoopConfig.FeedbackSensor;
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
import com.revrobotics.spark.config.SparkFlexConfig;
import edu.wpi.first.math.util.Units;
@@ -70,9 +64,9 @@ public FlywheelIOSpark() {
leaderConfig
.closedLoop
.feedbackSensor(FeedbackSensor.kPrimaryEncoder)
- .pidf(
- 0.0, 0.0,
- 0.0, 0.0);
+ .pid(0.0, 0.0, 0.0)
+ .feedForward
+ .kV(0.0);
leaderConfig
.signals
.primaryEncoderPositionAlwaysOn(true)
@@ -107,7 +101,7 @@ public void setVoltage(double volts) {
@Override
public void setVelocity(double velocityRadPerSec, double ffVolts) {
- pid.setReference(
+ pid.setSetpoint(
Units.radiansPerSecondToRotationsPerMinute(velocityRadPerSec) * kFlywheelGearRatio,
ControlType.kVelocity,
ClosedLoopSlot.kSlot0,
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 9364d32..571b596 100644
--- a/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIOTalonFX.java
+++ b/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIOTalonFX.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
-// Copyright (c) 2021-2025 FRC 6328
+// Copyright (c) 2021-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
-// 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.
+// 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.
package frc.robot.subsystems.flywheel_example;
@@ -25,6 +19,7 @@
import com.ctre.phoenix6.controls.VelocityVoltage;
import com.ctre.phoenix6.controls.VoltageOut;
import com.ctre.phoenix6.hardware.TalonFX;
+import com.ctre.phoenix6.signals.MotorAlignmentValue;
import com.ctre.phoenix6.signals.NeutralModeValue;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.units.measure.Angle;
@@ -39,11 +34,11 @@ public class FlywheelIOTalonFX implements FlywheelIO {
private final TalonFX leader =
new TalonFX(
CANandPowerPorts.FLYWHEEL_LEADER.getDeviceNumber(),
- CANandPowerPorts.FLYWHEEL_LEADER.getBus());
+ CANandPowerPorts.FLYWHEEL_LEADER.getCANBus());
private final TalonFX follower =
new TalonFX(
CANandPowerPorts.FLYWHEEL_FOLLOWER.getDeviceNumber(),
- CANandPowerPorts.FLYWHEEL_FOLLOWER.getBus());
+ CANandPowerPorts.FLYWHEEL_FOLLOWER.getCANBus());
// IMPORTANT: Include here all devices listed above that are part of this mechanism!
public final int[] powerPorts = {
CANandPowerPorts.FLYWHEEL_LEADER.getPowerPort(),
@@ -67,8 +62,8 @@ public FlywheelIOTalonFX() {
};
leader.getConfigurator().apply(config);
follower.getConfigurator().apply(config);
- // If follower rotates in the opposite direction, set "OpposeMasterDirection" to true
- follower.setControl(new Follower(leader.getDeviceID(), false));
+ // If follower rotates in the opposite direction, set "MotorAlignmentValue" to Opposed
+ follower.setControl(new Follower(leader.getDeviceID(), MotorAlignmentValue.Aligned));
BaseStatusSignal.setUpdateFrequencyForAll(
50.0, leaderPosition, leaderVelocity, leaderAppliedVolts, leaderCurrent, followerCurrent);
diff --git a/src/main/java/frc/robot/subsystems/vision/Vision.java b/src/main/java/frc/robot/subsystems/vision/Vision.java
index 34c676a..621cbf7 100644
--- a/src/main/java/frc/robot/subsystems/vision/Vision.java
+++ b/src/main/java/frc/robot/subsystems/vision/Vision.java
@@ -1,19 +1,13 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
// Copyright (c) 2024-2025 FRC 2486
// http://github.com/Coconuts2486-FRC
-// Copyright (c) 2021-2025 FRC 6328
+// Copyright (c) 2021-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
-// 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.
+// 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.
package frc.robot.subsystems.vision;
diff --git a/src/main/java/frc/robot/subsystems/vision/VisionIO.java b/src/main/java/frc/robot/subsystems/vision/VisionIO.java
index 6755c3a..c9ed834 100644
--- a/src/main/java/frc/robot/subsystems/vision/VisionIO.java
+++ b/src/main/java/frc/robot/subsystems/vision/VisionIO.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
-// Copyright (c) 2021-2025 FRC 6328
+// Copyright (c) 2021-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
-// 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.
+// 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.
package frc.robot.subsystems.vision;
@@ -24,7 +18,7 @@ public interface VisionIO {
public static class VisionIOInputs {
public boolean connected = false;
public TargetObservation latestTargetObservation =
- new TargetObservation(new Rotation2d(), new Rotation2d());
+ new TargetObservation(Rotation2d.kZero, Rotation2d.kZero);
public PoseObservation[] poseObservations = new PoseObservation[0];
public int[] tagIds = new int[0];
}
diff --git a/src/main/java/frc/robot/subsystems/vision/VisionIOLimelight.java b/src/main/java/frc/robot/subsystems/vision/VisionIOLimelight.java
index 14e06a8..a4b1eaf 100644
--- a/src/main/java/frc/robot/subsystems/vision/VisionIOLimelight.java
+++ b/src/main/java/frc/robot/subsystems/vision/VisionIOLimelight.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
-// Copyright (c) 2021-2025 FRC 6328
+// Copyright (c) 2021-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
-// 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.
+// 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.
package frc.robot.subsystems.vision;
diff --git a/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVision.java b/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVision.java
index df70163..5ed068e 100644
--- a/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVision.java
+++ b/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVision.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
-// Copyright (c) 2021-2025 FRC 6328
+// Copyright (c) 2021-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
-// 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.
+// 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.
package frc.robot.subsystems.vision;
@@ -57,7 +51,7 @@ public void updateInputs(VisionIOInputs inputs) {
Rotation2d.fromDegrees(result.getBestTarget().getYaw()),
Rotation2d.fromDegrees(result.getBestTarget().getPitch()));
} else {
- inputs.latestTargetObservation = new TargetObservation(new Rotation2d(), new Rotation2d());
+ inputs.latestTargetObservation = new TargetObservation(Rotation2d.kZero, Rotation2d.kZero);
}
// Add pose observation
diff --git a/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVisionSim.java b/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVisionSim.java
index e657459..97d01d3 100644
--- a/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVisionSim.java
+++ b/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVisionSim.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
-// Copyright (c) 2021-2025 FRC 6328
+// Copyright (c) 2021-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
-// 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.
+// 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.
package frc.robot.subsystems.vision;
diff --git a/src/main/java/frc/robot/util/Alert.java b/src/main/java/frc/robot/util/Alert.java
index b29d4ee..7ffb896 100644
--- a/src/main/java/frc/robot/util/Alert.java
+++ b/src/main/java/frc/robot/util/Alert.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
// Copyright (c) 2024-2025 FRC 6328
// 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
-// 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.
+// 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.
package frc.robot.util;
diff --git a/src/main/java/frc/robot/util/GeomUtil.java b/src/main/java/frc/robot/util/GeomUtil.java
index 3bc1578..7d1eb18 100644
--- a/src/main/java/frc/robot/util/GeomUtil.java
+++ b/src/main/java/frc/robot/util/GeomUtil.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
// Copyright (c) 2024 FRC 6328
// 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
-// 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.
+// 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.
package frc.robot.util;
@@ -33,7 +27,7 @@ public class GeomUtil {
* @return The resulting transform
*/
public static Transform2d toTransform2d(Translation2d translation) {
- return new Transform2d(translation, new Rotation2d());
+ return new Transform2d(translation, Rotation2d.kZero);
}
/**
@@ -44,7 +38,7 @@ public static Transform2d toTransform2d(Translation2d translation) {
* @return The resulting transform
*/
public static Transform2d toTransform2d(double x, double y) {
- return new Transform2d(x, y, new Rotation2d());
+ return new Transform2d(x, y, Rotation2d.kZero);
}
/**
@@ -54,7 +48,7 @@ public static Transform2d toTransform2d(double x, double y) {
* @return The resulting transform
*/
public static Transform2d toTransform2d(Rotation2d rotation) {
- return new Transform2d(new Translation2d(), rotation);
+ return new Transform2d(Translation2d.kZero, rotation);
}
/**
@@ -91,7 +85,7 @@ public static Pose2d toPose2d(Transform2d transform) {
* @return The resulting pose
*/
public static Pose2d toPose2d(Translation2d translation) {
- return new Pose2d(translation, new Rotation2d());
+ return new Pose2d(translation, Rotation2d.kZero);
}
/**
@@ -101,7 +95,7 @@ public static Pose2d toPose2d(Translation2d translation) {
* @return The resulting pose
*/
public static Pose2d toPose2d(Rotation2d rotation) {
- return new Pose2d(new Translation2d(), rotation);
+ return new Pose2d(Translation2d.kZero, rotation);
}
/**
diff --git a/src/main/java/frc/robot/util/GetJoystickValue.java b/src/main/java/frc/robot/util/GetJoystickValue.java
index d83b901..c149845 100644
--- a/src/main/java/frc/robot/util/GetJoystickValue.java
+++ b/src/main/java/frc/robot/util/GetJoystickValue.java
@@ -1,15 +1,9 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-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.
+// 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.
package frc.robot.util;
diff --git a/src/main/java/frc/robot/util/LocalADStarAK.java b/src/main/java/frc/robot/util/LocalADStarAK.java
index e7828e5..214b2c2 100644
--- a/src/main/java/frc/robot/util/LocalADStarAK.java
+++ b/src/main/java/frc/robot/util/LocalADStarAK.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
// Copyright (c) 2024 Michael Jansen
// http://gist.github.com/mjansen4857
//
-// 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.
+// 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.
package frc.robot.util;
diff --git a/src/main/java/frc/robot/util/LoggedTunableNumber.java b/src/main/java/frc/robot/util/LoggedTunableNumber.java
index 9db5d1c..7debee0 100644
--- a/src/main/java/frc/robot/util/LoggedTunableNumber.java
+++ b/src/main/java/frc/robot/util/LoggedTunableNumber.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
// Copyright (c) 2024 FRC 6328
// 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
-// 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.
+// 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.
package frc.robot.util;
diff --git a/src/main/java/frc/robot/util/OverrideSwitches.java b/src/main/java/frc/robot/util/OverrideSwitches.java
index 9301bab..6d9fddc 100644
--- a/src/main/java/frc/robot/util/OverrideSwitches.java
+++ b/src/main/java/frc/robot/util/OverrideSwitches.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
// Copyright (c) 2024 FRC 6328
// 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
-// 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.
+// 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.
// NOTE: This module assumes the design described in FRC6328's 2024 Chief
// Delphi build thread:
diff --git a/src/main/java/frc/robot/util/PhoenixUtil.java b/src/main/java/frc/robot/util/PhoenixUtil.java
index 2895118..fd7d10b 100644
--- a/src/main/java/frc/robot/util/PhoenixUtil.java
+++ b/src/main/java/frc/robot/util/PhoenixUtil.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
-// Copyright (c) 2021-2025 FRC 6328
+// Copyright (c) 2021-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
-// 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.
+// 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.
package frc.robot.util;
diff --git a/src/main/java/frc/robot/util/RBSIEnum.java b/src/main/java/frc/robot/util/RBSIEnum.java
index 00495da..93f9622 100644
--- a/src/main/java/frc/robot/util/RBSIEnum.java
+++ b/src/main/java/frc/robot/util/RBSIEnum.java
@@ -1,15 +1,9 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-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.
+// 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.
package frc.robot.util;
@@ -34,6 +28,7 @@ public static enum SwerveType {
/** Enumerate the supported autonomous path planning types */
public static enum AutoType {
+ MANUAL, // Manual commands only
PATHPLANNER, // PathPlanner (https://pathplanner.dev/home.html)
CHOREO // Choreo (https://sleipnirgroup.github.io/Choreo/)
}
diff --git a/src/main/java/frc/robot/util/RBSIIO.java b/src/main/java/frc/robot/util/RBSIIO.java
index 3c12d82..ed5ef71 100644
--- a/src/main/java/frc/robot/util/RBSIIO.java
+++ b/src/main/java/frc/robot/util/RBSIIO.java
@@ -1,15 +1,9 @@
-// Copyright (c) 2025 Az-FIRST
+// 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.
+// 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.
package frc.robot.util;
diff --git a/src/main/java/frc/robot/util/RBSIParsing.java b/src/main/java/frc/robot/util/RBSIParsing.java
index d61c501..68a7104 100644
--- a/src/main/java/frc/robot/util/RBSIParsing.java
+++ b/src/main/java/frc/robot/util/RBSIParsing.java
@@ -1,15 +1,9 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-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.
+// 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.
package frc.robot.util;
diff --git a/src/main/java/frc/robot/util/PowerMonitoring.java b/src/main/java/frc/robot/util/RBSIPowerMonitor.java
similarity index 93%
rename from src/main/java/frc/robot/util/PowerMonitoring.java
rename to src/main/java/frc/robot/util/RBSIPowerMonitor.java
index 52850d3..a4d2973 100644
--- a/src/main/java/frc/robot/util/PowerMonitoring.java
+++ b/src/main/java/frc/robot/util/RBSIPowerMonitor.java
@@ -1,4 +1,4 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
//
// This program is free software; you can redistribute it and/or
@@ -20,7 +20,6 @@
import frc.robot.util.Alert.AlertType;
import org.littletonrobotics.conduit.ConduitApi;
import org.littletonrobotics.junction.Logger;
-import org.littletonrobotics.junction.inputs.LoggedPowerDistribution;
/**
* Power monitoring virtual subsystem that periodically polls the Power Distribution Module. Each
@@ -28,13 +27,14 @@
* and subsystem total currents are also computed based on the power ports listed in
* ``RobotContainer.java``.
*/
-public class PowerMonitoring extends VirtualSubsystem {
+public class RBSIPowerMonitor extends VirtualSubsystem {
private final RBSISubsystem[] subsystems;
// Get the AdvantageKit conduit for pulling PDM information
- @SuppressWarnings("unused")
- private LoggedPowerDistribution loggedPowerDistribution = LoggedPowerDistribution.getInstance();
+ // @SuppressWarnings("unused")
+ // private LoggedPowerDistribution loggedPowerDistribution =
+ // LoggedPowerDistribution.getInstance();
private ConduitApi conduit = ConduitApi.getInstance();
@@ -67,7 +67,7 @@ public class PowerMonitoring extends VirtualSubsystem {
};
// Class method definition, including inputs of optional subsystems
- public PowerMonitoring(LoggedTunableNumber batteryCapacity, RBSISubsystem... subsystems) {
+ public RBSIPowerMonitor(LoggedTunableNumber batteryCapacity, RBSISubsystem... subsystems) {
this.batteryCapacity = batteryCapacity;
this.subsystems = subsystems;
}
diff --git a/src/main/java/frc/robot/util/RBSISubsystem.java b/src/main/java/frc/robot/util/RBSISubsystem.java
index 829300f..eebe1c3 100644
--- a/src/main/java/frc/robot/util/RBSISubsystem.java
+++ b/src/main/java/frc/robot/util/RBSISubsystem.java
@@ -1,15 +1,9 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-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.
+// 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.
package frc.robot.util;
diff --git a/src/main/java/frc/robot/util/RobotDeviceId.java b/src/main/java/frc/robot/util/RobotDeviceId.java
index 4f1c214..ca7db3f 100644
--- a/src/main/java/frc/robot/util/RobotDeviceId.java
+++ b/src/main/java/frc/robot/util/RobotDeviceId.java
@@ -1,20 +1,16 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
// Copyright (c) 2024 FRC 254
// https://github.com/team254
//
-// 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.
+// 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.
package frc.robot.util;
+import com.ctre.phoenix6.CANBus;
+
/**
* Class for wrapping Robot / CAN devices with a name and functionality. Included here are both the
* CAN ID for devices and the port on the Power Distribution Module for power monitoring and
@@ -46,6 +42,11 @@ public String getBus() {
return m_CANBus;
}
+ /** Get the CTRE CANBus object for a named device */
+ public CANBus getCANBus() {
+ return new CANBus(m_CANBus);
+ }
+
/** Get the Power Port for a named device */
public int getPowerPort() {
return m_PowerPort;
diff --git a/src/main/java/frc/robot/util/SparkUtil.java b/src/main/java/frc/robot/util/SparkUtil.java
index df627df..c4c8cdf 100644
--- a/src/main/java/frc/robot/util/SparkUtil.java
+++ b/src/main/java/frc/robot/util/SparkUtil.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
-// Copyright (c) 2021-2025 FRC 6328
+// Copyright (c) 2021-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
-// 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.
+// 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.
package frc.robot.util;
diff --git a/src/main/java/frc/robot/util/VirtualSubsystem.java b/src/main/java/frc/robot/util/VirtualSubsystem.java
index 59117db..de7f847 100644
--- a/src/main/java/frc/robot/util/VirtualSubsystem.java
+++ b/src/main/java/frc/robot/util/VirtualSubsystem.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
// Copyright (c) 2024 FRC 6328
// 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
-// 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.
+// 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.
package frc.robot.util;
diff --git a/src/main/java/frc/robot/util/YagslConstants.java b/src/main/java/frc/robot/util/YagslConstants.java
index 2b3302f..9a79f9f 100644
--- a/src/main/java/frc/robot/util/YagslConstants.java
+++ b/src/main/java/frc/robot/util/YagslConstants.java
@@ -1,15 +1,9 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-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.
+// 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.
//
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
diff --git a/src/test/CurrentLimitTests.java b/src/test/CurrentLimitTests.java
index 02459aa..079ec0e 100644
--- a/src/test/CurrentLimitTests.java
+++ b/src/test/CurrentLimitTests.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
// Copyright (c) 2024-2025 Cross The Road Electronics
// https://github.com/CrossTheRoadElec/Phoenix6-Examples
//
-// 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.
+// 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.
//
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
diff --git a/src/test/FusedCANcoderTests.java b/src/test/FusedCANcoderTests.java
index bda6925..c77f4c0 100644
--- a/src/test/FusedCANcoderTests.java
+++ b/src/test/FusedCANcoderTests.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
// Copyright (c) 2024-2025 Cross The Road Electronics
// https://github.com/CrossTheRoadElec/Phoenix6-Examples
//
-// 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.
+// 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.
//
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
diff --git a/src/test/LatencyCompensationTests.java b/src/test/LatencyCompensationTests.java
index 4fb6b65..24f748b 100644
--- a/src/test/LatencyCompensationTests.java
+++ b/src/test/LatencyCompensationTests.java
@@ -1,17 +1,11 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
// Copyright (c) -2025 Cross The Road Electronics
// https://github.com/CrossTheRoadElec/Phoenix6-Examples
//
-// 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.
+// 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.
//
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
diff --git a/src/test/RobotContainerTest.java b/src/test/RobotContainerTest.java
index ad125e0..23d042a 100644
--- a/src/test/RobotContainerTest.java
+++ b/src/test/RobotContainerTest.java
@@ -1,4 +1,4 @@
-// Copyright (c) 2024-2025 Az-FIRST
+// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
// Copyright (c) 2024 FRC 6328
// http://github.com/Mechanical-Advantage
diff --git a/vendordeps/AdvantageKit.json b/vendordeps/AdvantageKit.json
index 2707c2b..849af71 100644
--- a/vendordeps/AdvantageKit.json
+++ b/vendordeps/AdvantageKit.json
@@ -1,9 +1,9 @@
{
"fileName": "AdvantageKit.json",
"name": "AdvantageKit",
- "version": "4.1.2",
+ "version": "26.0.0-beta-1",
"uuid": "d820cc26-74e3-11ec-90d6-0242ac120003",
- "frcYear": "2025",
+ "frcYear": "2026beta",
"mavenUrls": [
"https://frcmaven.wpi.edu/artifactory/littletonrobotics-mvn-release/"
],
@@ -12,14 +12,14 @@
{
"groupId": "org.littletonrobotics.akit",
"artifactId": "akit-java",
- "version": "4.1.2"
+ "version": "26.0.0-beta-1"
}
],
"jniDependencies": [
{
"groupId": "org.littletonrobotics.akit",
"artifactId": "akit-wpilibio",
- "version": "4.1.2",
+ "version": "26.0.0-beta-1",
"skipInvalidPlatforms": false,
"isJar": false,
"validPlatforms": [
diff --git a/vendordeps/ChoreoLib2025.json b/vendordeps/ChoreoLib2025.json
index 2c2d3c3..5259ca8 100644
--- a/vendordeps/ChoreoLib2025.json
+++ b/vendordeps/ChoreoLib2025.json
@@ -3,7 +3,7 @@
"name": "ChoreoLib",
"version": "2025.0.3",
"uuid": "b5e23f0a-dac9-4ad2-8dd6-02767c520aca",
- "frcYear": "2025",
+ "frcYear": "2026beta",
"mavenUrls": [
"https://lib.choreo.autos/dep",
"https://repo1.maven.org/maven2"
diff --git a/vendordeps/PathplannerLib.json b/vendordeps/PathplannerLib.json
index 20b1b15..73ae375 100644
--- a/vendordeps/PathplannerLib.json
+++ b/vendordeps/PathplannerLib.json
@@ -3,7 +3,7 @@
"name": "PathplannerLib",
"version": "2025.2.7",
"uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786",
- "frcYear": "2025",
+ "frcYear": "2026beta",
"mavenUrls": [
"https://3015rangerrobotics.github.io/pathplannerlib/repo"
],
diff --git a/vendordeps/Phoenix5-frc2025-latest.json b/vendordeps/Phoenix5-5.36.0-beta-1.json
similarity index 84%
rename from vendordeps/Phoenix5-frc2025-latest.json
rename to vendordeps/Phoenix5-5.36.0-beta-1.json
index aa08d95..c40f569 100644
--- a/vendordeps/Phoenix5-frc2025-latest.json
+++ b/vendordeps/Phoenix5-5.36.0-beta-1.json
@@ -1,50 +1,50 @@
{
- "fileName": "Phoenix5-frc2025-latest.json",
+ "fileName": "Phoenix5-5.36.0-beta-1.json",
"name": "CTRE-Phoenix (v5)",
- "version": "5.35.1",
- "frcYear": "2025",
+ "version": "5.36.0-beta-1",
+ "frcYear": "2026beta",
"uuid": "ab676553-b602-441f-a38d-f1296eff6537",
"mavenUrls": [
"https://maven.ctr-electronics.com/release/"
],
- "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2025-latest.json",
+ "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2026-beta-latest.json",
"requires": [
{
"uuid": "e995de00-2c64-4df5-8831-c1441420ff19",
"errorMessage": "Phoenix 5 requires low-level libraries from Phoenix 6. Please add the Phoenix 6 vendordep before adding Phoenix 5.",
- "offlineFileName": "Phoenix6-frc2025-latest.json",
- "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-latest.json"
+ "offlineFileName": "Phoenix6-frc2026-beta-latest.json",
+ "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2026-beta-latest.json"
}
],
"conflictsWith": [
{
"uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af",
"errorMessage": "Users must use the Phoenix 5 replay vendordep when using the Phoenix 6 replay vendordep.",
- "offlineFileName": "Phoenix6-replay-frc2025-latest.json"
+ "offlineFileName": "Phoenix6-replay-frc2026-beta-latest.json"
},
{
"uuid": "fbc886a4-2cec-40c0-9835-71086a8cc3df",
"errorMessage": "Users cannot have both the replay and regular Phoenix 5 vendordeps in their robot program.",
- "offlineFileName": "Phoenix5-replay-frc2025-latest.json"
+ "offlineFileName": "Phoenix5-replay-frc2026-beta-latest.json"
}
],
"javaDependencies": [
{
"groupId": "com.ctre.phoenix",
"artifactId": "api-java",
- "version": "5.35.1"
+ "version": "5.36.0-beta-1"
},
{
"groupId": "com.ctre.phoenix",
"artifactId": "wpiapi-java",
- "version": "5.35.1"
+ "version": "5.36.0-beta-1"
}
],
"jniDependencies": [
{
"groupId": "com.ctre.phoenix",
"artifactId": "cci",
- "version": "5.35.1",
+ "version": "5.36.0-beta-1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -58,7 +58,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "cci-sim",
- "version": "5.35.1",
+ "version": "5.36.0-beta-1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -74,7 +74,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "wpiapi-cpp",
- "version": "5.35.1",
+ "version": "5.36.0-beta-1",
"libName": "CTRE_Phoenix_WPI",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -90,7 +90,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "api-cpp",
- "version": "5.35.1",
+ "version": "5.36.0-beta-1",
"libName": "CTRE_Phoenix",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -106,7 +106,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "cci",
- "version": "5.35.1",
+ "version": "5.36.0-beta-1",
"libName": "CTRE_PhoenixCCI",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -122,7 +122,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "wpiapi-cpp-sim",
- "version": "5.35.1",
+ "version": "5.36.0-beta-1",
"libName": "CTRE_Phoenix_WPISim",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -138,7 +138,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "api-cpp-sim",
- "version": "5.35.1",
+ "version": "5.36.0-beta-1",
"libName": "CTRE_PhoenixSim",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -154,7 +154,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "cci-sim",
- "version": "5.35.1",
+ "version": "5.36.0-beta-1",
"libName": "CTRE_PhoenixCCISim",
"headerClassifier": "headers",
"sharedLibrary": true,
diff --git a/vendordeps/Phoenix6-frc2025-latest.json b/vendordeps/Phoenix6-26.0.0-beta-1.json
similarity index 85%
rename from vendordeps/Phoenix6-frc2025-latest.json
rename to vendordeps/Phoenix6-26.0.0-beta-1.json
index ce44ce4..f4686ba 100644
--- a/vendordeps/Phoenix6-frc2025-latest.json
+++ b/vendordeps/Phoenix6-26.0.0-beta-1.json
@@ -1,32 +1,32 @@
{
- "fileName": "Phoenix6-frc2025-latest.json",
+ "fileName": "Phoenix6-26.0.0-beta-1.json",
"name": "CTRE-Phoenix (v6)",
- "version": "25.4.0",
- "frcYear": "2025",
+ "version": "26.0.0-beta-1",
+ "frcYear": "2026beta",
"uuid": "e995de00-2c64-4df5-8831-c1441420ff19",
"mavenUrls": [
"https://maven.ctr-electronics.com/release/"
],
- "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-latest.json",
+ "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2026-latest.json",
"conflictsWith": [
{
"uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af",
"errorMessage": "Users can not have both the replay and regular Phoenix 6 vendordeps in their robot program.",
- "offlineFileName": "Phoenix6-replay-frc2025-latest.json"
+ "offlineFileName": "Phoenix6-replay-frc2026-latest.json"
}
],
"javaDependencies": [
{
"groupId": "com.ctre.phoenix6",
"artifactId": "wpiapi-java",
- "version": "25.4.0"
+ "version": "26.0.0-beta-1"
}
],
"jniDependencies": [
{
"groupId": "com.ctre.phoenix6",
"artifactId": "api-cpp",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -40,7 +40,7 @@
{
"groupId": "com.ctre.phoenix6",
"artifactId": "tools",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -54,7 +54,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "api-cpp-sim",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -68,7 +68,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "tools-sim",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -82,7 +82,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simTalonSRX",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -96,7 +96,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simVictorSPX",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -110,21 +110,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simPigeonIMU",
- "version": "25.4.0",
- "isJar": false,
- "skipInvalidPlatforms": true,
- "validPlatforms": [
- "windowsx86-64",
- "linuxx86-64",
- "linuxarm64",
- "osxuniversal"
- ],
- "simMode": "swsim"
- },
- {
- "groupId": "com.ctre.phoenix6.sim",
- "artifactId": "simCANCoder",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -138,7 +124,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProTalonFX",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -152,7 +138,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProTalonFXS",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -166,7 +152,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANcoder",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -180,7 +166,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProPigeon2",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -194,7 +180,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANrange",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -208,7 +194,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANdi",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -222,7 +208,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANdle",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -238,7 +224,7 @@
{
"groupId": "com.ctre.phoenix6",
"artifactId": "wpiapi-cpp",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"libName": "CTRE_Phoenix6_WPI",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -254,7 +240,7 @@
{
"groupId": "com.ctre.phoenix6",
"artifactId": "tools",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"libName": "CTRE_PhoenixTools",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -270,7 +256,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "wpiapi-cpp-sim",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"libName": "CTRE_Phoenix6_WPISim",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -286,7 +272,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "tools-sim",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"libName": "CTRE_PhoenixTools_Sim",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -302,7 +288,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simTalonSRX",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"libName": "CTRE_SimTalonSRX",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -318,7 +304,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simVictorSPX",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"libName": "CTRE_SimVictorSPX",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -334,7 +320,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simPigeonIMU",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"libName": "CTRE_SimPigeonIMU",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -347,26 +333,10 @@
],
"simMode": "swsim"
},
- {
- "groupId": "com.ctre.phoenix6.sim",
- "artifactId": "simCANCoder",
- "version": "25.4.0",
- "libName": "CTRE_SimCANCoder",
- "headerClassifier": "headers",
- "sharedLibrary": true,
- "skipInvalidPlatforms": true,
- "binaryPlatforms": [
- "windowsx86-64",
- "linuxx86-64",
- "linuxarm64",
- "osxuniversal"
- ],
- "simMode": "swsim"
- },
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProTalonFX",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"libName": "CTRE_SimProTalonFX",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -382,7 +352,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProTalonFXS",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"libName": "CTRE_SimProTalonFXS",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -398,7 +368,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANcoder",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"libName": "CTRE_SimProCANcoder",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -414,7 +384,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProPigeon2",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"libName": "CTRE_SimProPigeon2",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -430,7 +400,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANrange",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"libName": "CTRE_SimProCANrange",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -446,7 +416,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANdi",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"libName": "CTRE_SimProCANdi",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -462,7 +432,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANdle",
- "version": "25.4.0",
+ "version": "26.0.0-beta-1",
"libName": "CTRE_SimProCANdle",
"headerClassifier": "headers",
"sharedLibrary": true,
diff --git a/vendordeps/REVLib.json b/vendordeps/REVLib.json
index 459a62f..a8f2648 100644
--- a/vendordeps/REVLib.json
+++ b/vendordeps/REVLib.json
@@ -1,25 +1,55 @@
{
"fileName": "REVLib.json",
"name": "REVLib",
- "version": "2025.0.3",
- "frcYear": "2025",
+ "version": "2026.0.0-beta-1",
+ "frcYear": "2026beta",
"uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb",
"mavenUrls": [
"https://maven.revrobotics.com/"
],
- "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2025.json",
+ "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2026.json",
"javaDependencies": [
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-java",
- "version": "2025.0.3"
+ "version": "2026.0.0-beta-1"
}
],
"jniDependencies": [
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-driver",
- "version": "2025.0.3",
+ "version": "2026.0.0-beta-1",
+ "skipInvalidPlatforms": true,
+ "isJar": false,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxarm64",
+ "linuxx86-64",
+ "linuxathena",
+ "linuxarm32",
+ "osxuniversal"
+ ]
+ },
+ {
+ "groupId": "com.revrobotics.frc",
+ "artifactId": "RevLibBackendDriver",
+ "version": "2026.0.0-beta-1",
+ "skipInvalidPlatforms": true,
+ "isJar": false,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxarm64",
+ "linuxx86-64",
+ "linuxathena",
+ "linuxarm32",
+ "osxuniversal"
+ ]
+ },
+ {
+ "groupId": "com.revrobotics.frc",
+ "artifactId": "RevLibWpiBackendDriver",
+ "version": "2026.0.0-beta-1",
"skipInvalidPlatforms": true,
"isJar": false,
"validPlatforms": [
@@ -36,7 +66,7 @@
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-cpp",
- "version": "2025.0.3",
+ "version": "2026.0.0-beta-1",
"libName": "REVLib",
"headerClassifier": "headers",
"sharedLibrary": false,
@@ -53,7 +83,7 @@
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-driver",
- "version": "2025.0.3",
+ "version": "2026.0.0-beta-1",
"libName": "REVLibDriver",
"headerClassifier": "headers",
"sharedLibrary": false,
@@ -66,6 +96,38 @@
"linuxarm32",
"osxuniversal"
]
+ },
+ {
+ "groupId": "com.revrobotics.frc",
+ "artifactId": "RevLibBackendDriver",
+ "version": "2026.0.0-beta-1",
+ "libName": "BackendDriver",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxarm64",
+ "linuxx86-64",
+ "linuxathena",
+ "linuxarm32",
+ "osxuniversal"
+ ]
+ },
+ {
+ "groupId": "com.revrobotics.frc",
+ "artifactId": "RevLibWpiBackendDriver",
+ "version": "2026.0.0-beta-1",
+ "libName": "REVLibWpi",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxarm64",
+ "linuxx86-64",
+ "linuxathena",
+ "linuxarm32",
+ "osxuniversal"
+ ]
}
]
}
diff --git a/vendordeps/ReduxLib-2025.0.1.json b/vendordeps/ReduxLib-2025.0.1.json
index 3a66d72..9aaec1c 100644
--- a/vendordeps/ReduxLib-2025.0.1.json
+++ b/vendordeps/ReduxLib-2025.0.1.json
@@ -2,7 +2,7 @@
"fileName": "ReduxLib-2025.0.1.json",
"name": "ReduxLib",
"version": "2025.0.1",
- "frcYear": "2025",
+ "frcYear": "2026beta",
"uuid": "151ecca8-670b-4026-8160-cdd2679ef2bd",
"mavenUrls": [
"https://maven.reduxrobotics.com/"
diff --git a/vendordeps/Studica-2025.0.1.json b/vendordeps/Studica-2026.0.0-beta.json
similarity index 68%
rename from vendordeps/Studica-2025.0.1.json
rename to vendordeps/Studica-2026.0.0-beta.json
index a3ed1fe..f664501 100644
--- a/vendordeps/Studica-2025.0.1.json
+++ b/vendordeps/Studica-2026.0.0-beta.json
@@ -1,71 +1,71 @@
{
- "fileName": "Studica-2025.0.1.json",
+ "fileName": "Studica-2026.0.0-beta.json",
"name": "Studica",
- "version": "2025.0.1",
+ "version": "2026.0.0-beta",
+ "frcYear": "2026beta",
"uuid": "cb311d09-36e9-4143-a032-55bb2b94443b",
- "frcYear": "2025",
"mavenUrls": [
- "https://dev.studica.com/maven/release/2025/"
+ "https://dev.studica.com/maven/release/2026/"
],
- "jsonUrl": "https://dev.studica.com/releases/2025/Studica-2025.0.1.json",
- "cppDependencies": [
+ "jsonUrl": "https://dev.studica.com/maven/release/2026/json/Studica-2026.0.0-beta.json",
+ "javaDependencies": [
{
- "artifactId": "Studica-cpp",
- "binaryPlatforms": [
- "linuxathena",
- "linuxarm32",
- "linuxarm64",
- "linuxx86-64",
- "osxuniversal",
- "windowsx86-64"
- ],
"groupId": "com.studica.frc",
- "headerClassifier": "headers",
- "libName": "Studica",
- "sharedLibrary": false,
- "skipInvalidPlatforms": true,
- "version": "2025.0.1"
- },
+ "artifactId": "Studica-java",
+ "version": "2026.0.0-beta"
+ }
+ ],
+ "jniDependencies": [
{
+ "groupId": "com.studica.frc",
"artifactId": "Studica-driver",
- "binaryPlatforms": [
- "linuxathena",
- "linuxarm32",
+ "version": "2026.0.0-beta",
+ "skipInvalidPlatforms": true,
+ "isJar": false,
+ "validPlatforms": [
+ "windowsx86-64",
"linuxarm64",
"linuxx86-64",
- "osxuniversal",
- "windowsx86-64"
- ],
+ "linuxathena",
+ "linuxarm32",
+ "osxuniversal"
+ ]
+ }
+ ],
+ "cppDependencies": [
+ {
"groupId": "com.studica.frc",
+ "artifactId": "Studica-cpp",
+ "version": "2026.0.0-beta",
+ "libName": "Studica",
"headerClassifier": "headers",
- "libName": "StudicaDriver",
"sharedLibrary": false,
"skipInvalidPlatforms": true,
- "version": "2025.0.1"
- }
- ],
- "javaDependencies": [
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxarm64",
+ "linuxx86-64",
+ "linuxathena",
+ "linuxarm32",
+ "osxuniversal"
+ ]
+ },
{
- "artifactId": "Studica-java",
"groupId": "com.studica.frc",
- "version": "2025.0.1"
- }
- ],
- "jniDependencies": [
- {
"artifactId": "Studica-driver",
- "groupId": "com.studica.frc",
- "isJar": false,
+ "version": "2026.0.0-beta",
+ "libName": "StudicaDriver",
+ "headerClassifier": "headers",
+ "sharedLibrary": false,
"skipInvalidPlatforms": true,
- "validPlatforms": [
- "linuxathena",
- "linuxarm32",
+ "binaryPlatforms": [
+ "windowsx86-64",
"linuxarm64",
"linuxx86-64",
- "osxuniversal",
- "windowsx86-64"
- ],
- "version": "2025.0.1"
+ "linuxathena",
+ "linuxarm32",
+ "osxuniversal"
+ ]
}
]
}
diff --git a/vendordeps/ThriftyLib.json b/vendordeps/ThriftyLib.json
index 5c3595e..b012e45 100644
--- a/vendordeps/ThriftyLib.json
+++ b/vendordeps/ThriftyLib.json
@@ -2,7 +2,7 @@
"fileName": "ThriftyLib.json",
"name": "ThriftyLib",
"version": "2025.1.1",
- "frcYear": "2025",
+ "frcYear": "2026beta",
"uuid": "60b2694b-9e6e-4026-81ee-6f167946f4b0",
"mavenUrls": [
"https://docs.home.thethriftybot.com"
diff --git a/vendordeps/URCL.json b/vendordeps/URCL.json
index 6beb912..8cb9ea0 100644
--- a/vendordeps/URCL.json
+++ b/vendordeps/URCL.json
@@ -2,7 +2,7 @@
"fileName": "URCL.json",
"name": "URCL",
"version": "2025.0.1",
- "frcYear": "2025",
+ "frcYear": "2026beta",
"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 3718e0a..7ebc954 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": "2025",
+ "frcYear": "2026beta",
"mavenUrls": [],
"jsonUrl": "",
"javaDependencies": [
@@ -25,6 +25,7 @@
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
+ "linuxsystemcore",
"linuxathena",
"linuxarm32",
"linuxarm64",
diff --git a/vendordeps/maple-sim.json b/vendordeps/maple-sim.json
index 65f4413..1975151 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": "2025",
+ "frcYear": "2026beta",
"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 2b5b6ad..5ea96a8 100644
--- a/vendordeps/photonlib.json
+++ b/vendordeps/photonlib.json
@@ -3,7 +3,7 @@
"name": "photonlib",
"version": "v2025.3.2",
"uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004",
- "frcYear": "2025",
+ "frcYear": "2026beta",
"mavenUrls": [
"https://maven.photonvision.org/repository/internal",
"https://maven.photonvision.org/repository/snapshots"
diff --git a/vendordeps/yagsl-2025.8.0.json b/vendordeps/yagsl-2025.8.0.json
index dc91af6..2cb0614 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": "2025",
+ "frcYear": "2026beta",
"uuid": "1ccce5a4-acd2-4d18-bca3-4b8047188400",
"mavenUrls": [
"https://broncbotz3481.github.io/YAGSL-Lib/yagsl/repos"