diff --git a/.github/dependabot.yml b/.github/dependabot.yml index ffd8ba16..436a2a8b 100644 --- a/.github/dependabot.yml +++ b/.github/dependabot.yml @@ -10,8 +10,10 @@ updates: - package-ecosystem: "github-actions" # Workflow files stored in the default location of `.github/workflows`. (You don't need to specify `/.github/workflows` for `directory`. You can use `directory: "/"`.) directory: "/" + labels: + - "github_actions" schedule: - interval: "weekly" + interval: "monthly" # Maintain dependencies for gradle - package-ecosystem: "gradle" @@ -20,4 +22,4 @@ updates: labels: - "gradle dependencies" schedule: - interval: "monthly" + interval: "weekly" diff --git a/.wpilib/wpilib_preferences.json b/.wpilib/wpilib_preferences.json index a1591102..51005bf5 100644 --- a/.wpilib/wpilib_preferences.json +++ b/.wpilib/wpilib_preferences.json @@ -1,6 +1,6 @@ { "enableCppIntellisense": false, "currentLanguage": "java", - "projectYear": "2025beta", + "projectYear": "2025", "teamNumber": 0 } diff --git a/AdvantageScope Swerve Calibration.json b/AdvantageScope Swerve Calibration.json index e3c2d54e..f412ed27 100644 --- a/AdvantageScope Swerve Calibration.json +++ b/AdvantageScope Swerve Calibration.json @@ -122,7 +122,7 @@ } } ], - "game": "2024 Field", + "game": "2025 Field", "origin": "blue" }, "controllerUUID": "psf0y633oclnjyocus23hcnq1d4tpyte", diff --git a/INSTALL.md b/INSTALL.md index ce8cb1c8..97a07847 100644 --- a/INSTALL.md +++ b/INSTALL.md @@ -24,13 +24,26 @@ recommended to **not** select the "Include all branches" checkbox. -------- -### Setting up your new project +### Software Requirements + +The Az-RBSI requires the [2025 WPILib Installer]( +https://github.com/wpilibsuite/allwpilib/releases) (VSCode and associated +tools), 2025 firmware installed on all hardware (motors, encoders, power +distribution, etc.), the [2025 NI FRC Game Tools]( +https://www.ni.com/en/support/downloads/drivers/download.frc-game-tools.html) +(Driver Station and associated tools), and the [2025 CTRE Phoenix Tuner X]( +https://v6.docs.ctr-electronics.com/en/stable/docs/tuner/index.html). Take a +moment to update all software and firmware before attempting to load your new +robot project. + +Please note that you need these _minimum_ versions of the following components: + +* WPILib `2025.1.1` +* RoboRIO image `FRC_roboRIO_2025_v2.0` -**The Az-RBSI requires the 2025 WPILib Installer (VSCode and associated tools), -2025 firmware installed on all hardware (motors, encoders, power distribution, -etc.), the 2025 NI FRC Game Tools (Driver Station and associated tools), and -the 2025 CTRE Phoenix Tuner X. Take a moment to update all software and -firmware before attempting to load your new robot project.** +-------- + +### Setting up your new project When your new robot code respository is created, it will have a single commit that contains the entire Az-RBSI template for the current release. (See the @@ -42,8 +55,8 @@ steps you need to complete: 1. Add your team number to the `.wpilib/wpilib_preferences.json` file. The generic Az-RBSI template contains a team number "0", and your code will not - deploy properly if this variable is not set (*e.g.*, VSCode looks for the - RoboRIO on IP address `10.TE.AM.2`, and it will not find anything if it + deploy properly if this variable is not set (*i.e.*, since VSCode looks for + the RoboRIO on IP address `10.TE.AM.2`, it will not find anything if it tries to contact `10.0.0.2`.) If you forget to change this value, you will get an error message when deploying code to your robot like: @@ -86,14 +99,24 @@ method are encouraged to submit bug reports and code fixes to the [Az-RBSI repository](https://github.com/AZ-First/Az-RBSI). 6. The Az-RBSI expects an Xbox-style controller -- if you have a PS4 or other, - change this at the top of the `RobotContainer.java` file in the - `src/main/java/frc/robot` directory. - -7. Power ports... + substitute the proper command-based controller class for + `CommandXboxController` near the top of the `RobotContainer.java` file in + the `src/main/java/frc/robot` directory. + +7. Power monitoring by subsystem is included in the Az-RBSI. In order to + properly match subsystems to ports on your Power Distribution Module, + carefully edit the `CANandPowerPorts` of `Constants.java` to include the + proper power ports for each motor in your drivetrain, and include any + motors from additional subsystems you add to your robot. To include + additional subsystems in the monitoring, add them to the [`m_power` + instantiation]( + https://github.com/AZ-First/Az-RBSI/blob/38f6391cb70c4caa90502710f591682815064677/src/main/java/frc/robot/RobotContainer.java#L154-L157) in the `RobotContainer.java` file. 8. All of the constants for needed for tuning your robot should be in the `Constants.java` file in the `src/main/java/frc/robot` directory. This file - should be thoroughly edited to match the particulars of your robot. + should be thoroughly edited to match the particulars of your robot. Be sure + to work through each section of this file and include the proper values for + your robot. -------- diff --git a/WPILib-License.md b/WPILib-License.md index 645e5425..d744196f 100644 --- a/WPILib-License.md +++ b/WPILib-License.md @@ -1,4 +1,4 @@ -Copyright (c) 2009-2024 FIRST and other WPILib contributors +Copyright (c) 2009-2025 FIRST and other WPILib contributors All rights reserved. Redistribution and use in source and binary forms, with or without diff --git a/build.gradle b/build.gradle index 9c88d910..8de0975c 100644 --- a/build.gradle +++ b/build.gradle @@ -1,6 +1,6 @@ plugins { id "java" - id "edu.wpi.first.GradleRIO" version "2025.1.1-beta-3" + id "edu.wpi.first.GradleRIO" version "2025.1.1" id "com.peterabeles.gversion" version "1.10.3" id "com.diffplug.spotless" version "6.25.0" id "io.freefair.lombok" version "8.11" diff --git a/settings.gradle b/settings.gradle index d94f73c6..969c7b09 100644 --- a/settings.gradle +++ b/settings.gradle @@ -4,7 +4,7 @@ pluginManagement { repositories { mavenLocal() gradlePluginPortal() - String frcYear = '2024' + String frcYear = '2025' File frcHome if (OperatingSystem.current().isWindows()) { String publicFolder = System.getenv('PUBLIC') diff --git a/src/main/deploy/pathplanner/navgrid.json b/src/main/deploy/pathplanner/navgrid.json index 690f5db2..bbd91940 100644 --- a/src/main/deploy/pathplanner/navgrid.json +++ b/src/main/deploy/pathplanner/navgrid.json @@ -1,7 +1,7 @@ { "field_size": { - "x": 16.54, - "y": 8.21 + "x": 17.548, + "y": 8.052 }, "nodeSizeMeters": 0.3, "grid": [ @@ -61,6 +61,9 @@ true, true, true, + true, + true, + true, true ], [ @@ -119,6 +122,9 @@ true, true, true, + true, + true, + true, true ], [ @@ -127,7 +133,6 @@ true, true, true, - true, false, false, false, @@ -171,8 +176,12 @@ false, false, false, - true, - true, + false, + false, + false, + false, + false, + false, true, true, true, @@ -184,7 +193,6 @@ true, true, true, - true, false, false, false, @@ -231,7 +239,11 @@ false, false, false, - true, + false, + false, + false, + false, + false, true, true, true, @@ -291,6 +303,9 @@ false, false, false, + false, + false, + false, true, true, true @@ -350,6 +365,9 @@ false, false, false, + false, + false, + false, true, true ], @@ -408,6 +426,9 @@ false, false, false, + false, + false, + false, true, true ], @@ -429,14 +450,6 @@ false, false, false, - true, - true, - true, - false, - false, - false, - false, - false, false, false, false, @@ -447,9 +460,6 @@ false, false, false, - true, - true, - true, false, false, false, @@ -466,12 +476,6 @@ false, false, false, - true, - true - ], - [ - true, - true, false, false, false, @@ -487,8 +491,9 @@ false, false, true, - true, - true, + true + ], + [ true, true, false, @@ -503,15 +508,8 @@ false, false, false, - false, - true, - true, true, true, - true, - false, - false, - false, false, false, false, @@ -524,12 +522,6 @@ false, false, false, - true, - true - ], - [ - true, - true, false, false, false, @@ -547,9 +539,6 @@ true, true, true, - true, - true, - false, false, false, false, @@ -563,15 +552,11 @@ false, false, true, + true + ], + [ true, true, - true, - true, - false, - false, - false, - false, - false, false, false, false, @@ -583,9 +568,9 @@ false, false, true, - true - ], - [ + true, + true, + true, true, true, false, @@ -602,15 +587,6 @@ false, false, false, - true, - true, - true, - true, - true, - false, - false, - false, - false, false, false, false, @@ -636,10 +612,6 @@ false, false, false, - false, - false, - false, - false, true, true ], @@ -654,13 +626,12 @@ false, false, false, + false, + true, + true, true, true, true, - false, - false, - false, - false, true, true, true, @@ -679,16 +650,20 @@ false, false, false, - true, - true, - true, false, false, false, false, + false, + false, + true, true, true, true, + true, + true, + true, + false, false, false, false, @@ -711,6 +686,12 @@ false, false, false, + false, + true, + true, + true, + true, + true, true, true, true, @@ -724,6 +705,9 @@ false, false, false, + true, + true, + true, false, false, false, @@ -732,6 +716,15 @@ false, false, false, + true, + true, + true, + true, + true, + true, + true, + true, + true, false, false, false, @@ -741,11 +734,10 @@ false, false, false, - false, - false, - true, - true, true, + true + ], + [ true, true, false, @@ -757,9 +749,13 @@ false, false, true, - true - ], - [ + true, + true, + true, + true, + true, + true, + true, true, true, false, @@ -781,6 +777,15 @@ false, false, false, + true, + true, + true, + true, + true, + true, + true, + true, + true, false, false, false, @@ -790,6 +795,12 @@ false, false, false, + true, + true + ], + [ + true, + true, false, false, false, @@ -798,9 +809,11 @@ false, false, false, - false, - false, - false, + true, + true, + true, + true, + true, true, true, true, @@ -815,9 +828,6 @@ false, true, true, - true - ], - [ true, true, true, @@ -827,6 +837,11 @@ false, false, false, + false, + true, + true, + true, + true, true, true, true, @@ -841,6 +856,12 @@ false, false, false, + true, + true + ], + [ + true, + true, false, false, false, @@ -849,9 +870,16 @@ false, false, false, - false, - false, - false, + true, + true, + true, + true, + true, + true, + true, + true, + true, + true, false, false, false, @@ -870,12 +898,12 @@ false, false, false, + false, + true, + true, true, true, true, - true - ], - [ true, true, true, @@ -886,14 +914,13 @@ false, false, false, - true, - true, - true, - false, false, false, false, true, + true + ], + [ true, true, false, @@ -904,6 +931,17 @@ false, false, false, + true, + true, + true, + true, + true, + true, + true, + true, + true, + true, + false, false, false, false, @@ -918,11 +956,6 @@ false, false, false, - true, - true, - true, - false, - false, false, false, false, @@ -931,9 +964,6 @@ true, true, true, - true - ], - [ true, true, true, @@ -948,13 +978,37 @@ false, false, false, + true, + true + ], + [ + true, + true, + false, + false, + false, + false, + false, false, false, + false, + false, + true, + true, true, true, true, true, true, + true, + false, + false, + false, + false, + false, + false, + false, + false, false, false, false, @@ -973,6 +1027,8 @@ true, true, true, + true, + true, false, false, false, @@ -983,18 +1039,10 @@ false, false, false, - false, - true, - true, - true, - true, true, true ], [ - true, - true, - true, true, true, false, @@ -1007,12 +1055,22 @@ false, false, false, - false, true, true, true, true, true, + true, + false, + false, + false, + false, + false, + false, + false, + false, + false, + false, false, false, false, @@ -1043,16 +1101,9 @@ false, false, true, - true, - true, - true, - true, true ], [ - true, - true, - true, true, true, false, @@ -1066,9 +1117,7 @@ false, false, false, - true, - true, - true, + false, true, true, false, @@ -1084,11 +1133,8 @@ false, false, false, - true, - true, - true, - true, - true, + false, + false, false, false, false, @@ -1103,14 +1149,22 @@ true, true, true, - true, + false, + false, + false, + false, + false, + false, + false, + false, + false, + false, + false, + false, true, true ], [ - true, - true, - true, true, true, false, @@ -1125,9 +1179,6 @@ false, false, false, - true, - true, - true, false, false, false, @@ -1143,9 +1194,6 @@ false, false, false, - true, - true, - true, false, false, false, @@ -1158,17 +1206,26 @@ false, false, false, - true, - true, - true, - true, + false, + false, + false, + false, + false, + false, + false, + false, + false, + false, + false, + false, + false, + false, + false, + false, true, true ], [ - true, - true, - true, true, true, false, @@ -1216,16 +1273,20 @@ false, false, false, - true, - true, - true, - true, + false, + false, + false, + false, + false, + false, + false, + false, + false, + false, true, true ], [ - true, - true, true, true, false, @@ -1275,9 +1336,14 @@ false, false, false, - true, - true, - true, + false, + false, + false, + false, + false, + false, + false, + false, true, true ], @@ -1334,12 +1400,17 @@ false, false, false, - true, + false, + false, + false, + false, true, true, true ], [ + true, + true, true, true, false, @@ -1395,9 +1466,13 @@ false, true, true, + true, true ], [ + true, + true, + true, true, true, false, @@ -1449,64 +1524,6 @@ false, false, false, - false, - false, - false, - true, - true - ], - [ - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, - true, true, true, true, @@ -1569,6 +1586,9 @@ true, true, true, + true, + true, + true, true ], [ @@ -1627,6 +1647,9 @@ true, true, true, + true, + true, + true, true ] ] diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 630a15d3..1ed48e94 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First // // This program is free software; you can redistribute it and/or @@ -34,7 +34,9 @@ import frc.robot.util.Alert; import frc.robot.util.Alert.AlertType; import frc.robot.util.RBSIEnum.AutoType; +import frc.robot.util.RBSIEnum.CTREPro; import frc.robot.util.RBSIEnum.Mode; +import frc.robot.util.RBSIEnum.MotorIdleMode; import frc.robot.util.RBSIEnum.RobotType; import frc.robot.util.RBSIEnum.SwerveType; import frc.robot.util.RBSIEnum.VisionType; @@ -67,7 +69,7 @@ public final class Constants { // under strict caveat emptor -- and submit any error and bugfixes // via GitHub issues. private static SwerveType swerveType = SwerveType.PHOENIX6; // PHOENIX6, YAGSL - private static boolean phoenixPro = false; // CTRE Pro License? true, false + private static CTREPro phoenixPro = CTREPro.LICENSED; // LICENSED, UNLICENSED private static AutoType autoType = AutoType.PATHPLANNER; // PATHPLANNER, CHOREO private static VisionType visionType = VisionType.NONE; // PHOTON, LIMELIGHT, NONE @@ -125,7 +127,7 @@ public static final class DrivebaseConstants { // of YOUR ROBOT, and replace the estimate here with your measured value! public static final double kMaxLinearSpeed = Units.feetToMeters(18); - // Set 3/4 of a rotation per second as the max angular velocity + // Set 3/4 of a rotation per second as the max angular velocity (radians/sec) public static final double kMaxAngularSpeed = 1.5 * Math.PI; // Maximum chassis accelerations desired for robot motion -- metric / radians @@ -135,7 +137,7 @@ public static final class DrivebaseConstants { // Drive and Turn PID constants public static final PIDConstants drivePID = new PIDConstants(0.05, 0.0, 0.0); - public static final PIDConstants steerPID = new PIDConstants(5.0, 0.0, 0.4); + public static final PIDConstants steerPID = new PIDConstants(2.0, 0.0, 0.4); // Hold time on motor brakes when disabled public static final double kWheelLockTime = 10; // seconds @@ -156,6 +158,9 @@ public static final class DrivebaseConstants { /** Example Flywheel Mechanism Constants ********************************* */ public static final class FlywheelConstants { + // Mechanism idle mode + public static final MotorIdleMode kFlywheelIdleMode = MotorIdleMode.COAST; // BRAKE, COAST + // Mechanism motor gear ratio public static final double kFlywheelGearRatio = 1.5; @@ -200,14 +205,16 @@ public static class AccelerometerConstants { public static class OperatorConstants { // Joystick Functions - // Set to TRUE for Drive = Left, Turn = Right; else FALSE + // Set to TRUE for Drive = Left Stick, Turn = Right Stick; else FALSE public static final boolean kDriveLeftTurnRight = true; // Joystick Deadbands - public static final double kLeftDeadband = 0.1; - public static final double kRightDeadband = 0.1; + public static final double kDeadband = 0.1; public static final double kTurnConstant = 6; + // Joystick slew rate limiters to smooth erratic joystick motions, measured in units per second + public static final double kJoystickSlewLimit = 0.5; + // Override and Console Toggle Switches // Assumes this controller: https://www.amazon.com/gp/product/B00UUROWWK // Example from: @@ -433,7 +440,7 @@ public static VisionType getVisionType() { } /** Get the current CTRE/Phoenix Pro License state */ - public static boolean getPhoenixPro() { + public static CTREPro getPhoenixPro() { return phoenixPro; } diff --git a/src/main/java/frc/robot/Main.java b/src/main/java/frc/robot/Main.java index 750b769a..3526e0ab 100644 --- a/src/main/java/frc/robot/Main.java +++ b/src/main/java/frc/robot/Main.java @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First // // This program is free software; you can redistribute it and/or diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index d5ba409e..f5bf2c26 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First // // This program is free software; you can redistribute it and/or @@ -143,6 +143,8 @@ public void disabledPeriodic() { /** This autonomous runs the autonomous command selected by your {@link RobotContainer} class. */ @Override public void autonomousInit() { + + // TODO: Make sure Gyro inits here with whatever is in the path planning thingie m_robotContainer.setMotorBrake(true); switch (Constants.getAutoType()) { case PATHPLANNER: diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 012fbd00..a2bedaaa 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright 2021-2024 FRC 6328 +// Copyright (c) 2021-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or @@ -23,11 +23,12 @@ import choreo.auto.AutoChooser; import choreo.auto.AutoFactory; -import choreo.auto.AutoFactory.AutoBindings; import choreo.auto.AutoRoutine; import choreo.auto.AutoTrajectory; import com.pathplanner.lib.auto.AutoBuilder; import com.pathplanner.lib.auto.NamedCommands; +import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj.GenericHID; import edu.wpi.first.wpilibj.XboxController; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; @@ -171,8 +172,7 @@ public RobotContainer() { // provided Pose2d m_drivebase::followTrajectory, // The drive subsystem trajectory follower true, // If alliance flipping should be enabled - m_drivebase, // The drive subsystem - new AutoBindings() // An empty AutoBindings object + m_drivebase // The drive subsystem ); autoChooserChoreo = new AutoChooser(); autoChooserChoreo.addRoutine("twoPieceAuto", this::twoPieceAuto); @@ -222,14 +222,15 @@ private void configureBindings() { } // SET STANDARD DRIVING AS DEFAULT COMMAND FOR THE DRIVEBASE + // TODO: With a re-do of Phoenix Tuner X on George, ensure the signs are all correct!!!!! m_drivebase.setDefaultCommand( DriveCommands.fieldRelativeDrive( m_drivebase, () -> -driveStickY.value(), () -> -driveStickX.value(), - () -> turnStickX.value())); + () -> -turnStickX.value())); - // Example Commands + // ** Example Commands -- Remap, remove, or change as desired ** // Press B button while driving --> ROBOT-CENTRIC driverController .b() @@ -252,7 +253,15 @@ private void configureBindings() { driverController.x().onTrue(Commands.runOnce(m_drivebase::stopWithX, m_drivebase)); // Press Y button --> Manually Re-Zero the Gyro - driverController.y().onTrue(Commands.runOnce(() -> m_drivebase.zero())); + driverController + .y() + .onTrue( + Commands.runOnce( + () -> + m_drivebase.setPose( + new Pose2d(m_drivebase.getPose().getTranslation(), new Rotation2d())), + m_drivebase) + .ignoringDisable(true)); // Press RIGHT BUMPER --> Run the example flywheel driverController @@ -365,7 +374,7 @@ private AutoRoutine twoPieceAuto() { AutoTrajectory scoreTraj = routine.trajectory("scoreGamepiece"); // When the routine begins, reset odometry and start the first trajectory - routine.active().onTrue(Commands.sequence(routine.resetOdometry(pickupTraj), pickupTraj.cmd())); + routine.active().onTrue(Commands.sequence(pickupTraj.resetOdometry(), pickupTraj.cmd())); // Starting at the event marker named "intake", run the intake // pickupTraj.atTime("intake").onTrue(intakeSubsystem.intake()); diff --git a/src/main/java/frc/robot/commands/ChoreoAutoController.java b/src/main/java/frc/robot/commands/ChoreoAutoController.java index 20fced4d..852cd6b6 100644 --- a/src/main/java/frc/robot/commands/ChoreoAutoController.java +++ b/src/main/java/frc/robot/commands/ChoreoAutoController.java @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First // Copyright 2024 SleipnirGroup // https://choreo.autos/ diff --git a/src/main/java/frc/robot/commands/DriveCommands.java b/src/main/java/frc/robot/commands/DriveCommands.java index 71829e25..ac130384 100644 --- a/src/main/java/frc/robot/commands/DriveCommands.java +++ b/src/main/java/frc/robot/commands/DriveCommands.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright 2021-2024 FRC 6328 +// Copyright (c) 2021-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or @@ -50,6 +50,12 @@ public class DriveCommands { private static final double WHEEL_RADIUS_MAX_VELOCITY = 0.25; // Rad/Sec private static final double WHEEL_RADIUS_RAMP_RATE = 0.05; // Rad/Sec^2 + // Create slew rate limiters for smoothing erratic joystick motions + private static final SlewRateLimiter linearVelocityFilter = + new SlewRateLimiter(OperatorConstants.kJoystickSlewLimit); + private static final SlewRateLimiter omegaFilter = + new SlewRateLimiter(OperatorConstants.kJoystickSlewLimit); + private DriveCommands() {} /** @@ -63,18 +69,22 @@ public static Command fieldRelativeDrive( return Commands.run( () -> { // Get the Linear Velocity & Omega from inputs - Translation2d linearVelocity = getLinearVelocity(xSupplier, ySupplier); - double omega = getOmega(omegaSupplier); + Translation2d linearVelocity = + getLinearVelocity(xSupplier.getAsDouble(), ySupplier.getAsDouble()); + double omega = getOmega(omegaSupplier.getAsDouble()); // Convert to field relative speeds & send command + ChassisSpeeds speeds = + new ChassisSpeeds( + linearVelocity.getX() * drive.getMaxLinearSpeedMetersPerSec(), + linearVelocity.getY() * drive.getMaxLinearSpeedMetersPerSec(), + omega * drive.getMaxAngularSpeedRadPerSec()); boolean isFlipped = DriverStation.getAlliance().isPresent() && DriverStation.getAlliance().get() == Alliance.Red; drive.runVelocity( ChassisSpeeds.fromFieldRelativeSpeeds( - linearVelocity.getX() * drive.getMaxLinearSpeedMetersPerSec(), - linearVelocity.getY() * drive.getMaxLinearSpeedMetersPerSec(), - omega * drive.getMaxAngularSpeedRadPerSec(), + speeds, isFlipped ? drive.getRotation().plus(new Rotation2d(Math.PI)) : drive.getRotation())); @@ -92,10 +102,10 @@ public static Command robotRelativeDrive( DoubleSupplier omegaSupplier) { return Commands.run( () -> { - // Get the Linear Velocity & Omega from inputs - Translation2d linearVelocity = getLinearVelocity(xSupplier, ySupplier); - double omega = getOmega(omegaSupplier); + Translation2d linearVelocity = + getLinearVelocity(xSupplier.getAsDouble(), ySupplier.getAsDouble()); + double omega = getOmega(omegaSupplier.getAsDouble()); // Run with straight-up velocities w.r.t. the robot! drive.runVelocity( @@ -107,59 +117,12 @@ public static Command robotRelativeDrive( drive); } - /** - * Compute the new linear velocity from inputs, including applying deadbands and squaring for - * smoothness - */ - private static Translation2d getLinearVelocity( - DoubleSupplier xSupplier, DoubleSupplier ySupplier) { - - // Apply deadband - double linearMagnitude = - MathUtil.applyDeadband( - Math.hypot(xSupplier.getAsDouble(), ySupplier.getAsDouble()), - OperatorConstants.kLeftDeadband); - Rotation2d linearDirection = new Rotation2d(xSupplier.getAsDouble(), ySupplier.getAsDouble()); - - // Square values - linearMagnitude = linearMagnitude * linearMagnitude; - - return new Pose2d(new Translation2d(), linearDirection) - .transformBy(new Transform2d(linearMagnitude, 0.0, new Rotation2d())) - .getTranslation(); - } - - /** - * Compute the new angular velocity from inputs, including applying deadbands and squaring for - * smoothness - */ - private static double getOmega(DoubleSupplier omegaSupplier) { - double omega = - MathUtil.applyDeadband(omegaSupplier.getAsDouble(), OperatorConstants.kRightDeadband); - return Math.copySign(omega * omega, omega); - } - - private static Translation2d getLinearVelocityFromJoysticks(double x, double y) { - // Apply deadband - double linearMagnitude = - MathUtil.applyDeadband(Math.hypot(x, y), OperatorConstants.kLeftDeadband); - Rotation2d linearDirection = new Rotation2d(Math.atan2(y, x)); - - // Square magnitude for more precise control - linearMagnitude = linearMagnitude * linearMagnitude; - - // Return new linear velocity - return new Pose2d(new Translation2d(), linearDirection) - .transformBy(new Transform2d(linearMagnitude, 0.0, new Rotation2d())) - .getTranslation(); - } - /** * Field relative drive command using joystick for linear control and PID for angular control. * Possible use cases include snapping to an angle, aiming at a vision target, or controlling * absolute rotation with a joystick. */ - public static Command joystickDriveAtAngle( + public static Command fieldRelativeDriveAtAngle( Drive drive, DoubleSupplier xSupplier, DoubleSupplier ySupplier, @@ -180,7 +143,7 @@ public static Command joystickDriveAtAngle( () -> { // Get linear velocity Translation2d linearVelocity = - getLinearVelocityFromJoysticks(xSupplier.getAsDouble(), ySupplier.getAsDouble()); + getLinearVelocity(xSupplier.getAsDouble(), ySupplier.getAsDouble()); // Calculate angular speed double omega = @@ -209,6 +172,36 @@ public static Command joystickDriveAtAngle( .beforeStarting(() -> angleController.reset(drive.getRotation().getRadians())); } + /** + * Compute the new linear velocity from inputs, including applying deadbands and squaring for + * smoothness. Also apply the linear velocity Slew Rate Limiter. + */ + private static Translation2d getLinearVelocity(double x, double y) { + // Apply deadband + double linearMagnitude = MathUtil.applyDeadband(Math.hypot(x, y), OperatorConstants.kDeadband); + Rotation2d linearDirection = new Rotation2d(Math.atan2(y, x)); + + // Square magnitude for more precise control + // NOTE: The x & y values range from -1 to +1, so their squares are as well + linearMagnitude = linearMagnitude * linearMagnitude; + + // Return new linear velocity + return new Pose2d(new Translation2d(), linearDirection) + .transformBy(new Transform2d(linearMagnitude, 0.0, new Rotation2d())) + .getTranslation(); + } + + /** + * Compute the new angular velocity from inputs, including applying deadbands and squaring for + * smoothness. Also apply the angular Slew Rate Limiter. + */ + private static double getOmega(double omega) { + omega = MathUtil.applyDeadband(omega, OperatorConstants.kDeadband); + return Math.copySign(omega * omega, omega); + } + + /***************************************************************************/ + /** DRIVEBASE CHARACTERIZATION COMMANDS ********************************** */ /** * Measures the velocity feedforward constants for the drive motors. * diff --git a/src/main/java/frc/robot/generated/TunerConstants.java b/src/main/java/frc/robot/generated/TunerConstants.java old mode 100644 new mode 100755 index d1f48432..4c4239af --- a/src/main/java/frc/robot/generated/TunerConstants.java +++ b/src/main/java/frc/robot/generated/TunerConstants.java @@ -3,17 +3,14 @@ import static edu.wpi.first.units.Units.*; import com.ctre.phoenix6.CANBus; -import com.ctre.phoenix6.configs.CANcoderConfiguration; -import com.ctre.phoenix6.configs.CurrentLimitsConfigs; -import com.ctre.phoenix6.configs.Pigeon2Configuration; -import com.ctre.phoenix6.configs.Slot0Configs; -import com.ctre.phoenix6.configs.TalonFXConfiguration; -import com.ctre.phoenix6.signals.StaticFeedforwardSignValue; -import com.ctre.phoenix6.swerve.SwerveDrivetrainConstants; -import com.ctre.phoenix6.swerve.SwerveModuleConstants; -import com.ctre.phoenix6.swerve.SwerveModuleConstants.ClosedLoopOutputType; -import com.ctre.phoenix6.swerve.SwerveModuleConstants.SteerFeedbackType; -import com.ctre.phoenix6.swerve.SwerveModuleConstantsFactory; +import com.ctre.phoenix6.configs.*; +import com.ctre.phoenix6.hardware.*; +import com.ctre.phoenix6.signals.*; +import com.ctre.phoenix6.swerve.*; +import com.ctre.phoenix6.swerve.SwerveModuleConstants.*; +import edu.wpi.first.math.Matrix; +import edu.wpi.first.math.numbers.N1; +import edu.wpi.first.math.numbers.N3; import edu.wpi.first.units.measure.*; // import frc.robot.subsystems.CommandSwerveDrivetrain; @@ -29,10 +26,10 @@ public class TunerConstants { new Slot0Configs() .withKP(100) .withKI(0) - .withKD(1.0) - .withKS(0.2) - .withKV(0.0) - .withKA(0.0) + .withKD(0.5) + .withKS(0.1) + .withKV(2.66) + .withKA(0) .withStaticFeedforwardSign(StaticFeedforwardSignValue.UseClosedLoopSign); // When using closed-loop control, the drive motor uses the control // output type specified by SwerveModuleConstants.DriveMotorClosedLoopOutput @@ -46,6 +43,13 @@ public class TunerConstants { // This affects the PID/FF gains for the drive motors private static final ClosedLoopOutputType kDriveClosedLoopOutput = ClosedLoopOutputType.Voltage; + // The type of motor used for the drive motor + private static final DriveMotorArrangement kDriveMotorType = + DriveMotorArrangement.TalonFX_Integrated; + // The type of motor used for the drive motor + private static final SteerMotorArrangement kSteerMotorType = + SteerMotorArrangement.TalonFX_Integrated; + // The remote sensor feedback type to use for the steer motors; // When not Pro-licensed, FusedCANcoder/SyncCANcoder automatically fall back to RemoteCANcoder private static final SteerFeedbackType kSteerFeedbackType = SteerFeedbackType.FusedCANcoder; @@ -54,7 +58,7 @@ public class TunerConstants { // This needs to be tuned to your individual robot private static final Current kSlipCurrent = Amps.of(120.0); - // Initial configs for the drive and steer motors and the CANcoder; these cannot be null. + // Initial configs for the drive and steer motors and the azimuth encoder; these cannot be null. // Some configs will be overwritten; check the `with*InitialConfigs()` API documentation. private static final TalonFXConfiguration driveInitialConfigs = new TalonFXConfiguration(); private static final TalonFXConfiguration steerInitialConfigs = @@ -66,7 +70,7 @@ public class TunerConstants { // stator current limit to help avoid brownouts without impacting performance. .withStatorCurrentLimit(Amps.of(60)) .withStatorCurrentLimitEnable(true)); - private static final CANcoderConfiguration cancoderInitialConfigs = new CANcoderConfiguration(); + private static final CANcoderConfiguration encoderInitialConfigs = new CANcoderConfiguration(); // Configs for the Pigeon 2; leave this null to skip applying Pigeon 2 configs private static final Pigeon2Configuration pigeonConfigs = null; @@ -80,10 +84,10 @@ public class TunerConstants { // Every 1 rotation of the azimuth results in kCoupleRatio drive motor turns; // This may need to be tuned to your individual robot - private static final double kCoupleRatio = 0; + private static final double kCoupleRatio = 3.5714285714285716; private static final double kDriveGearRatio = 6.746031746031747; - private static final double kSteerGearRatio = 15.42857142857143; + private static final double kSteerGearRatio = 21.428571428571427; private static final Distance kWheelRadius = Inches.of(2); private static final boolean kInvertLeftSide = false; @@ -92,11 +96,11 @@ public class TunerConstants { private static final int kPigeonId = 13; // These are only used for simulation - private static final double kSteerInertia = 0.004; - private static final double kDriveInertia = 0.025; + private static final MomentOfInertia kSteerInertia = KilogramSquareMeters.of(0.004); + private static final MomentOfInertia kDriveInertia = KilogramSquareMeters.of(0.025); // Simulated voltage necessary to overcome friction - private static final Voltage kSteerFrictionVoltage = Volts.of(0.25); - private static final Voltage kDriveFrictionVoltage = Volts.of(0.25); + private static final Voltage kSteerFrictionVoltage = Volts.of(0.2); + private static final Voltage kDriveFrictionVoltage = Volts.of(0.2); public static final SwerveDrivetrainConstants DrivetrainConstants = new SwerveDrivetrainConstants() @@ -104,34 +108,39 @@ public class TunerConstants { .withPigeon2Id(kPigeonId) .withPigeon2Configs(pigeonConfigs); - private static final SwerveModuleConstantsFactory ConstantCreator = - new SwerveModuleConstantsFactory() - .withDriveMotorGearRatio(kDriveGearRatio) - .withSteerMotorGearRatio(kSteerGearRatio) - .withCouplingGearRatio(kCoupleRatio) - .withWheelRadius(kWheelRadius) - .withSteerMotorGains(steerGains) - .withDriveMotorGains(driveGains) - .withSteerMotorClosedLoopOutput(kSteerClosedLoopOutput) - .withDriveMotorClosedLoopOutput(kDriveClosedLoopOutput) - .withSlipCurrent(kSlipCurrent) - .withSpeedAt12Volts(kSpeedAt12Volts) - .withFeedbackSource(kSteerFeedbackType) - .withDriveMotorInitialConfigs(driveInitialConfigs) - .withSteerMotorInitialConfigs(steerInitialConfigs) - .withCANcoderInitialConfigs(cancoderInitialConfigs) - .withSteerInertia(kSteerInertia) - .withDriveInertia(kDriveInertia) - .withSteerFrictionVoltage(kSteerFrictionVoltage) - .withDriveFrictionVoltage(kDriveFrictionVoltage); + private static final SwerveModuleConstantsFactory< + TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> + ConstantCreator = + new SwerveModuleConstantsFactory< + TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration>() + .withDriveMotorGearRatio(kDriveGearRatio) + .withSteerMotorGearRatio(kSteerGearRatio) + .withCouplingGearRatio(kCoupleRatio) + .withWheelRadius(kWheelRadius) + .withSteerMotorGains(steerGains) + .withDriveMotorGains(driveGains) + .withSteerMotorClosedLoopOutput(kSteerClosedLoopOutput) + .withDriveMotorClosedLoopOutput(kDriveClosedLoopOutput) + .withSlipCurrent(kSlipCurrent) + .withSpeedAt12Volts(kSpeedAt12Volts) + .withDriveMotorType(kDriveMotorType) + .withSteerMotorType(kSteerMotorType) + .withFeedbackSource(kSteerFeedbackType) + .withDriveMotorInitialConfigs(driveInitialConfigs) + .withSteerMotorInitialConfigs(steerInitialConfigs) + .withEncoderInitialConfigs(encoderInitialConfigs) + .withSteerInertia(kSteerInertia) + .withDriveInertia(kDriveInertia) + .withSteerFrictionVoltage(kSteerFrictionVoltage) + .withDriveFrictionVoltage(kDriveFrictionVoltage); // Front Left private static final int kFrontLeftDriveMotorId = 1; private static final int kFrontLeftSteerMotorId = 2; private static final int kFrontLeftEncoderId = 3; - private static final Angle kFrontLeftEncoderOffset = Rotations.of(-0.472900390625); + private static final Angle kFrontLeftEncoderOffset = Rotations.of(0.087158203125); private static final boolean kFrontLeftSteerMotorInverted = true; - private static final boolean kFrontLeftCANcoderInverted = false; + private static final boolean kFrontLeftEncoderInverted = false; private static final Distance kFrontLeftXPos = Inches.of(10.375); private static final Distance kFrontLeftYPos = Inches.of(10.375); @@ -140,9 +149,9 @@ public class TunerConstants { private static final int kFrontRightDriveMotorId = 4; private static final int kFrontRightSteerMotorId = 5; private static final int kFrontRightEncoderId = 6; - private static final Angle kFrontRightEncoderOffset = Rotations.of(-0.11474609375); + private static final Angle kFrontRightEncoderOffset = Rotations.of(0.410888671875); private static final boolean kFrontRightSteerMotorInverted = true; - private static final boolean kFrontRightCANcoderInverted = false; + private static final boolean kFrontRightEncoderInverted = false; private static final Distance kFrontRightXPos = Inches.of(10.375); private static final Distance kFrontRightYPos = Inches.of(-10.375); @@ -151,9 +160,9 @@ public class TunerConstants { private static final int kBackLeftDriveMotorId = 7; private static final int kBackLeftSteerMotorId = 8; private static final int kBackLeftEncoderId = 9; - private static final Angle kBackLeftEncoderOffset = Rotations.of(0.4091796875); + private static final Angle kBackLeftEncoderOffset = Rotations.of(-0.1142578125); private static final boolean kBackLeftSteerMotorInverted = true; - private static final boolean kBackLeftCANcoderInverted = false; + private static final boolean kBackLeftEncoderInverted = false; private static final Distance kBackLeftXPos = Inches.of(-10.375); private static final Distance kBackLeftYPos = Inches.of(10.375); @@ -162,65 +171,146 @@ public class TunerConstants { private static final int kBackRightDriveMotorId = 10; private static final int kBackRightSteerMotorId = 11; private static final int kBackRightEncoderId = 12; - private static final Angle kBackRightEncoderOffset = Rotations.of(0.086181640625); + private static final Angle kBackRightEncoderOffset = Rotations.of(-0.471923828125); private static final boolean kBackRightSteerMotorInverted = true; - private static final boolean kBackRightCANcoderInverted = false; + private static final boolean kBackRightEncoderInverted = false; private static final Distance kBackRightXPos = Inches.of(-10.375); private static final Distance kBackRightYPos = Inches.of(-10.375); - public static final SwerveModuleConstants FrontLeft = - ConstantCreator.createModuleConstants( - kFrontLeftSteerMotorId, - kFrontLeftDriveMotorId, - kFrontLeftEncoderId, - kFrontLeftEncoderOffset, - kFrontLeftXPos, - kFrontLeftYPos, - kInvertLeftSide, - kFrontLeftSteerMotorInverted, - kFrontLeftCANcoderInverted); - public static final SwerveModuleConstants FrontRight = - ConstantCreator.createModuleConstants( - kFrontRightSteerMotorId, - kFrontRightDriveMotorId, - kFrontRightEncoderId, - kFrontRightEncoderOffset, - kFrontRightXPos, - kFrontRightYPos, - kInvertRightSide, - kFrontRightSteerMotorInverted, - kFrontRightCANcoderInverted); - public static final SwerveModuleConstants BackLeft = - ConstantCreator.createModuleConstants( - kBackLeftSteerMotorId, - kBackLeftDriveMotorId, - kBackLeftEncoderId, - kBackLeftEncoderOffset, - kBackLeftXPos, - kBackLeftYPos, - kInvertLeftSide, - kBackLeftSteerMotorInverted, - kBackLeftCANcoderInverted); - public static final SwerveModuleConstants BackRight = - ConstantCreator.createModuleConstants( - kBackRightSteerMotorId, - kBackRightDriveMotorId, - kBackRightEncoderId, - kBackRightEncoderOffset, - kBackRightXPos, - kBackRightYPos, - kInvertRightSide, - kBackRightSteerMotorInverted, - kBackRightCANcoderInverted); - - // /** - // * Creates a CommandSwerveDrivetrain instance. - // * This should only be called once in your robot program,. - // */ - // public static CommandSwerveDrivetrain createDrivetrain() { - // return new CommandSwerveDrivetrain( - // DrivetrainConstants, FrontLeft, FrontRight, BackLeft, BackRight - // ); - // } + public static final SwerveModuleConstants< + TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> + FrontLeft = + ConstantCreator.createModuleConstants( + kFrontLeftSteerMotorId, + kFrontLeftDriveMotorId, + kFrontLeftEncoderId, + kFrontLeftEncoderOffset, + kFrontLeftXPos, + kFrontLeftYPos, + kInvertLeftSide, + kFrontLeftSteerMotorInverted, + kFrontLeftEncoderInverted); + public static final SwerveModuleConstants< + TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> + FrontRight = + ConstantCreator.createModuleConstants( + kFrontRightSteerMotorId, + kFrontRightDriveMotorId, + kFrontRightEncoderId, + kFrontRightEncoderOffset, + kFrontRightXPos, + kFrontRightYPos, + kInvertRightSide, + kFrontRightSteerMotorInverted, + kFrontRightEncoderInverted); + public static final SwerveModuleConstants< + TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> + BackLeft = + ConstantCreator.createModuleConstants( + kBackLeftSteerMotorId, + kBackLeftDriveMotorId, + kBackLeftEncoderId, + kBackLeftEncoderOffset, + kBackLeftXPos, + kBackLeftYPos, + kInvertLeftSide, + kBackLeftSteerMotorInverted, + kBackLeftEncoderInverted); + public static final SwerveModuleConstants< + TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> + BackRight = + ConstantCreator.createModuleConstants( + kBackRightSteerMotorId, + kBackRightDriveMotorId, + kBackRightEncoderId, + kBackRightEncoderOffset, + kBackRightXPos, + kBackRightYPos, + kInvertRightSide, + kBackRightSteerMotorInverted, + kBackRightEncoderInverted); + + // /** + // * Creates a CommandSwerveDrivetrain instance. + // * This should only be called once in your robot program,. + // */ + // public static CommandSwerveDrivetrain createDrivetrain() { + // return new CommandSwerveDrivetrain( + // DrivetrainConstants, FrontLeft, FrontRight, BackLeft, BackRight + // ); + // } + + /** Swerve Drive class utilizing CTR Electronics' Phoenix 6 API with the selected device types. */ + public static class TunerSwerveDrivetrain extends SwerveDrivetrain { + /** + * Constructs a CTRE SwerveDrivetrain using the specified constants. + * + *

This constructs the underlying hardware devices, so users should not construct the devices + * themselves. If they need the devices, they can access them through getters in the classes. + * + * @param drivetrainConstants Drivetrain-wide constants for the swerve drive + * @param modules Constants for each specific module + */ + public TunerSwerveDrivetrain( + SwerveDrivetrainConstants drivetrainConstants, SwerveModuleConstants... modules) { + super(TalonFX::new, TalonFX::new, CANcoder::new, drivetrainConstants, modules); + } + + /** + * Constructs a CTRE SwerveDrivetrain using the specified constants. + * + *

This constructs the underlying hardware devices, so users should not construct the devices + * themselves. If they need the devices, they can access them through getters in the classes. + * + * @param drivetrainConstants Drivetrain-wide constants for the swerve drive + * @param odometryUpdateFrequency The frequency to run the odometry loop. If unspecified or set + * to 0 Hz, this is 250 Hz on CAN FD, and 100 Hz on CAN 2.0. + * @param modules Constants for each specific module + */ + public TunerSwerveDrivetrain( + SwerveDrivetrainConstants drivetrainConstants, + double odometryUpdateFrequency, + SwerveModuleConstants... modules) { + super( + TalonFX::new, + TalonFX::new, + CANcoder::new, + drivetrainConstants, + odometryUpdateFrequency, + modules); + } + + /** + * Constructs a CTRE SwerveDrivetrain using the specified constants. + * + *

This constructs the underlying hardware devices, so users should not construct the devices + * themselves. If they need the devices, they can access them through getters in the classes. + * + * @param drivetrainConstants Drivetrain-wide constants for the swerve drive + * @param odometryUpdateFrequency The frequency to run the odometry loop. If unspecified or set + * to 0 Hz, this is 250 Hz on CAN FD, and 100 Hz on CAN 2.0. + * @param odometryStandardDeviation The standard deviation for odometry calculation in the form + * [x, y, theta]ᵀ, with units in meters and radians + * @param visionStandardDeviation The standard deviation for vision calculation in the form [x, + * y, theta]ᵀ, with units in meters and radians + * @param modules Constants for each specific module + */ + public TunerSwerveDrivetrain( + SwerveDrivetrainConstants drivetrainConstants, + double odometryUpdateFrequency, + Matrix odometryStandardDeviation, + Matrix visionStandardDeviation, + SwerveModuleConstants... modules) { + super( + TalonFX::new, + TalonFX::new, + CANcoder::new, + drivetrainConstants, + odometryUpdateFrequency, + odometryStandardDeviation, + visionStandardDeviation, + modules); + } + } } diff --git a/src/main/java/frc/robot/subsystems/accelerometer/Accelerometer.java b/src/main/java/frc/robot/subsystems/accelerometer/Accelerometer.java index 91519de3..b63d4ba8 100644 --- a/src/main/java/frc/robot/subsystems/accelerometer/Accelerometer.java +++ b/src/main/java/frc/robot/subsystems/accelerometer/Accelerometer.java @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First // // This program is free software; you can redistribute it and/or @@ -16,7 +16,7 @@ import static frc.robot.Constants.AccelerometerConstants.*; import com.ctre.phoenix6.hardware.Pigeon2; -import com.kauailabs.navx.frc.AHRS; +import com.studica.frc.AHRS; import edu.wpi.first.math.geometry.Rotation3d; import edu.wpi.first.math.geometry.Translation3d; import edu.wpi.first.wpilibj.BuiltInAccelerometer; diff --git a/src/main/java/frc/robot/subsystems/drive/Drive.java b/src/main/java/frc/robot/subsystems/drive/Drive.java index 3affb922..7d468d9a 100644 --- a/src/main/java/frc/robot/subsystems/drive/Drive.java +++ b/src/main/java/frc/robot/subsystems/drive/Drive.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright 2021-2024 FRC 6328 +// Copyright (c) 2021-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or @@ -129,8 +129,12 @@ public Drive() { for (int i = 0; i < 4; i++) { switch (modType) { case 0b00000000: // ALL-CTRE - throw new RuntimeException( - "For an all-CTRE drive base, use Phoenix Tuner X Swerve Generator instead of YAGSL!"); + if (kImuType == "navx" || kImuType == "navx_spi") { + modules[i] = new Module(new ModuleIOTalonFX(i), i); + } else { + throw new RuntimeException( + "For an all-CTRE drive base, use Phoenix Tuner X Swerve Generator instead of YAGSL!"); + } case 0b00010000: // Blended Talon Drive / NEO Steer modules[i] = new Module(new ModuleIOBlended(i), i); break; @@ -277,7 +281,7 @@ public void setMotorBrake(boolean brake) { */ public void runVelocity(ChassisSpeeds speeds) { // Calculate module setpoints - ChassisSpeeds discreteSpeeds = ChassisSpeeds.discretize(speeds, 0.02); + ChassisSpeeds discreteSpeeds = ChassisSpeeds.discretize(speeds, Constants.loopPeriodSecs); SwerveModuleState[] setpointStates = kinematics.toSwerveModuleStates(discreteSpeeds); SwerveDriveKinematics.desaturateWheelSpeeds(setpointStates, DrivebaseConstants.kMaxLinearSpeed); diff --git a/src/main/java/frc/robot/subsystems/drive/GyroIO.java b/src/main/java/frc/robot/subsystems/drive/GyroIO.java index 89467c24..c8c4d16f 100644 --- a/src/main/java/frc/robot/subsystems/drive/GyroIO.java +++ b/src/main/java/frc/robot/subsystems/drive/GyroIO.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright 2021-2024 FRC 6328 +// Copyright (c) 2021-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or diff --git a/src/main/java/frc/robot/subsystems/drive/GyroIONavX.java b/src/main/java/frc/robot/subsystems/drive/GyroIONavX.java index 4d31f036..6de5b723 100644 --- a/src/main/java/frc/robot/subsystems/drive/GyroIONavX.java +++ b/src/main/java/frc/robot/subsystems/drive/GyroIONavX.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright 2021-2024 FRC 6328 +// Copyright (c) 2021-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or @@ -15,17 +15,18 @@ package frc.robot.subsystems.drive; -import com.kauailabs.navx.frc.AHRS; +import com.studica.frc.AHRS; +import com.studica.frc.AHRS.NavXComType; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.util.Units; import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.DriverStation.Alliance; -import edu.wpi.first.wpilibj.SPI; import java.util.Queue; /** IO implementation for Pigeon2 */ public class GyroIONavX implements GyroIO { - private final AHRS navx = new AHRS(SPI.Port.kMXP, (byte) SwerveConstants.kOdometryFrequency); + private final AHRS navx = + new AHRS(NavXComType.kMXP_SPI, (byte) SwerveConstants.kOdometryFrequency); private final Queue yawPositionQueue; private final Queue yawTimestampQueue; diff --git a/src/main/java/frc/robot/subsystems/drive/GyroIOPigeon2.java b/src/main/java/frc/robot/subsystems/drive/GyroIOPigeon2.java index 56130ab5..a4ae3d30 100644 --- a/src/main/java/frc/robot/subsystems/drive/GyroIOPigeon2.java +++ b/src/main/java/frc/robot/subsystems/drive/GyroIOPigeon2.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright 2021-2024 FRC 6328 +// Copyright (c) 2021-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or diff --git a/src/main/java/frc/robot/subsystems/drive/Module.java b/src/main/java/frc/robot/subsystems/drive/Module.java index 0b2ccdb1..c51680ef 100644 --- a/src/main/java/frc/robot/subsystems/drive/Module.java +++ b/src/main/java/frc/robot/subsystems/drive/Module.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright 2021-2024 FRC 6328 +// Copyright (c) 2021-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIO.java b/src/main/java/frc/robot/subsystems/drive/ModuleIO.java index 23b2f26b..bcd3bb3c 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIO.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIO.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright 2021-2024 FRC 6328 +// Copyright (c) 2021-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOBlended.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOBlended.java index 2a375a98..d7f6e9da 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOBlended.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOBlended.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright 2024 FRC 2486 +// Copyright 2024-2025 FRC 2486 // https://github.com/Coconuts2486-FRC // // This program is free software; you can redistribute it and/or @@ -20,6 +20,7 @@ import com.ctre.phoenix6.BaseStatusSignal; import com.ctre.phoenix6.StatusSignal; import com.ctre.phoenix6.configs.CANcoderConfiguration; +import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.ctre.phoenix6.controls.TorqueCurrentFOC; import com.ctre.phoenix6.controls.VelocityTorqueCurrentFOC; import com.ctre.phoenix6.controls.VelocityVoltage; @@ -31,6 +32,7 @@ import com.ctre.phoenix6.signals.NeutralModeValue; import com.ctre.phoenix6.signals.SensorDirectionValue; import com.ctre.phoenix6.swerve.SwerveModuleConstants; +import com.ctre.phoenix6.swerve.SwerveModuleConstants.ClosedLoopOutputType; import com.ctre.phoenix6.swerve.SwerveModuleConstantsFactory; import com.revrobotics.spark.SparkBase; import com.revrobotics.spark.SparkBase.ControlType; @@ -50,6 +52,7 @@ import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.units.measure.Current; import edu.wpi.first.units.measure.Voltage; +import frc.robot.Constants; import frc.robot.Constants.DrivebaseConstants; import frc.robot.util.PhoenixUtil; import frc.robot.util.SparkUtil; @@ -65,7 +68,9 @@ * "/Drive/ModuleX/TurnAbsolutePositionRad" */ public class ModuleIOBlended implements ModuleIO { - private final SwerveModuleConstants constants; + private final SwerveModuleConstants< + TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> + constants; // CAN Devices private final TalonFX driveTalon; @@ -163,7 +168,7 @@ public ModuleIOBlended(int module) { driveTalon = new TalonFX(constants.DriveMotorId, SwerveConstants.kCANbusName); turnSpark = new SparkMax(constants.SteerMotorId, MotorType.kBrushless); - cancoder = new CANcoder(constants.CANcoderId, SwerveConstants.kCANbusName); + cancoder = new CANcoder(constants.EncoderId, SwerveConstants.kCANbusName); turnController = turnSpark.getClosedLoopController(); @@ -171,17 +176,15 @@ public ModuleIOBlended(int module) { var driveConfig = constants.DriveMotorInitialConfigs; driveConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; driveConfig.Slot0 = constants.DriveMotorGains; - driveConfig.Feedback.SensorToMechanismRatio = constants.DriveMotorGearRatio; - driveConfig.TorqueCurrent.PeakForwardTorqueCurrent = constants.SlipCurrent; - driveConfig.TorqueCurrent.PeakReverseTorqueCurrent = -constants.SlipCurrent; - driveConfig.CurrentLimits.StatorCurrentLimit = constants.SlipCurrent; + driveConfig.Feedback.SensorToMechanismRatio = SwerveConstants.kDriveGearRatio; + driveConfig.TorqueCurrent.PeakForwardTorqueCurrent = SwerveConstants.kDriveSlipCurrent; + driveConfig.TorqueCurrent.PeakReverseTorqueCurrent = -SwerveConstants.kDriveSlipCurrent; + driveConfig.CurrentLimits.StatorCurrentLimit = SwerveConstants.kDriveCurrentLimit; driveConfig.CurrentLimits.StatorCurrentLimitEnable = true; driveConfig.MotorOutput.Inverted = constants.DriveMotorInverted ? InvertedValue.Clockwise_Positive : InvertedValue.CounterClockwise_Positive; - PhoenixUtil.tryUntilOk(5, () -> driveTalon.getConfigurator().apply(driveConfig, 0.25)); - PhoenixUtil.tryUntilOk(5, () -> driveTalon.setPosition(0.0, 0.25)); // Configure turn motor var turnConfig = new SparkMaxConfig(); @@ -192,7 +195,7 @@ public ModuleIOBlended(int module) { .voltageCompensation(12.0); turnConfig .absoluteEncoder - .inverted(constants.CANcoderInverted) + .inverted(constants.EncoderInverted) .positionConversionFactor(turnEncoderPositionFactor) .velocityConversionFactor(turnEncoderVelocityFactor) .averageDepth(2); @@ -223,12 +226,23 @@ public ModuleIOBlended(int module) { turnConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters)); // Configure CANCoder - CANcoderConfiguration cancoderConfig = constants.CANcoderInitialConfigs; - cancoderConfig.MagnetSensor.MagnetOffset = constants.CANcoderOffset; + CANcoderConfiguration cancoderConfig = constants.EncoderInitialConfigs; + cancoderConfig.MagnetSensor.MagnetOffset = constants.EncoderOffset; cancoderConfig.MagnetSensor.SensorDirection = - constants.CANcoderInverted + constants.EncoderInverted ? SensorDirectionValue.Clockwise_Positive : SensorDirectionValue.CounterClockwise_Positive; + + // Set motor Closed Loop Output type based on Phoenix Pro status + constants.DriveMotorClosedLoopOutput = + switch (Constants.getPhoenixPro()) { + case LICENSED -> ClosedLoopOutputType.TorqueCurrentFOC; + case UNLICENSED -> ClosedLoopOutputType.Voltage; + }; + + // Finally, apply the configs to the motor controllers + PhoenixUtil.tryUntilOk(5, () -> driveTalon.getConfigurator().apply(driveConfig, 0.25)); + PhoenixUtil.tryUntilOk(5, () -> driveTalon.setPosition(0.0, 0.25)); cancoder.getConfigurator().apply(cancoderConfig); // Create timestamp queue @@ -322,20 +336,23 @@ public void setDriveVelocity(double velocityRadPerSec) { public void setTurnPosition(Rotation2d rotation) { double setpoint = MathUtil.inputModulus( - rotation.plus(Rotation2d.fromRotations(constants.CANcoderOffset)).getRadians(), + rotation.plus(Rotation2d.fromRotations(constants.EncoderOffset)).getRadians(), turnPIDMinInput, turnPIDMaxInput); turnController.setReference(setpoint, ControlType.kPosition); } - private SwerveModuleConstantsFactory ConstantCreator = - new SwerveModuleConstantsFactory() - .withDriveMotorGearRatio(kDriveGearRatio) - .withSteerMotorGearRatio(kSteerGearRatio) - .withCouplingGearRatio(kCoupleRatio) - .withWheelRadius(kWheelRadiusMeters) - .withSteerInertia(kSteerInertia) - .withDriveInertia(kDriveInertia) - .withSteerFrictionVoltage(kSteerFrictionVoltage) - .withDriveFrictionVoltage(kDriveFrictionVoltage); + private SwerveModuleConstantsFactory< + TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> + ConstantCreator = + new SwerveModuleConstantsFactory< + TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration>() + .withDriveMotorGearRatio(kDriveGearRatio) + .withSteerMotorGearRatio(kSteerGearRatio) + .withCouplingGearRatio(kCoupleRatio) + .withWheelRadius(kWheelRadiusMeters) + .withSteerInertia(kSteerInertia) + .withDriveInertia(kDriveInertia) + .withSteerFrictionVoltage(kSteerFrictionVoltage) + .withDriveFrictionVoltage(kDriveFrictionVoltage); } diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOSim.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOSim.java index 7d060c8b..52950e24 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOSim.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOSim.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright 2021-2024 FRC 6328 +// Copyright (c) 2021-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or @@ -15,6 +15,8 @@ package frc.robot.subsystems.drive; +import com.ctre.phoenix6.configs.CANcoderConfiguration; +import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.ctre.phoenix6.swerve.SwerveModuleConstants; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.controller.PIDController; @@ -53,7 +55,9 @@ public class ModuleIOSim implements ModuleIO { private double driveAppliedVolts = 0.0; private double turnAppliedVolts = 0.0; - public ModuleIOSim(SwerveModuleConstants constants) { + public ModuleIOSim( + SwerveModuleConstants + constants) { // Create drive and turn sim models driveSim = new DCMotorSim( diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java index a20abfe6..841ac551 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright 2021-2024 FRC 6328 +// Copyright (c) 2021-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or @@ -20,6 +20,7 @@ import com.revrobotics.AbsoluteEncoder; import com.revrobotics.RelativeEncoder; +import com.revrobotics.spark.ClosedLoopSlot; import com.revrobotics.spark.SparkBase; import com.revrobotics.spark.SparkBase.ControlType; import com.revrobotics.spark.SparkBase.PersistMode; @@ -259,7 +260,11 @@ public void setDriveVelocity(double velocityRadPerSec) { SwerveConstants.kDriveFrictionVoltage * Math.signum(velocityRadPerSec) + driveKv * velocityRadPerSec; driveController.setReference( - velocityRadPerSec, ControlType.kVelocity, 0, ffVolts, ArbFFUnits.kVoltage); + velocityRadPerSec, + ControlType.kVelocity, + ClosedLoopSlot.kSlot0, + ffVolts, + ArbFFUnits.kVoltage); } @Override diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkCANcoder.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkCANcoder.java index aeb152a1..ce7744c3 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkCANcoder.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkCANcoder.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright 2021-2024 FRC 6328 +// Copyright (c) 2021-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or @@ -22,6 +22,7 @@ import com.ctre.phoenix6.StatusSignal; import com.ctre.phoenix6.hardware.CANcoder; import com.revrobotics.RelativeEncoder; +import com.revrobotics.spark.ClosedLoopSlot; import com.revrobotics.spark.SparkBase; import com.revrobotics.spark.SparkBase.ControlType; import com.revrobotics.spark.SparkBase.PersistMode; @@ -286,7 +287,11 @@ public void setDriveVelocity(double velocityRadPerSec) { SwerveConstants.kDriveFrictionVoltage * Math.signum(velocityRadPerSec) + driveKv * velocityRadPerSec; driveController.setReference( - velocityRadPerSec, ControlType.kVelocity, 0, ffVolts, ArbFFUnits.kVoltage); + velocityRadPerSec, + ControlType.kVelocity, + ClosedLoopSlot.kSlot0, + ffVolts, + ArbFFUnits.kVoltage); } @Override diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java index 16f05567..20d5db3e 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright 2021-2024 FRC 6328 +// Copyright (c) 2021-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or @@ -35,6 +35,7 @@ import com.ctre.phoenix6.signals.NeutralModeValue; import com.ctre.phoenix6.signals.SensorDirectionValue; import com.ctre.phoenix6.swerve.SwerveModuleConstants; +import com.ctre.phoenix6.swerve.SwerveModuleConstants.ClosedLoopOutputType; import edu.wpi.first.math.filter.Debouncer; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.util.Units; @@ -42,6 +43,7 @@ import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.units.measure.Current; import edu.wpi.first.units.measure.Voltage; +import frc.robot.Constants; import frc.robot.generated.TunerConstants; import java.util.Queue; @@ -52,7 +54,9 @@ *

Device configuration and other behaviors not exposed by TunerConstants can be customized here. */ public class ModuleIOTalonFX implements ModuleIO { - private final SwerveModuleConstants constants; + private final SwerveModuleConstants< + TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> + constants; // Hardware objects private final TalonFX driveTalon; @@ -109,55 +113,63 @@ public ModuleIOTalonFX(int module) { driveTalon = new TalonFX(constants.DriveMotorId, SwerveConstants.kCANbusName); turnTalon = new TalonFX(constants.SteerMotorId, SwerveConstants.kCANbusName); - cancoder = new CANcoder(constants.CANcoderId, SwerveConstants.kCANbusName); + cancoder = new CANcoder(constants.EncoderId, SwerveConstants.kCANbusName); // Configure drive motor var driveConfig = constants.DriveMotorInitialConfigs; driveConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; driveConfig.Slot0 = constants.DriveMotorGains; - driveConfig.Feedback.SensorToMechanismRatio = constants.DriveMotorGearRatio; - driveConfig.TorqueCurrent.PeakForwardTorqueCurrent = constants.SlipCurrent; - driveConfig.TorqueCurrent.PeakReverseTorqueCurrent = -constants.SlipCurrent; - driveConfig.CurrentLimits.StatorCurrentLimit = constants.SlipCurrent; + driveConfig.Feedback.SensorToMechanismRatio = SwerveConstants.kDriveGearRatio; + driveConfig.TorqueCurrent.PeakForwardTorqueCurrent = SwerveConstants.kDriveSlipCurrent; + driveConfig.TorqueCurrent.PeakReverseTorqueCurrent = -SwerveConstants.kDriveSlipCurrent; + driveConfig.CurrentLimits.StatorCurrentLimit = SwerveConstants.kDriveCurrentLimit; driveConfig.CurrentLimits.StatorCurrentLimitEnable = true; driveConfig.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 TalonFXConfiguration(); turnConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; turnConfig.Slot0 = constants.SteerMotorGains; - turnConfig.Feedback.FeedbackRemoteSensorID = constants.CANcoderId; - turnConfig.Feedback.FeedbackSensorSource = - switch (constants.FeedbackSource) { - case RemoteCANcoder -> FeedbackSensorSourceValue.RemoteCANcoder; - case FusedCANcoder -> FeedbackSensorSourceValue.FusedCANcoder; - case SyncCANcoder -> FeedbackSensorSourceValue.SyncCANcoder; - }; - turnConfig.Feedback.RotorToSensorRatio = constants.SteerMotorGearRatio; - turnConfig.MotionMagic.MotionMagicCruiseVelocity = 100.0 / constants.SteerMotorGearRatio; + turnConfig.Feedback.FeedbackRemoteSensorID = constants.EncoderId; + turnConfig.Feedback.RotorToSensorRatio = SwerveConstants.kSteerGearRatio; + turnConfig.MotionMagic.MotionMagicCruiseVelocity = 100.0 / SwerveConstants.kSteerGearRatio; turnConfig.MotionMagic.MotionMagicAcceleration = turnConfig.MotionMagic.MotionMagicCruiseVelocity / 0.100; - turnConfig.MotionMagic.MotionMagicExpo_kV = 0.12 * constants.SteerMotorGearRatio; + turnConfig.MotionMagic.MotionMagicExpo_kV = 0.12 * SwerveConstants.kSteerGearRatio; 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 CANCoder - CANcoderConfiguration cancoderConfig = constants.CANcoderInitialConfigs; - cancoderConfig.MagnetSensor.MagnetOffset = constants.CANcoderOffset; + CANcoderConfiguration cancoderConfig = constants.EncoderInitialConfigs; + cancoderConfig.MagnetSensor.MagnetOffset = constants.EncoderOffset; cancoderConfig.MagnetSensor.SensorDirection = - constants.CANcoderInverted + constants.EncoderInverted ? SensorDirectionValue.Clockwise_Positive : SensorDirectionValue.CounterClockwise_Positive; + + // Set motor Closed Loop Output type and CANCoder feedback type based on Phoenix Pro status + switch (Constants.getPhoenixPro()) { + case LICENSED: + turnConfig.Feedback.FeedbackSensorSource = FeedbackSensorSourceValue.FusedCANcoder; + constants.DriveMotorClosedLoopOutput = ClosedLoopOutputType.TorqueCurrentFOC; + constants.SteerMotorClosedLoopOutput = ClosedLoopOutputType.TorqueCurrentFOC; + case UNLICENSED: + turnConfig.Feedback.FeedbackSensorSource = FeedbackSensorSourceValue.RemoteCANcoder; + constants.DriveMotorClosedLoopOutput = ClosedLoopOutputType.Voltage; + constants.SteerMotorClosedLoopOutput = ClosedLoopOutputType.Voltage; + } + + // Finally, apply the configs to the motor controllers + tryUntilOk(5, () -> driveTalon.getConfigurator().apply(driveConfig, 0.25)); + tryUntilOk(5, () -> driveTalon.setPosition(0.0, 0.25)); + tryUntilOk(5, () -> turnTalon.getConfigurator().apply(turnConfig, 0.25)); cancoder.getConfigurator().apply(cancoderConfig); // Create timestamp queue diff --git a/src/main/java/frc/robot/subsystems/drive/PhoenixOdometryThread.java b/src/main/java/frc/robot/subsystems/drive/PhoenixOdometryThread.java index 90f0f6f9..3b3a2e56 100644 --- a/src/main/java/frc/robot/subsystems/drive/PhoenixOdometryThread.java +++ b/src/main/java/frc/robot/subsystems/drive/PhoenixOdometryThread.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright 2021-2024 FRC 6328 +// Copyright (c) 2021-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or diff --git a/src/main/java/frc/robot/subsystems/drive/README b/src/main/java/frc/robot/subsystems/drive/README index 1e84dc77..2b457143 100644 --- a/src/main/java/frc/robot/subsystems/drive/README +++ b/src/main/java/frc/robot/subsystems/drive/README @@ -12,10 +12,10 @@ Existing IO files: - ``GyroIONavX.java``: NavX as the swerve IMU, connected via SPI - ``ModuleIOTalonFX.java``: 2x TalonFX motors + CANcoder - - ``ModuleIOSparkMax.java``: 2x Rev NEO motors + analog absolute encoder connected to the RIO + - ``ModuleIOSpark.java``: 2x Rev NEO motors + analog absolute encoder connected to the RIO - ``ModuleIOSparkCANcoder.java``: 2x Rv NEO motors + CANcoder - ``ModuleIOBlended.java``: TalonFX drive, Rev NEO steer motors + CANcoder -------------------- -Last Modified: 22 Nov 2024, TPEB +Last Modified: 2 Jan 2025, TPEB diff --git a/src/main/java/frc/robot/subsystems/drive/SparkOdometryThread.java b/src/main/java/frc/robot/subsystems/drive/SparkOdometryThread.java index 6df6929c..8ccb2edc 100644 --- a/src/main/java/frc/robot/subsystems/drive/SparkOdometryThread.java +++ b/src/main/java/frc/robot/subsystems/drive/SparkOdometryThread.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright 2021-2024 FRC 6328 +// Copyright (c) 2021-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or diff --git a/src/main/java/frc/robot/subsystems/drive/SwerveConstants.java b/src/main/java/frc/robot/subsystems/drive/SwerveConstants.java index 8f4d2e25..d5119272 100644 --- a/src/main/java/frc/robot/subsystems/drive/SwerveConstants.java +++ b/src/main/java/frc/robot/subsystems/drive/SwerveConstants.java @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First // // This program is free software; you can redistribute it and/or @@ -123,9 +123,10 @@ public class SwerveConstants { kDriveCurrentLimit = 120.0; // Example from CTRE documentation kDriveSlipCurrent = TunerConstants.FrontLeft.SlipCurrent; kOptimalVoltage = 12.0; // Assumed Ideal + // Front Left kFLDriveMotorId = TunerConstants.FrontLeft.DriveMotorId; kFLSteerMotorId = TunerConstants.FrontLeft.SteerMotorId; - kFLEncoderId = TunerConstants.FrontLeft.CANcoderId; + kFLEncoderId = TunerConstants.FrontLeft.EncoderId; kFLDriveCanbus = TunerConstants.DrivetrainConstants.CANBusName; kFLSteerCanbus = TunerConstants.DrivetrainConstants.CANBusName; kFLEncoderCanbus = TunerConstants.DrivetrainConstants.CANBusName; @@ -133,30 +134,32 @@ public class SwerveConstants { kFLSteerType = "kraken"; kFLEncoderType = "cancoder"; kFLEncoderOffset = - -Units.rotationsToRadians(TunerConstants.FrontLeft.CANcoderOffset) + Math.PI; + -Units.rotationsToRadians(TunerConstants.FrontLeft.EncoderOffset) + Math.PI; kFLDriveInvert = TunerConstants.FrontLeft.DriveMotorInverted; kFLSteerInvert = TunerConstants.FrontLeft.SteerMotorInverted; - kFLEncoderInvert = false; + kFLEncoderInvert = TunerConstants.FrontLeft.EncoderInverted; kFLXPosMeters = TunerConstants.FrontLeft.LocationX; kFLYPosMeters = TunerConstants.FrontLeft.LocationY; + // Front Right kFRDriveMotorId = TunerConstants.FrontRight.DriveMotorId; kFRSteerMotorId = TunerConstants.FrontRight.SteerMotorId; - kFREncoderId = TunerConstants.FrontRight.CANcoderId; + kFREncoderId = TunerConstants.FrontRight.EncoderId; kFRDriveCanbus = TunerConstants.DrivetrainConstants.CANBusName; kFRSteerCanbus = TunerConstants.DrivetrainConstants.CANBusName; kFREncoderCanbus = TunerConstants.DrivetrainConstants.CANBusName; kFRDriveType = "kraken"; kFRSteerType = "kraken"; kFREncoderType = "cancoder"; - kFREncoderOffset = -Units.rotationsToRadians(TunerConstants.FrontRight.CANcoderOffset); + kFREncoderOffset = -Units.rotationsToRadians(TunerConstants.FrontRight.EncoderOffset); kFRDriveInvert = TunerConstants.FrontRight.DriveMotorInverted; kFRSteerInvert = TunerConstants.FrontRight.SteerMotorInverted; - kFREncoderInvert = false; + kFREncoderInvert = TunerConstants.FrontRight.EncoderInverted; kFRXPosMeters = TunerConstants.FrontRight.LocationX; kFRYPosMeters = TunerConstants.FrontRight.LocationY; + // Back Left kBLDriveMotorId = TunerConstants.BackLeft.DriveMotorId; kBLSteerMotorId = TunerConstants.BackLeft.SteerMotorId; - kBLEncoderId = TunerConstants.BackLeft.CANcoderId; + kBLEncoderId = TunerConstants.BackLeft.EncoderId; kBLDriveCanbus = TunerConstants.DrivetrainConstants.CANBusName; kBLSteerCanbus = TunerConstants.DrivetrainConstants.CANBusName; kBLEncoderCanbus = TunerConstants.DrivetrainConstants.CANBusName; @@ -164,25 +167,26 @@ public class SwerveConstants { kBLSteerType = "kraken"; kBLEncoderType = "cancoder"; kBLEncoderOffset = - -Units.rotationsToRadians(TunerConstants.BackLeft.CANcoderOffset) + Math.PI; + -Units.rotationsToRadians(TunerConstants.BackLeft.EncoderOffset) + Math.PI; kBLDriveInvert = TunerConstants.BackLeft.DriveMotorInverted; kBLSteerInvert = TunerConstants.BackLeft.SteerMotorInverted; - kBLEncoderInvert = false; + kBLEncoderInvert = TunerConstants.BackLeft.EncoderInverted; kBLXPosMeters = TunerConstants.BackLeft.LocationX; kBLYPosMeters = TunerConstants.BackLeft.LocationY; + // Back Right kBRDriveMotorId = TunerConstants.BackRight.DriveMotorId; kBRSteerMotorId = TunerConstants.BackRight.SteerMotorId; - kBREncoderId = TunerConstants.BackRight.CANcoderId; + kBREncoderId = TunerConstants.BackRight.EncoderId; kBRDriveCanbus = TunerConstants.DrivetrainConstants.CANBusName; kBRSteerCanbus = TunerConstants.DrivetrainConstants.CANBusName; kBREncoderCanbus = TunerConstants.DrivetrainConstants.CANBusName; kBRDriveType = "kraken"; kBRSteerType = "kraken"; kBREncoderType = "cancoder"; - kBREncoderOffset = -Units.rotationsToRadians(TunerConstants.BackRight.CANcoderOffset); + kBREncoderOffset = -Units.rotationsToRadians(TunerConstants.BackRight.EncoderOffset); kBRDriveInvert = TunerConstants.BackRight.DriveMotorInverted; kBRSteerInvert = TunerConstants.BackRight.SteerMotorInverted; - kBREncoderInvert = false; + kBREncoderInvert = TunerConstants.BackRight.EncoderInverted; kBRXPosMeters = TunerConstants.BackRight.LocationX; kBRYPosMeters = TunerConstants.BackRight.LocationY; break; @@ -203,6 +207,7 @@ public class SwerveConstants { kDriveCurrentLimit = YagslConstants.kDriveCurrentLimit; kDriveSlipCurrent = 120.0; kOptimalVoltage = YagslConstants.kOptimalVoltage; + // Front Left kFLDriveMotorId = YagslConstants.kFrontLeftDriveMotorId; kFLSteerMotorId = YagslConstants.kFrontLeftSteerMotorId; kFLEncoderId = YagslConstants.kFrontLeftEncoderId; @@ -218,6 +223,7 @@ public class SwerveConstants { kFLEncoderInvert = YagslConstants.kFrontLeftEncoderInvert; kFLXPosMeters = Units.inchesToMeters(YagslConstants.kFrontLeftXPosInches); kFLYPosMeters = Units.inchesToMeters(YagslConstants.kFrontLeftYPosInches); + // Front Right kFRDriveMotorId = YagslConstants.kFrontRightDriveMotorId; kFRSteerMotorId = YagslConstants.kFrontRightSteerMotorId; kFREncoderId = YagslConstants.kFrontRightEncoderId; @@ -233,6 +239,7 @@ public class SwerveConstants { kFREncoderInvert = YagslConstants.kFrontRightEncoderInvert; kFRXPosMeters = Units.inchesToMeters(YagslConstants.kFrontRightXPosInches); kFRYPosMeters = Units.inchesToMeters(YagslConstants.kFrontRightYPosInches); + // Back Left kBLDriveMotorId = YagslConstants.kBackLeftDriveMotorId; kBLSteerMotorId = YagslConstants.kBackLeftSteerMotorId; kBLEncoderId = YagslConstants.kBackLeftEncoderId; @@ -248,6 +255,7 @@ public class SwerveConstants { kBLEncoderInvert = YagslConstants.kBackLeftEncoderInvert; kBLXPosMeters = Units.inchesToMeters(YagslConstants.kBackLeftXPosInches); kBLYPosMeters = Units.inchesToMeters(YagslConstants.kBackLeftYPosInches); + // Back Right kBRDriveMotorId = YagslConstants.kBackRightDriveMotorId; kBRSteerMotorId = YagslConstants.kBackRightSteerMotorId; kBREncoderId = YagslConstants.kBackRightEncoderId; 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 ee332e8f..53e3b0d3 100644 --- a/src/main/java/frc/robot/subsystems/flywheel_example/Flywheel.java +++ b/src/main/java/frc/robot/subsystems/flywheel_example/Flywheel.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright 2021-2024 FRC 6328 +// Copyright (c) 2021-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or 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 8c7d0139..5ffbf398 100644 --- a/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIO.java +++ b/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIO.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright 2021-2024 FRC 6328 +// Copyright (c) 2021-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or 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 fe3046d4..a4a82cd8 100644 --- a/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIOSim.java +++ b/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIOSim.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright 2021-2024 FRC 6328 +// Copyright (c) 2021-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or @@ -29,7 +29,7 @@ public class FlywheelIOSim implements FlywheelIO { // spins slower than the motors, this number should be greater than one. private static final double kFlywheelGearing = 1.0; - // 1/2 MR² + // 1/2 MR^2 private static final double kFlywheelMomentOfInertia = 0.5 * Units.lbsToKilograms(1.5) * Math.pow(Units.inchesToMeters(4), 2); 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 9a916bfc..871a9dea 100644 --- a/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIOSpark.java +++ b/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIOSpark.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright 2021-2024 FRC 6328 +// Copyright (c) 2021-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or @@ -19,6 +19,7 @@ import static frc.robot.util.SparkUtil.*; import com.revrobotics.RelativeEncoder; +import com.revrobotics.spark.ClosedLoopSlot; import com.revrobotics.spark.SparkBase; import com.revrobotics.spark.SparkBase.ControlType; import com.revrobotics.spark.SparkBase.PersistMode; @@ -58,7 +59,11 @@ public FlywheelIOSpark() { // Configure leader motor var leaderConfig = new SparkFlexConfig(); leaderConfig - .idleMode(IdleMode.kBrake) + .idleMode( + switch (kFlywheelIdleMode) { + case COAST -> IdleMode.kCoast; + case BRAKE -> IdleMode.kBrake; + }) .smartCurrentLimit((int) SwerveConstants.kDriveCurrentLimit) .voltageCompensation(12.0); leaderConfig.encoder.uvwMeasurementPeriod(10).uvwAverageDepth(2); @@ -105,7 +110,7 @@ public void setVelocity(double velocityRadPerSec, double ffVolts) { pid.setReference( Units.radiansPerSecondToRotationsPerMinute(velocityRadPerSec) * kFlywheelGearRatio, ControlType.kVelocity, - 0, + ClosedLoopSlot.kSlot0, ffVolts, ArbFFUnits.kVoltage); } 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 e294d1e6..9364d321 100644 --- a/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/flywheel_example/FlywheelIOTalonFX.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright 2021-2024 FRC 6328 +// Copyright (c) 2021-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or @@ -60,9 +60,14 @@ public FlywheelIOTalonFX() { var config = new TalonFXConfiguration(); config.CurrentLimits.SupplyCurrentLimit = 30.0; config.CurrentLimits.SupplyCurrentLimitEnable = true; - config.MotorOutput.NeutralMode = NeutralModeValue.Coast; + config.MotorOutput.NeutralMode = + switch (kFlywheelIdleMode) { + case COAST -> NeutralModeValue.Coast; + case BRAKE -> NeutralModeValue.Brake; + }; 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)); BaseStatusSignal.setUpdateFrequencyForAll( diff --git a/src/main/java/frc/robot/subsystems/flywheel_example/README b/src/main/java/frc/robot/subsystems/flywheel_example/README index 7cad088f..b796c05d 100644 --- a/src/main/java/frc/robot/subsystems/flywheel_example/README +++ b/src/main/java/frc/robot/subsystems/flywheel_example/README @@ -10,7 +10,7 @@ with AdvantageKit. The structure of the subsystem directory is: * FlywheelIO.java The base subsystem I/O (input/output) interface that contains the - structure and class varibales needed by the library-specific modules. + structure and class variables needed by the library-specific modules. * FlywheelIOSim.java Simulated flywheel module, for use with robot simulations, does not diff --git a/src/main/java/frc/robot/subsystems/vision/README b/src/main/java/frc/robot/subsystems/vision/README new file mode 100644 index 00000000..a8c8ad27 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/vision/README @@ -0,0 +1,29 @@ +This directory contains an the basic vision template, as distributed with +AdvantageKit. The structure of the subsystem directory is: + + * Vision.java + The base subsystem definitions and outward-facing (public) hardware- + agnostic functions for interacting with the subsystem. The idea is + that any of the hardware-specific (i.e. camera system API calls) + functionality is insulated from the rest of the robot code within + the library-specific modules in this directory. + + * VisionIO.java + The base subsystem I/O (input/output) interface that contains the + structure and class variables needed by the library-specific modules. + + * VisionIOLimelight.java + The vision implementation for the Limelight camera system, which maps + Limelight-specific API calls back onto the generic vision API defined + above. + + * VisionIOPhotonVision.java + The vision implementation for the Photon Vision camera system, which + maps PhotonLib-specific API calls back onto the generic vision API + defined above. + + * VisionIOPhotonVisionSim.java + Simulated vision module, for use with robot simulations, does not + control actual hardware. + + \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/vision/Vision.java b/src/main/java/frc/robot/subsystems/vision/Vision.java index d285f469..34c676a2 100644 --- a/src/main/java/frc/robot/subsystems/vision/Vision.java +++ b/src/main/java/frc/robot/subsystems/vision/Vision.java @@ -1,8 +1,8 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright (c) 2024 FRC 2486 +// Copyright (c) 2024-2025 FRC 2486 // http://github.com/Coconuts2486-FRC -// Copyright 2021-2024 FRC 6328 +// Copyright (c) 2021-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or diff --git a/src/main/java/frc/robot/subsystems/vision/VisionIO.java b/src/main/java/frc/robot/subsystems/vision/VisionIO.java index f2b85b8f..6755c3a7 100644 --- a/src/main/java/frc/robot/subsystems/vision/VisionIO.java +++ b/src/main/java/frc/robot/subsystems/vision/VisionIO.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright 2021-2024 FRC 6328 +// Copyright (c) 2021-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or diff --git a/src/main/java/frc/robot/subsystems/vision/VisionIOLimelight.java b/src/main/java/frc/robot/subsystems/vision/VisionIOLimelight.java index 21316dad..14e06a87 100644 --- a/src/main/java/frc/robot/subsystems/vision/VisionIOLimelight.java +++ b/src/main/java/frc/robot/subsystems/vision/VisionIOLimelight.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright 2021-2024 FRC 6328 +// Copyright (c) 2021-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or diff --git a/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVision.java b/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVision.java index 7f374e65..e61fc331 100644 --- a/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVision.java +++ b/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVision.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright 2021-2024 FRC 6328 +// Copyright (c) 2021-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or diff --git a/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVisionSim.java b/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVisionSim.java index a71991c4..e6574596 100644 --- a/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVisionSim.java +++ b/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVisionSim.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright 2021-2024 FRC 6328 +// Copyright (c) 2021-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or diff --git a/src/main/java/frc/robot/util/Alert.java b/src/main/java/frc/robot/util/Alert.java index 5608c3b7..b29d4ee7 100644 --- a/src/main/java/frc/robot/util/Alert.java +++ b/src/main/java/frc/robot/util/Alert.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright (c) 2024 FRC 6328 +// Copyright (c) 2024-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or diff --git a/src/main/java/frc/robot/util/GeomUtil.java b/src/main/java/frc/robot/util/GeomUtil.java index 3a59a7fd..3bc1578f 100644 --- a/src/main/java/frc/robot/util/GeomUtil.java +++ b/src/main/java/frc/robot/util/GeomUtil.java @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First // Copyright (c) 2024 FRC 6328 // http://github.com/Mechanical-Advantage diff --git a/src/main/java/frc/robot/util/GetJoystickValue.java b/src/main/java/frc/robot/util/GetJoystickValue.java index e2188313..d83b9018 100644 --- a/src/main/java/frc/robot/util/GetJoystickValue.java +++ b/src/main/java/frc/robot/util/GetJoystickValue.java @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First // // This program is free software; you can redistribute it and/or diff --git a/src/main/java/frc/robot/util/LocalADStarAK.java b/src/main/java/frc/robot/util/LocalADStarAK.java index 08b61727..e7828e50 100644 --- a/src/main/java/frc/robot/util/LocalADStarAK.java +++ b/src/main/java/frc/robot/util/LocalADStarAK.java @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First // Copyright (c) 2024 Michael Jansen // http://gist.github.com/mjansen4857 diff --git a/src/main/java/frc/robot/util/LoggedTunableNumber.java b/src/main/java/frc/robot/util/LoggedTunableNumber.java index 20c6b561..9db5d1cd 100644 --- a/src/main/java/frc/robot/util/LoggedTunableNumber.java +++ b/src/main/java/frc/robot/util/LoggedTunableNumber.java @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First // Copyright (c) 2024 FRC 6328 // http://github.com/Mechanical-Advantage diff --git a/src/main/java/frc/robot/util/OverrideSwitches.java b/src/main/java/frc/robot/util/OverrideSwitches.java index a04b00e3..9301bab4 100644 --- a/src/main/java/frc/robot/util/OverrideSwitches.java +++ b/src/main/java/frc/robot/util/OverrideSwitches.java @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First // Copyright (c) 2024 FRC 6328 // http://github.com/Mechanical-Advantage @@ -18,7 +18,7 @@ // https://www.chiefdelphi.com/t/frc-6328-mechanical-advantage-2024-build-thread/442736/72 // // The "Arcade Controller" used by 6328 (https://www.amazon.com/gp/product/B00UUROWWK) -// enumerates as a “Generic USB Controller”, mapped in this modules as a GenericHID. +// enumerates as a "Generic USB Controller", mapped in this modules as a GenericHID. // // If another type of controller is used, swap in the proper class. diff --git a/src/main/java/frc/robot/util/PhoenixUtil.java b/src/main/java/frc/robot/util/PhoenixUtil.java index cbe2d3ea..28951184 100644 --- a/src/main/java/frc/robot/util/PhoenixUtil.java +++ b/src/main/java/frc/robot/util/PhoenixUtil.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright 2021-2024 FRC 6328 +// Copyright (c) 2021-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or diff --git a/src/main/java/frc/robot/util/PowerMonitoring.java b/src/main/java/frc/robot/util/PowerMonitoring.java index 31dc7e81..52850d31 100644 --- a/src/main/java/frc/robot/util/PowerMonitoring.java +++ b/src/main/java/frc/robot/util/PowerMonitoring.java @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First // // This program is free software; you can redistribute it and/or diff --git a/src/main/java/frc/robot/util/RBSIEnum.java b/src/main/java/frc/robot/util/RBSIEnum.java index 8725c45a..ddb31d86 100644 --- a/src/main/java/frc/robot/util/RBSIEnum.java +++ b/src/main/java/frc/robot/util/RBSIEnum.java @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First // // This program is free software; you can redistribute it and/or @@ -51,4 +51,19 @@ public static enum VisionType { LIMELIGHT, // Limelight (https://docs.limelightvision.io/docs/docs-limelight/) NONE // No cameras } + + /** + * Enumerate CTRE Phoenix Pro Status + * https://v6.docs.ctr-electronics.com/en/latest/docs/licensing/licensing.html + */ + public static enum CTREPro { + LICENSED, // Have a valid 2025 CTRE Phoenix Pro License + UNLICENSED // Do not have a valid 2025 CTRE Phoenix Pro License + } + + /** Enumerate the supported motor idle modes */ + public static enum MotorIdleMode { + COAST, // Allow the motor to coast when idle + BRAKE // Hold motor position when idle + } } diff --git a/src/main/java/frc/robot/util/RBSISubsystem.java b/src/main/java/frc/robot/util/RBSISubsystem.java index 7a5c8e46..829300ff 100644 --- a/src/main/java/frc/robot/util/RBSISubsystem.java +++ b/src/main/java/frc/robot/util/RBSISubsystem.java @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First // // This program is free software; you can redistribute it and/or diff --git a/src/main/java/frc/robot/util/RobotDeviceId.java b/src/main/java/frc/robot/util/RobotDeviceId.java index 055491bc..4f1c2141 100644 --- a/src/main/java/frc/robot/util/RobotDeviceId.java +++ b/src/main/java/frc/robot/util/RobotDeviceId.java @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First // Copyright (c) 2024 FRC 254 // https://github.com/team254 diff --git a/src/main/java/frc/robot/util/SparkUtil.java b/src/main/java/frc/robot/util/SparkUtil.java index 9c86fd2e..df627df4 100644 --- a/src/main/java/frc/robot/util/SparkUtil.java +++ b/src/main/java/frc/robot/util/SparkUtil.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright 2021-2024 FRC 6328 +// Copyright (c) 2021-2025 FRC 6328 // http://github.com/Mechanical-Advantage // // This program is free software; you can redistribute it and/or diff --git a/src/main/java/frc/robot/util/VirtualSubsystem.java b/src/main/java/frc/robot/util/VirtualSubsystem.java index 2943eb06..59117db7 100644 --- a/src/main/java/frc/robot/util/VirtualSubsystem.java +++ b/src/main/java/frc/robot/util/VirtualSubsystem.java @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First // Copyright (c) 2024 FRC 6328 // http://github.com/Mechanical-Advantage diff --git a/src/main/java/frc/robot/util/YagslConstants.java b/src/main/java/frc/robot/util/YagslConstants.java index 9630b932..2b3302fe 100644 --- a/src/main/java/frc/robot/util/YagslConstants.java +++ b/src/main/java/frc/robot/util/YagslConstants.java @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First // // This program is free software; you can redistribute it and/or diff --git a/src/test/CurrentLimitTests.java b/src/test/CurrentLimitTests.java index dcf25f9c..02459aa3 100644 --- a/src/test/CurrentLimitTests.java +++ b/src/test/CurrentLimitTests.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright (c) 2024 Cross The Road Electronics +// 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 diff --git a/src/test/FusedCANcoderTests.java b/src/test/FusedCANcoderTests.java index 077eb269..bda6925f 100644 --- a/src/test/FusedCANcoderTests.java +++ b/src/test/FusedCANcoderTests.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright (c) 2024 Cross The Road Electronics +// 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 diff --git a/src/test/LatencyCompensationTests.java b/src/test/LatencyCompensationTests.java index 27c696a2..4fb6b653 100644 --- a/src/test/LatencyCompensationTests.java +++ b/src/test/LatencyCompensationTests.java @@ -1,6 +1,6 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 Az-FIRST // http://github.com/AZ-First -// Copyright (c) 2024 Cross The Road Electronics +// Copyright (c) -2025 Cross The Road Electronics // https://github.com/CrossTheRoadElec/Phoenix6-Examples // // This program is free software; you can redistribute it and/or diff --git a/src/test/RobotContainerTest.java b/src/test/RobotContainerTest.java index a7912d60..ad125e03 100644 --- a/src/test/RobotContainerTest.java +++ b/src/test/RobotContainerTest.java @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Az-FIRST +// Copyright (c) 2024-2025 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 69538ea8..c7f5262f 100644 --- a/vendordeps/AdvantageKit.json +++ b/vendordeps/AdvantageKit.json @@ -1,23 +1,25 @@ { "fileName": "AdvantageKit.json", "name": "AdvantageKit", - "version": "4.0.0-beta-1", + "version": "4.0.0", "uuid": "d820cc26-74e3-11ec-90d6-0242ac120003", "frcYear": "2025", - "mavenUrls": [], + "mavenUrls": [ + "https://frcmaven.wpi.edu/artifactory/littletonrobotics-mvn-release/" + ], "jsonUrl": "https://github.com/Mechanical-Advantage/AdvantageKit/releases/latest/download/AdvantageKit.json", "javaDependencies": [ { "groupId": "org.littletonrobotics.akit", "artifactId": "akit-java", - "version": "4.0.0-beta-1" + "version": "4.0.0" } ], "jniDependencies": [ { "groupId": "org.littletonrobotics.akit", "artifactId": "akit-wpilibio", - "version": "4.0.0-beta-1", + "version": "4.0.0", "skipInvalidPlatforms": false, "isJar": false, "validPlatforms": [ diff --git a/vendordeps/ChoreoLib2025Beta.json b/vendordeps/ChoreoLib2025.json similarity index 79% rename from vendordeps/ChoreoLib2025Beta.json rename to vendordeps/ChoreoLib2025.json index 914a8593..faef0111 100644 --- a/vendordeps/ChoreoLib2025Beta.json +++ b/vendordeps/ChoreoLib2025.json @@ -1,19 +1,19 @@ { - "fileName": "ChoreoLib2025Beta.json", + "fileName": "ChoreoLib2025.json", "name": "ChoreoLib", - "version": "2025.0.0-beta-9", + "version": "2025.0.1", "uuid": "b5e23f0a-dac9-4ad2-8dd6-02767c520aca", "frcYear": "2025", "mavenUrls": [ "https://lib.choreo.autos/dep", "https://repo1.maven.org/maven2" ], - "jsonUrl": "https://lib.choreo.autos/dep/ChoreoLib2025Beta.json", + "jsonUrl": "https://lib.choreo.autos/dep/ChoreoLib2025.json", "javaDependencies": [ { "groupId": "choreo", "artifactId": "ChoreoLib-java", - "version": "2025.0.0-beta-9" + "version": "2025.0.1" }, { "groupId": "com.google.code.gson", @@ -26,7 +26,7 @@ { "groupId": "choreo", "artifactId": "ChoreoLib-cpp", - "version": "2025.0.0-beta-9", + "version": "2025.0.1", "libName": "ChoreoLib", "headerClassifier": "headers", "sharedLibrary": false, diff --git a/vendordeps/NavX.json b/vendordeps/NavX.json deleted file mode 100644 index 6e535663..00000000 --- a/vendordeps/NavX.json +++ /dev/null @@ -1,39 +0,0 @@ -{ - "fileName": "NavX-2025.1.1-beta-1.json", - "name": "navx_frc", - "version": "2025.1.1-beta-1", - "uuid": "cb311d09-36e9-4143-a032-55bb2b94443b", - "frcYear": "2025", - "mavenUrls": [ - "https://dev.studica.com/maven/release/2025/" - ], - "jsonUrl": "https://dev.studica.com/releases/2025/NavX-2025.1.1-beta-1.json", - "javaDependencies": [ - { - "groupId": "com.kauailabs.navx.frc", - "artifactId": "navx_frc-java", - "version": "2025.1.1-beta-1" - } - ], - "jniDependencies": [], - "cppDependencies": [ - { - "groupId": "com.kauailabs.navx.frc", - "artifactId": "navx_frc-cpp", - "version": "2025.1.1-beta-1", - "headerClassifier": "headers", - "sourcesClassifier": "sources", - "sharedLibrary": false, - "libName": "navx_frc", - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "linuxathena", - "linuxarm32", - "linuxarm64", - "linuxx86-64", - "osxuniversal", - "windowsx86-64" - ] - } - ] -} diff --git a/vendordeps/PathplannerLib-beta.json b/vendordeps/PathplannerLib.json similarity index 82% rename from vendordeps/PathplannerLib-beta.json rename to vendordeps/PathplannerLib.json index 0185feb4..1371a406 100644 --- a/vendordeps/PathplannerLib-beta.json +++ b/vendordeps/PathplannerLib.json @@ -1,18 +1,18 @@ { - "fileName": "PathplannerLib-beta.json", + "fileName": "PathplannerLib.json", "name": "PathplannerLib", - "version": "2025.0.0-beta-6.1", + "version": "2025.2.1", "uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786", "frcYear": "2025", "mavenUrls": [ "https://3015rangerrobotics.github.io/pathplannerlib/repo" ], - "jsonUrl": "https://3015rangerrobotics.github.io/pathplannerlib/PathplannerLib-beta.json", + "jsonUrl": "https://3015rangerrobotics.github.io/pathplannerlib/PathplannerLib.json", "javaDependencies": [ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-java", - "version": "2025.0.0-beta-6.1" + "version": "2025.2.1" } ], "jniDependencies": [], @@ -20,15 +20,15 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-cpp", - "version": "2025.0.0-beta-6.1", + "version": "2025.2.1", "libName": "PathplannerLib", "headerClassifier": "headers", "sharedLibrary": false, "skipInvalidPlatforms": true, "binaryPlatforms": [ "windowsx86-64", - "osxuniversal", "linuxx86-64", + "osxuniversal", "linuxathena", "linuxarm32", "linuxarm64" diff --git a/vendordeps/Phoenix5-frc2025-beta-latest.json b/vendordeps/Phoenix5-frc2025-latest.json similarity index 84% rename from vendordeps/Phoenix5-frc2025-beta-latest.json rename to vendordeps/Phoenix5-frc2025-latest.json index ff142cf6..aa08d95b 100644 --- a/vendordeps/Phoenix5-frc2025-beta-latest.json +++ b/vendordeps/Phoenix5-frc2025-latest.json @@ -1,50 +1,50 @@ { - "fileName": "Phoenix5-frc2025-beta-latest.json", + "fileName": "Phoenix5-frc2025-latest.json", "name": "CTRE-Phoenix (v5)", - "version": "5.34.0-beta-4", + "version": "5.35.1", "frcYear": "2025", "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-beta-latest.json", + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2025-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-beta-latest.json", - "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-beta-latest.json" + "offlineFileName": "Phoenix6-frc2025-latest.json", + "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-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-beta-latest.json" + "offlineFileName": "Phoenix6-replay-frc2025-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-beta-latest.json" + "offlineFileName": "Phoenix5-replay-frc2025-latest.json" } ], "javaDependencies": [ { "groupId": "com.ctre.phoenix", "artifactId": "api-java", - "version": "5.34.0-beta-4" + "version": "5.35.1" }, { "groupId": "com.ctre.phoenix", "artifactId": "wpiapi-java", - "version": "5.34.0-beta-4" + "version": "5.35.1" } ], "jniDependencies": [ { "groupId": "com.ctre.phoenix", "artifactId": "cci", - "version": "5.34.0-beta-4", + "version": "5.35.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -58,7 +58,7 @@ { "groupId": "com.ctre.phoenix.sim", "artifactId": "cci-sim", - "version": "5.34.0-beta-4", + "version": "5.35.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -74,7 +74,7 @@ { "groupId": "com.ctre.phoenix", "artifactId": "wpiapi-cpp", - "version": "5.34.0-beta-4", + "version": "5.35.1", "libName": "CTRE_Phoenix_WPI", "headerClassifier": "headers", "sharedLibrary": true, @@ -90,7 +90,7 @@ { "groupId": "com.ctre.phoenix", "artifactId": "api-cpp", - "version": "5.34.0-beta-4", + "version": "5.35.1", "libName": "CTRE_Phoenix", "headerClassifier": "headers", "sharedLibrary": true, @@ -106,7 +106,7 @@ { "groupId": "com.ctre.phoenix", "artifactId": "cci", - "version": "5.34.0-beta-4", + "version": "5.35.1", "libName": "CTRE_PhoenixCCI", "headerClassifier": "headers", "sharedLibrary": true, @@ -122,7 +122,7 @@ { "groupId": "com.ctre.phoenix.sim", "artifactId": "wpiapi-cpp-sim", - "version": "5.34.0-beta-4", + "version": "5.35.1", "libName": "CTRE_Phoenix_WPISim", "headerClassifier": "headers", "sharedLibrary": true, @@ -138,7 +138,7 @@ { "groupId": "com.ctre.phoenix.sim", "artifactId": "api-cpp-sim", - "version": "5.34.0-beta-4", + "version": "5.35.1", "libName": "CTRE_PhoenixSim", "headerClassifier": "headers", "sharedLibrary": true, @@ -154,7 +154,7 @@ { "groupId": "com.ctre.phoenix.sim", "artifactId": "cci-sim", - "version": "5.34.0-beta-4", + "version": "5.35.1", "libName": "CTRE_PhoenixCCISim", "headerClassifier": "headers", "sharedLibrary": true, diff --git a/vendordeps/Phoenix6-frc2025-beta-latest.json b/vendordeps/Phoenix6-frc2025-latest.json similarity index 89% rename from vendordeps/Phoenix6-frc2025-beta-latest.json rename to vendordeps/Phoenix6-frc2025-latest.json index 140c7704..b1f42e3e 100644 --- a/vendordeps/Phoenix6-frc2025-beta-latest.json +++ b/vendordeps/Phoenix6-frc2025-latest.json @@ -1,32 +1,32 @@ { - "fileName": "Phoenix6-frc2025-beta-latest.json", + "fileName": "Phoenix6-frc2025-latest.json", "name": "CTRE-Phoenix (v6)", - "version": "25.0.0-beta-4", + "version": "25.1.0", "frcYear": "2025", "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-beta-latest.json", + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-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-beta-latest.json" + "offlineFileName": "Phoenix6-replay-frc2025-latest.json" } ], "javaDependencies": [ { "groupId": "com.ctre.phoenix6", "artifactId": "wpiapi-java", - "version": "25.0.0-beta-4" + "version": "25.1.0" } ], "jniDependencies": [ { "groupId": "com.ctre.phoenix6", "artifactId": "api-cpp", - "version": "25.0.0-beta-4", + "version": "25.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -40,7 +40,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "tools", - "version": "25.0.0-beta-4", + "version": "25.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -54,7 +54,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "api-cpp-sim", - "version": "25.0.0-beta-4", + "version": "25.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -68,7 +68,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "tools-sim", - "version": "25.0.0-beta-4", + "version": "25.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -82,7 +82,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonSRX", - "version": "25.0.0-beta-4", + "version": "25.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -96,7 +96,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simVictorSPX", - "version": "25.0.0-beta-4", + "version": "25.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -110,7 +110,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simPigeonIMU", - "version": "25.0.0-beta-4", + "version": "25.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -124,7 +124,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simCANCoder", - "version": "25.0.0-beta-4", + "version": "25.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -138,7 +138,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFX", - "version": "25.0.0-beta-4", + "version": "25.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -152,7 +152,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANcoder", - "version": "25.0.0-beta-4", + "version": "25.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -166,7 +166,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProPigeon2", - "version": "25.0.0-beta-4", + "version": "25.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -180,7 +180,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANrange", - "version": "25.0.0-beta-4", + "version": "25.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -196,7 +196,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "wpiapi-cpp", - "version": "25.0.0-beta-4", + "version": "25.1.0", "libName": "CTRE_Phoenix6_WPI", "headerClassifier": "headers", "sharedLibrary": true, @@ -212,7 +212,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "tools", - "version": "25.0.0-beta-4", + "version": "25.1.0", "libName": "CTRE_PhoenixTools", "headerClassifier": "headers", "sharedLibrary": true, @@ -228,7 +228,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "wpiapi-cpp-sim", - "version": "25.0.0-beta-4", + "version": "25.1.0", "libName": "CTRE_Phoenix6_WPISim", "headerClassifier": "headers", "sharedLibrary": true, @@ -244,7 +244,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "tools-sim", - "version": "25.0.0-beta-4", + "version": "25.1.0", "libName": "CTRE_PhoenixTools_Sim", "headerClassifier": "headers", "sharedLibrary": true, @@ -260,7 +260,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonSRX", - "version": "25.0.0-beta-4", + "version": "25.1.0", "libName": "CTRE_SimTalonSRX", "headerClassifier": "headers", "sharedLibrary": true, @@ -276,7 +276,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simVictorSPX", - "version": "25.0.0-beta-4", + "version": "25.1.0", "libName": "CTRE_SimVictorSPX", "headerClassifier": "headers", "sharedLibrary": true, @@ -292,7 +292,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simPigeonIMU", - "version": "25.0.0-beta-4", + "version": "25.1.0", "libName": "CTRE_SimPigeonIMU", "headerClassifier": "headers", "sharedLibrary": true, @@ -308,7 +308,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simCANCoder", - "version": "25.0.0-beta-4", + "version": "25.1.0", "libName": "CTRE_SimCANCoder", "headerClassifier": "headers", "sharedLibrary": true, @@ -324,7 +324,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFX", - "version": "25.0.0-beta-4", + "version": "25.1.0", "libName": "CTRE_SimProTalonFX", "headerClassifier": "headers", "sharedLibrary": true, @@ -340,7 +340,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANcoder", - "version": "25.0.0-beta-4", + "version": "25.1.0", "libName": "CTRE_SimProCANcoder", "headerClassifier": "headers", "sharedLibrary": true, @@ -356,7 +356,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProPigeon2", - "version": "25.0.0-beta-4", + "version": "25.1.0", "libName": "CTRE_SimProPigeon2", "headerClassifier": "headers", "sharedLibrary": true, @@ -372,7 +372,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANrange", - "version": "25.0.0-beta-4", + "version": "25.1.0", "libName": "CTRE_SimProCANrange", "headerClassifier": "headers", "sharedLibrary": true, diff --git a/vendordeps/REVLib.json b/vendordeps/REVLib.json index 6b3a1574..6e719675 100644 --- a/vendordeps/REVLib.json +++ b/vendordeps/REVLib.json @@ -1,7 +1,7 @@ { "fileName": "REVLib.json", "name": "REVLib", - "version": "2025.0.0-beta-4", + "version": "2025.0.0", "frcYear": "2025", "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", "mavenUrls": [ @@ -12,14 +12,14 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-java", - "version": "2025.0.0-beta-4" + "version": "2025.0.0" } ], "jniDependencies": [ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2025.0.0-beta-4", + "version": "2025.0.0", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ @@ -37,7 +37,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-cpp", - "version": "2025.0.0-beta-4", + "version": "2025.0.0", "libName": "REVLib", "headerClassifier": "headers", "sharedLibrary": false, @@ -55,7 +55,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2025.0.0-beta-4", + "version": "2025.0.0", "libName": "REVLibDriver", "headerClassifier": "headers", "sharedLibrary": false, diff --git a/vendordeps/ReduxLib_2025.json b/vendordeps/ReduxLib-2025.0.0.json similarity index 87% rename from vendordeps/ReduxLib_2025.json rename to vendordeps/ReduxLib-2025.0.0.json index 5305e85a..18ff5a11 100644 --- a/vendordeps/ReduxLib_2025.json +++ b/vendordeps/ReduxLib-2025.0.0.json @@ -1,8 +1,8 @@ { - "fileName": "ReduxLib_2025.json", + "fileName": "ReduxLib-2025.0.0.json", "name": "ReduxLib", - "version": "2025.0.0-beta2", - "frcYear": 2025, + "version": "2025.0.0", + "frcYear": "2025", "uuid": "151ecca8-670b-4026-8160-cdd2679ef2bd", "mavenUrls": [ "https://maven.reduxrobotics.com/" @@ -12,14 +12,14 @@ { "groupId": "com.reduxrobotics.frc", "artifactId": "ReduxLib-java", - "version": "2025.0.0-beta2" + "version": "2025.0.0" } ], "jniDependencies": [ { "groupId": "com.reduxrobotics.frc", "artifactId": "ReduxLib-driver", - "version": "2025.0.0-beta2", + "version": "2025.0.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -36,7 +36,7 @@ { "groupId": "com.reduxrobotics.frc", "artifactId": "ReduxLib-cpp", - "version": "2025.0.0-beta2", + "version": "2025.0.0", "libName": "ReduxLib", "headerClassifier": "headers", "sourcesClassifier": "sources", @@ -54,7 +54,7 @@ { "groupId": "com.reduxrobotics.frc", "artifactId": "ReduxLib-driver", - "version": "2025.0.0-beta2", + "version": "2025.0.0", "libName": "ReduxCore", "headerClassifier": "headers", "sharedLibrary": true, diff --git a/vendordeps/Studica-2025.0.0.json b/vendordeps/Studica-2025.0.0.json new file mode 100644 index 00000000..8cba5305 --- /dev/null +++ b/vendordeps/Studica-2025.0.0.json @@ -0,0 +1,71 @@ +{ + "fileName": "Studica-2025.0.0.json", + "name": "Studica", + "version": "2025.0.0", + "uuid": "cb311d09-36e9-4143-a032-55bb2b94443b", + "frcYear": "2025", + "mavenUrls": [ + "https://dev.studica.com/maven/release/2025/" + ], + "jsonUrl": "https://dev.studica.com/releases/2025/Studica-2025.0.0.json", + "cppDependencies": [ + { + "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.0" + }, + { + "artifactId": "Studica-driver", + "binaryPlatforms": [ + "linuxathena", + "linuxarm32", + "linuxarm64", + "linuxx86-64", + "osxuniversal", + "windowsx86-64" + ], + "groupId": "com.studica.frc", + "headerClassifier": "headers", + "libName": "StudicaDriver", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "version": "2025.0.0" + } + ], + "javaDependencies": [ + { + "artifactId": "Studica-java", + "groupId": "com.studica.frc", + "version": "2025.0.0" + } + ], + "jniDependencies": [ + { + "artifactId": "Studica-driver", + "groupId": "com.studica.frc", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "linuxathena", + "linuxarm32", + "linuxarm64", + "linuxx86-64", + "osxuniversal", + "windowsx86-64" + ], + "version": "2025.0.0" + } + ] +} diff --git a/vendordeps/ThriftyLib.json b/vendordeps/ThriftyLib.json new file mode 100644 index 00000000..23948625 --- /dev/null +++ b/vendordeps/ThriftyLib.json @@ -0,0 +1,20 @@ +{ + "fileName": "ThriftyLib.json", + "name": "ThriftyLib", + "version": "2025.0.1", + "frcYear": "2025", + "uuid": "60b2694b-9e6e-4026-81ee-6f167946f4b0", + "mavenUrls": [ + "https://docs.home.thethriftybot.com" + ], + "jsonUrl": "https://docs.home.thethriftybot.com/ThriftyLib.json", + "javaDependencies": [ + { + "groupId": "com.thethriftybot.frc", + "artifactId": "ThriftyLib-java", + "version": "2025.0.1" + } + ], + "jniDependencies": [], + "cppDependencies": [] +} diff --git a/vendordeps/URCL.json b/vendordeps/URCL.json index 1099ee6c..c991b6af 100644 --- a/vendordeps/URCL.json +++ b/vendordeps/URCL.json @@ -1,25 +1,25 @@ { "fileName": "URCL.json", "name": "URCL", - "version": "2025.0.0-beta-1", + "version": "2025.0.0", "frcYear": "2025", "uuid": "84246d17-a797-4d1e-bd9f-c59cd8d2477c", "mavenUrls": [ - "https://raw.githubusercontent.com/Mechanical-Advantage/URCL/2025.0.0-beta-1" + "https://frcmaven.wpi.edu/artifactory/littletonrobotics-mvn-release/" ], - "jsonUrl": "https://raw.githubusercontent.com/Mechanical-Advantage/URCL/maven/URCL.json", + "jsonUrl": "https://raw.githubusercontent.com/Mechanical-Advantage/URCL/main/URCL.json", "javaDependencies": [ { "groupId": "org.littletonrobotics.urcl", "artifactId": "URCL-java", - "version": "2025.0.0-beta-1" + "version": "2025.0.0" } ], "jniDependencies": [ { "groupId": "org.littletonrobotics.urcl", "artifactId": "URCL-driver", - "version": "2025.0.0-beta-1", + "version": "2025.0.0", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ @@ -34,7 +34,7 @@ { "groupId": "org.littletonrobotics.urcl", "artifactId": "URCL-cpp", - "version": "2025.0.0-beta-1", + "version": "2025.0.0", "libName": "URCL", "headerClassifier": "headers", "sharedLibrary": false, @@ -49,7 +49,7 @@ { "groupId": "org.littletonrobotics.urcl", "artifactId": "URCL-driver", - "version": "2025.0.0-beta-1", + "version": "2025.0.0", "libName": "URCLDriver", "headerClassifier": "headers", "sharedLibrary": false, diff --git a/vendordeps/maple-sim.json b/vendordeps/maple-sim.json index 4b4a9c57..39a6c80b 100644 --- a/vendordeps/maple-sim.json +++ b/vendordeps/maple-sim.json @@ -1,7 +1,7 @@ { "fileName": "maple-sim.json", "name": "maplesim", - "version": "0.2.7", + "version": "0.3.1", "frcYear": "2025", "uuid": "c39481e8-4a63-4a4c-9df6-48d91e4da37b", "mavenUrls": [ @@ -13,7 +13,7 @@ { "groupId": "org.ironmaple", "artifactId": "maplesim-java", - "version": "0.2.7" + "version": "0.3.1" }, { "groupId": "org.dyn4j", diff --git a/vendordeps/yagsl.json b/vendordeps/yagsl-2025.1.3.json similarity index 70% rename from vendordeps/yagsl.json rename to vendordeps/yagsl-2025.1.3.json index cb05dc8d..b3be624b 100644 --- a/vendordeps/yagsl.json +++ b/vendordeps/yagsl-2025.1.3.json @@ -1,7 +1,7 @@ { - "fileName": "yagsl.json", + "fileName": "yagsl-2025.1.3.json", "name": "YAGSL", - "version": "2025.1.0.4", + "version": "2025.1.3", "frcYear": "2025", "uuid": "1ccce5a4-acd2-4d18-bca3-4b8047188400", "mavenUrls": [ @@ -12,39 +12,45 @@ { "groupId": "swervelib", "artifactId": "YAGSL-java", - "version": "2025.1.0.4" + "version": "2025.1.3" } ], "requires": [ { "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", "errorMessage": "REVLib is required!", - "offlineFileName": "REVLib.json", + "offlineFileName": "REVLib-2025.0.0.json", "onlineUrl": "https://software-metadata.revrobotics.com/REVLib-2025.json" }, { "uuid": "151ecca8-670b-4026-8160-cdd2679ef2bd", "errorMessage": "ReduxLib is required!", - "offlineFileName": "ReduxLib_2025.json", + "offlineFileName": "ReduxLib-2025.0.0.json", "onlineUrl": "https://frcsdk.reduxrobotics.com/ReduxLib_2025.json" }, { "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", "errorMessage": "Phoenix6 is required!", - "offlineFileName": "Phoenix6-frc2025-beta-latest.json", - "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-beta-latest.json" + "offlineFileName": "Phoenix6-25.1.0.json", + "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-latest.json" }, { "uuid": "ab676553-b602-441f-a38d-f1296eff6537", "errorMessage": "Phoenix5 is required!", - "offlineFileName": "Phoenix5.json", - "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2025-beta-latest.json" + "offlineFileName": "Phoenix5-5.35.0.json", + "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2025-latest.json" }, { "uuid": "cb311d09-36e9-4143-a032-55bb2b94443b", "errorMessage": "NavX is required!", - "offlineFileName": "Studica-2025.1.1-beta-3.json", - "onlineUrl": "https://dev.studica.com/releases/2025/Studica-2025.1.1-beta-3.json" + "offlineFileName": "Studica-2025.0.0.json", + "onlineUrl": "https://dev.studica.com/releases/2025/Studica-2025.0.0.json" + }, + { + "uuid": "60b2694b-9e6e-4026-81ee-6f167946f4b0", + "errorMessage": "ThriftyLib is required!", + "offlineFileName": "ThriftyLib.json", + "onlineUrl": "https://docs.home.thethriftybot.com/ThriftyLib.json" }, { "uuid": "c39481e8-4a63-4a4c-9df6-48d91e4da37b",