diff --git a/.vscode/settings.json b/.vscode/settings.json index 5c330e4..cba58c6 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -59,6 +59,7 @@ "edu.wpi.first.math.**.proto.*", "edu.wpi.first.math.**.struct.*", ], + "java.dependency.enableDependencyCheckup": false, "java.format.settings.url": "formatter.xml", "java.format.settings.profile": "GoogleStyle", "[java]": { diff --git a/.wpilib/wpilib_preferences.json b/.wpilib/wpilib_preferences.json index 81736c3..d96b33f 100644 --- a/.wpilib/wpilib_preferences.json +++ b/.wpilib/wpilib_preferences.json @@ -1,6 +1,6 @@ { "enableCppIntellisense": false, "currentLanguage": "java", - "projectYear": "2025", + "projectYear": "2026", "teamNumber": 5572 } \ No newline at end of file diff --git a/WPILib-License.md b/WPILib-License.md index 645e542..eb3061b 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-2026 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 541fbe4..79aee7c 100644 --- a/build.gradle +++ b/build.gradle @@ -1,6 +1,6 @@ plugins { id "java" - id "edu.wpi.first.GradleRIO" version "2025.3.2" + id "edu.wpi.first.GradleRIO" version "2026.1.1" id "com.peterabeles.gversion" version "1.10" } @@ -44,7 +44,8 @@ deploy { def deployArtifact = deploy.targets.roborio.artifacts.frcJava -// Set to true to use debug for JNI. +// Set to true to use debug for all targets including JNI, which will drastically impact +// performance. wpi.java.debugJni = false // Set this to true to enable desktop support. @@ -109,7 +110,9 @@ wpi.sim.addDriverstation() // knows where to look for our Robot Class. jar { from { configurations.runtimeClasspath.collect { it.isDirectory() ? it : zipTree(it) } } - from sourceSets.main.allSource + from('src') { into 'backup/src' } + from('vendordeps') { into 'backup/vendordeps' } + from('build.gradle') { into 'backup' } manifest edu.wpi.first.gradlerio.GradleRIOPlugin.javaManifest(ROBOT_MAIN_CLASS) duplicatesStrategy = DuplicatesStrategy.INCLUDE } diff --git a/settings.gradle b/settings.gradle index 969c7b0..25f6f6e 100644 --- a/settings.gradle +++ b/settings.gradle @@ -4,7 +4,7 @@ pluginManagement { repositories { mavenLocal() gradlePluginPortal() - String frcYear = '2025' + String frcYear = '2026' File frcHome if (OperatingSystem.current().isWindows()) { String publicFolder = System.getenv('PUBLIC') @@ -20,8 +20,8 @@ pluginManagement { } def frcHomeMaven = new File(frcHome, 'maven') maven { - name 'frcHome' - url frcHomeMaven + name = 'frcHome' + url = frcHomeMaven } } } diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 9a3c3c5..f780747 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -1,16 +1,11 @@ package frc.robot; -import org.ironmaple.simulation.SimulatedArena; import org.jspecify.annotations.NullMarked; -import org.littletonrobotics.junction.Logger; -import edu.wpi.first.math.geometry.Pose2d; -import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import frc.robot.Robot.RobotRunType; import frc.robot.subsystems.swerve.Swerve; import frc.robot.subsystems.swerve.SwerveIOEmpty; import frc.robot.subsystems.swerve.SwerveReal; -import frc.robot.subsystems.swerve.SwerveSim; import frc.robot.subsystems.swerve.gyro.GyroIOEmpty; import frc.robot.subsystems.swerve.gyro.GyroNavX2; import frc.robot.subsystems.swerve.mod.SwerveModuleIOEmpty; @@ -19,7 +14,6 @@ import frc.robot.subsystems.vision.Vision; import frc.robot.subsystems.vision.VisionIOEmpty; import frc.robot.subsystems.vision.VisionReal; -import frc.robot.subsystems.vision.VisionSim; import frc.robot.util.DeviceDebug; import frc.robot.viz.RobotViz; @@ -40,8 +34,6 @@ public final class RobotContainer { /* Subsystems */ private final Swerve swerve; private final Vision vision; - - private final SwerveSim sim; private final RobotViz viz; /** @@ -49,21 +41,14 @@ public final class RobotContainer { public RobotContainer(RobotRunType runtimeType) { switch (runtimeType) { case kReal: - sim = null; swerve = new Swerve(SwerveReal::new, GyroNavX2::new, SwerveModuleReal::new); vision = new Vision(swerve.state, new VisionReal()); break; - case kSimulation: - sim = new SwerveSim(new Pose2d(2.0, 2.0, Rotation2d.kZero)); - swerve = new Swerve(sim::simProvider, sim::gyroProvider, sim::moduleProvider); - vision = new Vision(swerve.state, new VisionSim(sim)); - break; default: - sim = null; swerve = new Swerve(SwerveIOEmpty::new, GyroIOEmpty::new, SwerveModuleIOEmpty::new); vision = new Vision(swerve.state, new VisionIOEmpty()); } - viz = new RobotViz(sim, swerve); + viz = new RobotViz(swerve); DeviceDebug.initialize(); @@ -78,13 +63,6 @@ public RobotContainer(RobotRunType runtimeType) { /** Runs once per 0.02 seconds after subsystems and commands. */ public void periodic() { - if (sim != null) { - SimulatedArena.getInstance().simulationPeriodic(); - Logger.recordOutput("FieldSimulation/Algae", - SimulatedArena.getInstance().getGamePiecesArrayByType("Algae")); - Logger.recordOutput("FieldSimulation/Coral", - SimulatedArena.getInstance().getGamePiecesArrayByType("Coral")); - } viz.periodic(); } } diff --git a/src/main/java/frc/robot/subsystems/swerve/SwerveSim.java b/src/main/java/frc/robot/subsystems/swerve/SwerveSim.java deleted file mode 100644 index 036bcf0..0000000 --- a/src/main/java/frc/robot/subsystems/swerve/SwerveSim.java +++ /dev/null @@ -1,71 +0,0 @@ -package frc.robot.subsystems.swerve; - -import static edu.wpi.first.units.Units.KilogramSquareMeters; -import static edu.wpi.first.units.Units.Pounds; -import static edu.wpi.first.units.Units.Volts; -import org.ironmaple.simulation.SimulatedArena; -import org.ironmaple.simulation.drivesims.COTS; -import org.ironmaple.simulation.drivesims.SwerveDriveSimulation; -import org.ironmaple.simulation.drivesims.configs.DriveTrainSimulationConfig; -import org.ironmaple.simulation.drivesims.configs.SwerveModuleSimulationConfig; -import org.jspecify.annotations.NullMarked; -import edu.wpi.first.math.geometry.Pose2d; -import edu.wpi.first.math.system.plant.DCMotor; -import edu.wpi.first.wpilibj.Timer; -import frc.robot.Constants; -import frc.robot.subsystems.swerve.gyro.GyroIO; -import frc.robot.subsystems.swerve.gyro.GyroSim; -import frc.robot.subsystems.swerve.mod.SwerveModuleIO; -import frc.robot.subsystems.swerve.mod.SwerveModuleSim; -import frc.robot.subsystems.swerve.util.PhoenixOdometryThread; - -/** Simulation implementation for swerve */ -@NullMarked -public final class SwerveSim implements SwerveIO { - - public final SwerveDriveSimulation mapleSim; - - /** Simulation implementation for swerve */ - public SwerveSim(Pose2d initialPose) { - this.mapleSim = new SwerveDriveSimulation( - DriveTrainSimulationConfig.Default().withGyro(COTS.ofNav2X()) - .withRobotMass(Pounds.of(150)) - .withCustomModuleTranslations(Constants.Swerve.swerveTranslations) - .withBumperSize(Constants.Swerve.bumperFront.times(2), - Constants.Swerve.bumperRight.times(2)) - .withSwerveModule(new SwerveModuleSimulationConfig(DCMotor.getKrakenX60(1), - DCMotor.getKrakenX60(1), Constants.Swerve.driveGearRatio, - Constants.Swerve.angleGearRatio, Volts.of(0.15), Volts.of(0.35), - Constants.Swerve.wheelRadius, KilogramSquareMeters.of(0.02), 1.2)), - initialPose); - SimulatedArena.getInstance().addDriveTrainSimulation(this.mapleSim); - } - - - /** Supplier passed into Swerve constructor */ - public SwerveSim simProvider(PhoenixOdometryThread odometryThread) { - return this; - } - - /** Supplier passed into Swerve constructor */ - public GyroIO gyroProvider(PhoenixOdometryThread odometryThread) { - return new GyroSim(this.mapleSim.getGyroSimulation()); - } - - /** Supplier passed into Swerve constructor */ - public SwerveModuleIO moduleProvider(int index, PhoenixOdometryThread odometryThread) { - return new SwerveModuleSim(index, this.mapleSim.getModules()[index]); - } - - @Override - public void updateInputs(SwerveInputs inputs) { - inputs.timestamps = new double[] {Timer.getTimestamp()}; - } - - - @Override - public void resetPose(Pose2d pose) { - mapleSim.setSimulationWorldPose(pose); - } - -} diff --git a/src/main/java/frc/robot/subsystems/swerve/gyro/GyroSim.java b/src/main/java/frc/robot/subsystems/swerve/gyro/GyroSim.java deleted file mode 100644 index 5d3f62c..0000000 --- a/src/main/java/frc/robot/subsystems/swerve/gyro/GyroSim.java +++ /dev/null @@ -1,26 +0,0 @@ -package frc.robot.subsystems.swerve.gyro; - -import static edu.wpi.first.units.Units.RadiansPerSecond; -import org.ironmaple.simulation.drivesims.GyroSimulation; -import org.jspecify.annotations.NullMarked; - -/** Simulation implementation for gyro */ -@NullMarked -public class GyroSim implements GyroIO { - - private final GyroSimulation gyro; - - /** Simulation implementation for gyro */ - public GyroSim(GyroSimulation gyro) { - this.gyro = gyro; - } - - @Override - public void updateInputs(GyroInputs inputs) { - inputs.yaw = gyro.getGyroReading(); - inputs.yawVelocityRadPerSec = gyro.getMeasuredAngularVelocity().in(RadiansPerSecond); - inputs.yawRads = new double[] {inputs.yaw.getRadians()}; - inputs.connected = true; - } - -} diff --git a/src/main/java/frc/robot/subsystems/swerve/mod/SwerveModuleReal.java b/src/main/java/frc/robot/subsystems/swerve/mod/SwerveModuleReal.java index 5dfe773..e593301 100644 --- a/src/main/java/frc/robot/subsystems/swerve/mod/SwerveModuleReal.java +++ b/src/main/java/frc/robot/subsystems/swerve/mod/SwerveModuleReal.java @@ -5,6 +5,7 @@ import java.util.concurrent.Executors; import org.jspecify.annotations.NullMarked; import com.ctre.phoenix6.BaseStatusSignal; +import com.ctre.phoenix6.CANBus; import com.ctre.phoenix6.StatusSignal; import com.ctre.phoenix6.configs.CANcoderConfiguration; import com.ctre.phoenix6.configs.TalonFXConfiguration; @@ -65,7 +66,7 @@ public class SwerveModuleReal implements SwerveModuleIO { public SwerveModuleReal(int index, PhoenixOdometryThread odometryThread) { boolean isCanivore = Constants.Swerve.isCanviore; - String loop = isCanivore ? "*" : ""; + CANBus loop = isCanivore ? new CANBus("*") : CANBus.roboRIO(); driveMotor = new TalonFX(Constants.Swerve.modulesConstants[index].driveMotorId, loop); angleMotor = new TalonFX(Constants.Swerve.modulesConstants[index].angleMotorId, loop); absoluteEncoder = new CANcoder(Constants.Swerve.modulesConstants[index].canCoderId, loop); diff --git a/src/main/java/frc/robot/subsystems/swerve/mod/SwerveModuleSim.java b/src/main/java/frc/robot/subsystems/swerve/mod/SwerveModuleSim.java deleted file mode 100644 index 5763a8c..0000000 --- a/src/main/java/frc/robot/subsystems/swerve/mod/SwerveModuleSim.java +++ /dev/null @@ -1,142 +0,0 @@ -package frc.robot.subsystems.swerve.mod; - -import static edu.wpi.first.units.Units.Amps; -import static edu.wpi.first.units.Units.Radians; -import static edu.wpi.first.units.Units.RadiansPerSecond; -import org.ironmaple.simulation.drivesims.SwerveModuleSimulation; -import org.ironmaple.simulation.motorsims.SimulatedMotorController; -import org.jspecify.annotations.NullMarked; -import org.littletonrobotics.junction.Logger; -import edu.wpi.first.math.controller.PIDController; -import edu.wpi.first.math.geometry.Rotation2d; -import edu.wpi.first.units.Units; -import frc.robot.Constants; - -/** Simulation implementation for Swerve Module */ -@NullMarked -public class SwerveModuleSim implements SwerveModuleIO { - - private final SwerveModuleSimulation moduleSimulation; - private final SimulatedMotorController.GenericMotorController driveMotor; - private final SimulatedMotorController.GenericMotorController turnMotor; - - private final int id; - - private boolean driveClosedLoop = false; - private boolean turnClosedLoop = false; - private final PIDController driveController; - private final PIDController turnController; - private double driveFFVolts = 0.0; - private double driveAppliedVolts = 0.0; - private double turnAppliedVolts = 0.0; - - private double kV = 1.0; - private double targetVelocity = 0.0; - - /** Simulation implementation for Swerve Module */ - public SwerveModuleSim(int index, SwerveModuleSimulation modSim) { - this.id = index; - this.moduleSimulation = modSim; - this.driveMotor = moduleSimulation.useGenericMotorControllerForDrive() - .withCurrentLimit(Amps.of(Constants.Swerve.driveCurrentLimit)); - this.turnMotor = - moduleSimulation.useGenericControllerForSteer().withCurrentLimit(Amps.of(20)); - - this.driveController = new PIDController(0.5, 0.0, 0.0); - this.turnController = new PIDController(8.0, 0.0, 0.0); - - // Enable wrapping for turn PID - turnController.enableContinuousInput(-Math.PI, Math.PI); - } - - @Override - public void updateInputs(SwerveModuleInputs inputs) { - if (driveClosedLoop) { - if (Math.abs(driveController.getSetpoint()) < 0.01) { - driveAppliedVolts = 0.0; - driveController.reset(); - } else { - driveAppliedVolts = driveFFVolts - + driveController.calculate( - moduleSimulation.getDriveWheelFinalSpeed().in(Units.RadiansPerSecond)) - + kV * targetVelocity; - } - } else { - driveController.reset(); - } - if (turnClosedLoop) { - turnAppliedVolts = - turnController.calculate(moduleSimulation.getSteerAbsoluteFacing().getRadians()); - } else { - turnController.reset(); - } - - Logger.recordOutput("driveVoltage" + id, driveAppliedVolts); - Logger.recordOutput("angleVoltage" + id, turnAppliedVolts); - - driveMotor.requestVoltage(Units.Volts.of(driveAppliedVolts)); - turnMotor.requestVoltage(Units.Volts.of(turnAppliedVolts)); - - inputs.driveConnected = true; - inputs.angleConnected = true; - inputs.absoluteAngleConnected = true; - - inputs.drivePositionRad = moduleSimulation.getDriveWheelFinalPosition().in(Radians); - inputs.driveVelocityRadPerSec = - moduleSimulation.getDriveWheelFinalSpeed().in(RadiansPerSecond); - inputs.angleAbsolutePosition = moduleSimulation.getSteerAbsoluteFacing(); - inputs.anglePosition = inputs.angleAbsolutePosition; - inputs.angleVelocityRadPerSec = - moduleSimulation.getSteerAbsoluteEncoderSpeed().in(RadiansPerSecond); - - inputs.odometryDrivePositionsRad = new double[] {inputs.drivePositionRad}; - inputs.odometryDriveVelocityRadsPerSec = new double[] {inputs.driveVelocityRadPerSec}; - inputs.odometryAnglePositions = new Rotation2d[] {inputs.anglePosition}; - } - - @Override - public void runDriveOpenLoop(double output) { - driveClosedLoop = false; - driveAppliedVolts = output; - } - - @Override - public void runAngleOpenLoop(double output) { - turnClosedLoop = false; - turnAppliedVolts = output; - } - - @Override - public void runDriveVelocity(double velocityRadPerSec, double feedforward) { - driveClosedLoop = true; - driveController.setSetpoint(velocityRadPerSec); - targetVelocity = velocityRadPerSec; - } - - @Override - public void runAnglePosition(Rotation2d rotation) { - turnClosedLoop = true; - turnController.setSetpoint(rotation.getRadians()); - } - - @Override - public void setDrivePID(double kP, double kI, double kD, double kS, double kV, double kA) { - // Changing PID not handled in sim - } - - @Override - public void setAnglePID(double kP, double kI, double kD) { - // Changing PID not handled in sim - } - - @Override - public void setDriveBrakeMode(boolean enabled) { - // Brake mode not handled in sim - } - - @Override - public void setAngleBrakeMode(boolean enabled) { - // Brake mode not handled in sim - } - -} diff --git a/src/main/java/frc/robot/subsystems/vision/VisionSim.java b/src/main/java/frc/robot/subsystems/vision/VisionSim.java deleted file mode 100644 index d2c77fe..0000000 --- a/src/main/java/frc/robot/subsystems/vision/VisionSim.java +++ /dev/null @@ -1,48 +0,0 @@ -package frc.robot.subsystems.vision; - -import static edu.wpi.first.units.Units.Hertz; -import static edu.wpi.first.units.Units.Milliseconds; -import org.ironmaple.simulation.drivesims.SwerveDriveSimulation; -import org.jspecify.annotations.NullMarked; -import org.photonvision.simulation.PhotonCameraSim; -import org.photonvision.simulation.SimCameraProperties; -import org.photonvision.simulation.VisionSystemSim; -import frc.robot.Constants; -import frc.robot.subsystems.swerve.SwerveSim; - -/** Simulation of vision using built-in PhotonVision simulator. */ -@NullMarked -public class VisionSim extends VisionReal { - - private final SwerveDriveSimulation sim; - private final VisionSystemSim visionSim; - - /** Simulation of vision using built-in PhotonVision simulator. */ - public VisionSim(SwerveSim sim) { - this.sim = sim.mapleSim; - this.visionSim = new VisionSystemSim("main"); - - visionSim.addAprilTags(Constants.Vision.fieldLayout); - - var constants = Constants.Vision.cameraConstants; - for (int i = 0; i < constants.length; i++) { - SimCameraProperties props = new SimCameraProperties(); - props.setCalibration(constants[i].width, constants[i].height, - constants[i].horizontalFieldOfView); - props.setCalibError(constants[i].calibrationErrorMean, - constants[i].calibrationErrorStdDev); - props.setFPS(constants[i].simFps.in(Hertz)); - props.setAvgLatencyMs(constants[i].simLatency.in(Milliseconds)); - props.setLatencyStdDevMs(constants[i].simLatencyStdDev.in(Milliseconds)); - PhotonCameraSim cameraSim = new PhotonCameraSim(this.cameras[i], props); - visionSim.addCamera(cameraSim, constants[i].robotToCamera); - } - } - - @Override - public void updateInputs(CameraInputs[] inputs) { - visionSim.update(sim.getSimulatedDriveTrainPose()); - super.updateInputs(inputs); - } - -} diff --git a/src/main/java/frc/robot/viz/RobotViz.java b/src/main/java/frc/robot/viz/RobotViz.java index e52f7ca..0232197 100644 --- a/src/main/java/frc/robot/viz/RobotViz.java +++ b/src/main/java/frc/robot/viz/RobotViz.java @@ -8,7 +8,6 @@ import edu.wpi.first.math.geometry.Pose3d; import frc.robot.Constants; import frc.robot.subsystems.swerve.Swerve; -import frc.robot.subsystems.swerve.SwerveSim; import frc.robot.subsystems.vision.CameraConstants; /** @@ -27,11 +26,8 @@ *

* This class supports both real and simulated operation: *

* *

@@ -48,17 +44,11 @@ public class RobotViz { /** * Creates a new visualization helper. * - * @param sim optional swerve simulator; when provided, simulated ground-truth drivetrain pose - * is used for visualization * @param swerve live swerve subsystem providing pose estimates when not simulating */ - public RobotViz(@Nullable SwerveSim sim, Swerve swerve) { + public RobotViz(Swerve swerve) { estPoseSupplier = () -> new Pose3d(swerve.state.getGlobalPoseEstimate()); - if (sim != null) { - robotPoseSupplier = () -> new Pose3d(sim.mapleSim.getSimulatedDriveTrainPose()); - } else { - robotPoseSupplier = estPoseSupplier; - } + robotPoseSupplier = estPoseSupplier; } /** diff --git a/vendordeps/AdvantageKit.json b/vendordeps/AdvantageKit.json index bef4a15..162ad66 100644 --- a/vendordeps/AdvantageKit.json +++ b/vendordeps/AdvantageKit.json @@ -1,9 +1,9 @@ { "fileName": "AdvantageKit.json", "name": "AdvantageKit", - "version": "4.1.2", + "version": "26.0.0", "uuid": "d820cc26-74e3-11ec-90d6-0242ac120003", - "frcYear": "2025", + "frcYear": "2026", "mavenUrls": [ "https://frcmaven.wpi.edu/artifactory/littletonrobotics-mvn-release/" ], @@ -12,14 +12,14 @@ { "groupId": "org.littletonrobotics.akit", "artifactId": "akit-java", - "version": "4.1.2" + "version": "26.0.0" } ], "jniDependencies": [ { "groupId": "org.littletonrobotics.akit", "artifactId": "akit-wpilibio", - "version": "4.1.2", + "version": "26.0.0", "skipInvalidPlatforms": false, "isJar": false, "validPlatforms": [ diff --git a/vendordeps/ChoreoLib2025.json b/vendordeps/ChoreoLib2025.json deleted file mode 100644 index 2c2d3c3..0000000 --- a/vendordeps/ChoreoLib2025.json +++ /dev/null @@ -1,44 +0,0 @@ -{ - "fileName": "ChoreoLib2025.json", - "name": "ChoreoLib", - "version": "2025.0.3", - "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/ChoreoLib2025.json", - "javaDependencies": [ - { - "groupId": "choreo", - "artifactId": "ChoreoLib-java", - "version": "2025.0.3" - }, - { - "groupId": "com.google.code.gson", - "artifactId": "gson", - "version": "2.11.0" - } - ], - "jniDependencies": [], - "cppDependencies": [ - { - "groupId": "choreo", - "artifactId": "ChoreoLib-cpp", - "version": "2025.0.3", - "libName": "ChoreoLib", - "headerClassifier": "headers", - "sharedLibrary": false, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal", - "linuxathena", - "linuxarm32", - "linuxarm64" - ] - } - ] -} diff --git a/vendordeps/ChoreoLib2026.json b/vendordeps/ChoreoLib2026.json new file mode 100644 index 0000000..322c9e2 --- /dev/null +++ b/vendordeps/ChoreoLib2026.json @@ -0,0 +1,44 @@ +{ + "fileName": "ChoreoLib2026.json", + "name": "ChoreoLib", + "version": "2026.0.1", + "uuid": "b5e23f0a-dac9-4ad2-8dd6-02767c520aca", + "frcYear": "2026", + "mavenUrls": [ + "https://frcmaven.wpi.edu/artifactory/sleipnirgroup-mvn-release/", + "https://repo1.maven.org/maven2" + ], + "jsonUrl": "https://choreo.autos/lib/ChoreoLib2026.json", + "javaDependencies": [ + { + "groupId": "choreo", + "artifactId": "ChoreoLib-java", + "version": "2026.0.1" + }, + { + "groupId": "com.google.code.gson", + "artifactId": "gson", + "version": "2.11.0" + } + ], + "jniDependencies": [], + "cppDependencies": [ + { + "groupId": "choreo", + "artifactId": "ChoreoLib-cpp", + "version": "2026.0.1", + "libName": "ChoreoLib", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal", + "linuxathena", + "linuxarm32", + "linuxarm64" + ] + } + ] +} \ No newline at end of file diff --git a/vendordeps/Phoenix6-frc2025-latest.json b/vendordeps/Phoenix6-26.1.0.json similarity index 85% rename from vendordeps/Phoenix6-frc2025-latest.json rename to vendordeps/Phoenix6-26.1.0.json index 6f40c84..dc5dc62 100644 --- a/vendordeps/Phoenix6-frc2025-latest.json +++ b/vendordeps/Phoenix6-26.1.0.json @@ -1,32 +1,32 @@ { - "fileName": "Phoenix6-frc2025-latest.json", + "fileName": "Phoenix6-26.1.0.json", "name": "CTRE-Phoenix (v6)", - "version": "25.4.0", - "frcYear": "2025", + "version": "26.1.0", + "frcYear": "2026", "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", "mavenUrls": [ "https://maven.ctr-electronics.com/release/" ], - "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-latest.json", + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2026-latest.json", "conflictsWith": [ { "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af", "errorMessage": "Users can not have both the replay and regular Phoenix 6 vendordeps in their robot program.", - "offlineFileName": "Phoenix6-replay-frc2025-latest.json" + "offlineFileName": "Phoenix6-replay-frc2026-latest.json" } ], "javaDependencies": [ { "groupId": "com.ctre.phoenix6", "artifactId": "wpiapi-java", - "version": "25.4.0" + "version": "26.1.0" } ], "jniDependencies": [ { "groupId": "com.ctre.phoenix6", "artifactId": "api-cpp", - "version": "25.4.0", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -40,7 +40,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "tools", - "version": "25.4.0", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -54,7 +54,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "api-cpp-sim", - "version": "25.4.0", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -68,7 +68,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "tools-sim", - "version": "25.4.0", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -82,7 +82,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonSRX", - "version": "25.4.0", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -96,7 +96,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simVictorSPX", - "version": "25.4.0", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -110,21 +110,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simPigeonIMU", - "version": "25.4.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simCANCoder", - "version": "25.4.0", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -138,7 +124,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFX", - "version": "25.4.0", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -152,7 +138,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFXS", - "version": "25.4.0", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -166,7 +152,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANcoder", - "version": "25.4.0", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -180,7 +166,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProPigeon2", - "version": "25.4.0", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -194,7 +180,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANrange", - "version": "25.4.0", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -208,7 +194,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANdi", - "version": "25.4.0", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -222,7 +208,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANdle", - "version": "25.4.0", + "version": "26.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -238,7 +224,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "wpiapi-cpp", - "version": "25.4.0", + "version": "26.1.0", "libName": "CTRE_Phoenix6_WPI", "headerClassifier": "headers", "sharedLibrary": true, @@ -254,7 +240,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "tools", - "version": "25.4.0", + "version": "26.1.0", "libName": "CTRE_PhoenixTools", "headerClassifier": "headers", "sharedLibrary": true, @@ -270,7 +256,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "wpiapi-cpp-sim", - "version": "25.4.0", + "version": "26.1.0", "libName": "CTRE_Phoenix6_WPISim", "headerClassifier": "headers", "sharedLibrary": true, @@ -286,7 +272,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "tools-sim", - "version": "25.4.0", + "version": "26.1.0", "libName": "CTRE_PhoenixTools_Sim", "headerClassifier": "headers", "sharedLibrary": true, @@ -302,7 +288,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonSRX", - "version": "25.4.0", + "version": "26.1.0", "libName": "CTRE_SimTalonSRX", "headerClassifier": "headers", "sharedLibrary": true, @@ -318,7 +304,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simVictorSPX", - "version": "25.4.0", + "version": "26.1.0", "libName": "CTRE_SimVictorSPX", "headerClassifier": "headers", "sharedLibrary": true, @@ -334,7 +320,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simPigeonIMU", - "version": "25.4.0", + "version": "26.1.0", "libName": "CTRE_SimPigeonIMU", "headerClassifier": "headers", "sharedLibrary": true, @@ -347,26 +333,10 @@ ], "simMode": "swsim" }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simCANCoder", - "version": "25.4.0", - "libName": "CTRE_SimCANCoder", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFX", - "version": "25.4.0", + "version": "26.1.0", "libName": "CTRE_SimProTalonFX", "headerClassifier": "headers", "sharedLibrary": true, @@ -382,7 +352,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFXS", - "version": "25.4.0", + "version": "26.1.0", "libName": "CTRE_SimProTalonFXS", "headerClassifier": "headers", "sharedLibrary": true, @@ -398,7 +368,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANcoder", - "version": "25.4.0", + "version": "26.1.0", "libName": "CTRE_SimProCANcoder", "headerClassifier": "headers", "sharedLibrary": true, @@ -414,7 +384,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProPigeon2", - "version": "25.4.0", + "version": "26.1.0", "libName": "CTRE_SimProPigeon2", "headerClassifier": "headers", "sharedLibrary": true, @@ -430,7 +400,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANrange", - "version": "25.4.0", + "version": "26.1.0", "libName": "CTRE_SimProCANrange", "headerClassifier": "headers", "sharedLibrary": true, @@ -446,7 +416,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANdi", - "version": "25.4.0", + "version": "26.1.0", "libName": "CTRE_SimProCANdi", "headerClassifier": "headers", "sharedLibrary": true, @@ -462,7 +432,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANdle", - "version": "25.4.0", + "version": "26.1.0", "libName": "CTRE_SimProCANdle", "headerClassifier": "headers", "sharedLibrary": true, diff --git a/vendordeps/REVLib.json b/vendordeps/REVLib.json index ac62be8..d35e593 100644 --- a/vendordeps/REVLib.json +++ b/vendordeps/REVLib.json @@ -1,25 +1,55 @@ { "fileName": "REVLib.json", "name": "REVLib", - "version": "2025.0.3", - "frcYear": "2025", + "version": "2026.0.1", + "frcYear": "2026", "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", "mavenUrls": [ "https://maven.revrobotics.com/" ], - "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2025.json", + "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2026.json", "javaDependencies": [ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-java", - "version": "2025.0.3" + "version": "2026.0.1" } ], "jniDependencies": [ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2025.0.3", + "version": "2026.0.1", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "RevLibBackendDriver", + "version": "2026.0.1", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "RevLibWpiBackendDriver", + "version": "2026.0.1", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ @@ -36,7 +66,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-cpp", - "version": "2025.0.3", + "version": "2026.0.1", "libName": "REVLib", "headerClassifier": "headers", "sharedLibrary": false, @@ -53,7 +83,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2025.0.3", + "version": "2026.0.1", "libName": "REVLibDriver", "headerClassifier": "headers", "sharedLibrary": false, @@ -66,6 +96,38 @@ "linuxarm32", "osxuniversal" ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "RevLibBackendDriver", + "version": "2026.0.1", + "libName": "BackendDriver", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "RevLibWpiBackendDriver", + "version": "2026.0.1", + "libName": "REVLibWpi", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] } ] } \ No newline at end of file diff --git a/vendordeps/ReduxLib-2025.0.1.json b/vendordeps/ReduxLib-2026.1.1.json similarity index 75% rename from vendordeps/ReduxLib-2025.0.1.json rename to vendordeps/ReduxLib-2026.1.1.json index 6cc750e..09dd4f0 100644 --- a/vendordeps/ReduxLib-2025.0.1.json +++ b/vendordeps/ReduxLib-2026.1.1.json @@ -1,31 +1,30 @@ { - "fileName": "ReduxLib-2025.0.1.json", + "fileName": "ReduxLib-2026.1.1.json", "name": "ReduxLib", - "version": "2025.0.1", - "frcYear": "2025", + "version": "2026.1.1", + "frcYear": "2026", "uuid": "151ecca8-670b-4026-8160-cdd2679ef2bd", "mavenUrls": [ "https://maven.reduxrobotics.com/" ], - "jsonUrl": "https://frcsdk.reduxrobotics.com/ReduxLib_2025.json", + "jsonUrl": "https://frcsdk.reduxrobotics.com/ReduxLib_2026.json", "javaDependencies": [ { "groupId": "com.reduxrobotics.frc", "artifactId": "ReduxLib-java", - "version": "2025.0.1" + "version": "2026.1.1" } ], "jniDependencies": [ { "groupId": "com.reduxrobotics.frc", - "artifactId": "ReduxLib-driver", - "version": "2025.0.1", + "artifactId": "ReduxLib-fifo", + "version": "2026.1.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "linuxathena", "linuxx86-64", - "linuxarm32", "linuxarm64", "osxuniversal", "windowsx86-64" @@ -36,7 +35,7 @@ { "groupId": "com.reduxrobotics.frc", "artifactId": "ReduxLib-cpp", - "version": "2025.0.1", + "version": "2026.1.1", "libName": "ReduxLib", "headerClassifier": "headers", "sourcesClassifier": "sources", @@ -45,7 +44,6 @@ "binaryPlatforms": [ "linuxathena", "linuxx86-64", - "linuxarm32", "linuxarm64", "osxuniversal", "windowsx86-64" @@ -53,16 +51,15 @@ }, { "groupId": "com.reduxrobotics.frc", - "artifactId": "ReduxLib-driver", - "version": "2025.0.1", - "libName": "ReduxCore", + "artifactId": "ReduxLib-fifo", + "version": "2026.1.1", + "libName": "reduxfifo", "headerClassifier": "headers", "sharedLibrary": true, "skipInvalidPlatforms": true, "binaryPlatforms": [ "linuxathena", "linuxx86-64", - "linuxarm32", "linuxarm64", "osxuniversal", "windowsx86-64" diff --git a/vendordeps/Studica-2025.0.1.json b/vendordeps/Studica.json similarity index 71% rename from vendordeps/Studica-2025.0.1.json rename to vendordeps/Studica.json index 5010be0..b51bf58 100644 --- a/vendordeps/Studica-2025.0.1.json +++ b/vendordeps/Studica.json @@ -1,71 +1,71 @@ { - "fileName": "Studica-2025.0.1.json", + "fileName": "Studica.json", "name": "Studica", - "version": "2025.0.1", + "version": "2026.0.0", + "frcYear": "2026", "uuid": "cb311d09-36e9-4143-a032-55bb2b94443b", - "frcYear": "2025", "mavenUrls": [ - "https://dev.studica.com/maven/release/2025/" + "https://dev.studica.com/maven/release/2026/" ], - "jsonUrl": "https://dev.studica.com/releases/2025/Studica-2025.0.1.json", - "cppDependencies": [ + "jsonUrl": "https://dev.studica.com/maven/release/2026/json/Studica-2026.0.0.json", + "javaDependencies": [ { - "artifactId": "Studica-cpp", - "binaryPlatforms": [ - "linuxathena", - "linuxarm32", - "linuxarm64", - "linuxx86-64", - "osxuniversal", - "windowsx86-64" - ], "groupId": "com.studica.frc", - "headerClassifier": "headers", - "libName": "Studica", - "sharedLibrary": false, - "skipInvalidPlatforms": true, - "version": "2025.0.1" - }, + "artifactId": "Studica-java", + "version": "2026.0.0" + } + ], + "jniDependencies": [ { + "groupId": "com.studica.frc", "artifactId": "Studica-driver", - "binaryPlatforms": [ - "linuxathena", - "linuxarm32", + "version": "2026.0.0", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", "linuxarm64", "linuxx86-64", - "osxuniversal", - "windowsx86-64" - ], + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ], + "cppDependencies": [ + { "groupId": "com.studica.frc", + "artifactId": "Studica-cpp", + "version": "2026.0.0", + "libName": "Studica", "headerClassifier": "headers", - "libName": "StudicaDriver", "sharedLibrary": false, "skipInvalidPlatforms": true, - "version": "2025.0.1" - } - ], - "javaDependencies": [ + "binaryPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, { - "artifactId": "Studica-java", "groupId": "com.studica.frc", - "version": "2025.0.1" - } - ], - "jniDependencies": [ - { "artifactId": "Studica-driver", - "groupId": "com.studica.frc", - "isJar": false, + "version": "2026.0.0", + "libName": "StudicaDriver", + "headerClassifier": "headers", + "sharedLibrary": false, "skipInvalidPlatforms": true, - "validPlatforms": [ - "linuxathena", - "linuxarm32", + "binaryPlatforms": [ + "windowsx86-64", "linuxarm64", "linuxx86-64", - "osxuniversal", - "windowsx86-64" - ], - "version": "2025.0.1" + "linuxathena", + "linuxarm32", + "osxuniversal" + ] } ] } \ No newline at end of file diff --git a/vendordeps/WPILibNewCommands.json b/vendordeps/WPILibNewCommands.json index 3718e0a..d90630e 100644 --- a/vendordeps/WPILibNewCommands.json +++ b/vendordeps/WPILibNewCommands.json @@ -3,7 +3,7 @@ "name": "WPILib-New-Commands", "version": "1.0.0", "uuid": "111e20f7-815e-48f8-9dd6-e675ce75b266", - "frcYear": "2025", + "frcYear": "2026", "mavenUrls": [], "jsonUrl": "", "javaDependencies": [ @@ -25,6 +25,7 @@ "sharedLibrary": true, "skipInvalidPlatforms": true, "binaryPlatforms": [ + "linuxsystemcore", "linuxathena", "linuxarm32", "linuxarm64", diff --git a/vendordeps/maple-sim.json b/vendordeps/maple-sim.json deleted file mode 100644 index 73c812f..0000000 --- a/vendordeps/maple-sim.json +++ /dev/null @@ -1,26 +0,0 @@ -{ - "fileName": "maple-sim.json", - "name": "maplesim", - "version": "0.3.14", - "frcYear": "2025", - "uuid": "c39481e8-4a63-4a4c-9df6-48d91e4da37b", - "mavenUrls": [ - "https://shenzhen-robotics-alliance.github.io/maple-sim/vendordep/repos/releases", - "https://repo1.maven.org/maven2" - ], - "jsonUrl": "https://shenzhen-robotics-alliance.github.io/maple-sim/vendordep/maple-sim.json", - "javaDependencies": [ - { - "groupId": "org.ironmaple", - "artifactId": "maplesim-java", - "version": "0.3.14" - }, - { - "groupId": "org.dyn4j", - "artifactId": "dyn4j", - "version": "5.0.2" - } - ], - "jniDependencies": [], - "cppDependencies": [] -} \ No newline at end of file diff --git a/vendordeps/photonlib.json b/vendordeps/photonlib.json index 5c6484d..db230c7 100644 --- a/vendordeps/photonlib.json +++ b/vendordeps/photonlib.json @@ -1,9 +1,9 @@ { "fileName": "photonlib.json", "name": "photonlib", - "version": "v2025.3.1", + "version": "v2026.1.1-rc-3", "uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004", - "frcYear": "2025", + "frcYear": "2026", "mavenUrls": [ "https://maven.photonvision.org/repository/internal", "https://maven.photonvision.org/repository/snapshots" @@ -13,7 +13,7 @@ { "groupId": "org.photonvision", "artifactId": "photontargeting-cpp", - "version": "v2025.3.1", + "version": "v2026.1.1-rc-3", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ @@ -28,7 +28,7 @@ { "groupId": "org.photonvision", "artifactId": "photonlib-cpp", - "version": "v2025.3.1", + "version": "v2026.1.1-rc-3", "libName": "photonlib", "headerClassifier": "headers", "sharedLibrary": true, @@ -43,7 +43,7 @@ { "groupId": "org.photonvision", "artifactId": "photontargeting-cpp", - "version": "v2025.3.1", + "version": "v2026.1.1-rc-3", "libName": "photontargeting", "headerClassifier": "headers", "sharedLibrary": true, @@ -60,12 +60,12 @@ { "groupId": "org.photonvision", "artifactId": "photonlib-java", - "version": "v2025.3.1" + "version": "v2026.1.1-rc-3" }, { "groupId": "org.photonvision", "artifactId": "photontargeting-java", - "version": "v2025.3.1" + "version": "v2026.1.1-rc-3" } ] } \ No newline at end of file