diff --git a/build.gradle b/build.gradle index d236403..9b2c774 100644 --- a/build.gradle +++ b/build.gradle @@ -12,7 +12,7 @@ allprojects { // Set this to the latest version of StuyLib. // You can check here: https://github.com/StuyPulse/StuyLib/releases. -final String STUYLIB_VERSION = 'v2025.1.1' +final String STUYLIB_VERSION = 'v2025.1.2' def ROBOT_MAIN_CLASS = "com.stuypulse.robot.Main" diff --git a/src/main/java/com/stuypulse/robot/constants/Motors.java b/src/main/java/com/stuypulse/robot/constants/Motors.java index bc883b3..f9d39dd 100644 --- a/src/main/java/com/stuypulse/robot/constants/Motors.java +++ b/src/main/java/com/stuypulse/robot/constants/Motors.java @@ -5,9 +5,21 @@ package com.stuypulse.robot.constants; -import com.ctre.phoenix.motorcontrol.NeutralMode; -import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX; -import com.ctre.phoenix.motorcontrol.can.WPI_VictorSPX; +import com.ctre.phoenix6.configs.ClosedLoopRampsConfigs; +import com.ctre.phoenix6.configs.CurrentLimitsConfigs; +import com.ctre.phoenix6.configs.FeedbackConfigs; +import com.ctre.phoenix6.configs.MotionMagicConfigs; +import com.ctre.phoenix6.configs.MotorOutputConfigs; +import com.ctre.phoenix6.configs.OpenLoopRampsConfigs; +import com.ctre.phoenix6.configs.Slot0Configs; +import com.ctre.phoenix6.configs.Slot1Configs; +import com.ctre.phoenix6.configs.Slot2Configs; +import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.hardware.TalonFX; +import com.ctre.phoenix6.signals.FeedbackSensorSourceValue; +import com.ctre.phoenix6.signals.GravityTypeValue; +import com.ctre.phoenix6.signals.InvertedValue; +import com.ctre.phoenix6.signals.NeutralModeValue; /*- * File containing all of the configurations that different motors require. @@ -22,64 +34,176 @@ public interface Motors { /** Classes to store all of the values a motor needs */ - public static class TalonSRXConfig { - public final boolean INVERTED; - public final NeutralMode NEUTRAL_MODE; - public final int PEAK_CURRENT_LIMIT_AMPS; - public final double OPEN_LOOP_RAMP_RATE; - - public TalonSRXConfig( - boolean inverted, - NeutralMode neutralMode, - int peakCurrentLimitAmps, - double openLoopRampRate) { - this.INVERTED = inverted; - this.NEUTRAL_MODE = neutralMode; - this.PEAK_CURRENT_LIMIT_AMPS = peakCurrentLimitAmps; - this.OPEN_LOOP_RAMP_RATE = openLoopRampRate; + public static class TalonFXConfig { + private final TalonFXConfiguration configuration = new TalonFXConfiguration(); + private final Slot0Configs slot0Configs = new Slot0Configs(); + private final Slot1Configs slot1Configs = new Slot1Configs(); + private final Slot2Configs slot2Configs = new Slot2Configs(); + private final MotorOutputConfigs motorOutputConfigs = new MotorOutputConfigs(); + private final ClosedLoopRampsConfigs closedLoopRampsConfigs = new ClosedLoopRampsConfigs(); + private final OpenLoopRampsConfigs openLoopRampsConfigs = new OpenLoopRampsConfigs(); + private final CurrentLimitsConfigs currentLimitsConfigs = new CurrentLimitsConfigs(); + private final FeedbackConfigs feedbackConfigs = new FeedbackConfigs(); + private final MotionMagicConfigs motionMagicConfigs = new MotionMagicConfigs(); + + public void configure(TalonFX motor) { + motor.getConfigurator().apply(configuration); } - public TalonSRXConfig(boolean inverted, NeutralMode neutralMode, int peakCurrentLimitAmps) { - this(inverted, neutralMode, peakCurrentLimitAmps, 0.0); + // SLOT 0 CONFIGS + + public TalonFXConfig withPIDConstants(double kP, double kI, double kD, int slot) { + switch (slot) { + case 0: + slot0Configs.kP = kP; + slot0Configs.kI = kI; + slot0Configs.kD = kD; + configuration.withSlot0(slot0Configs); + break; + case 1: + slot1Configs.kP = kP; + slot1Configs.kI = kI; + slot1Configs.kD = kD; + configuration.withSlot1(slot1Configs); + break; + case 2: + slot2Configs.kP = kP; + slot2Configs.kI = kI; + slot2Configs.kD = kD; + configuration.withSlot2(slot2Configs); + break; + } + return this; } - public TalonSRXConfig(boolean inverted, NeutralMode neutralMode) { - this(inverted, neutralMode, 80); + public TalonFXConfig withFFConstants(double kS, double kV, double kA, int slot) { + return withFFConstants(kS, kV, kA, 0, slot); } - public void configure(WPI_TalonSRX motor) { - motor.setInverted(INVERTED); - motor.setNeutralMode(NEUTRAL_MODE); - motor.configContinuousCurrentLimit(PEAK_CURRENT_LIMIT_AMPS - 10, 0); - motor.configPeakCurrentLimit(PEAK_CURRENT_LIMIT_AMPS, 0); - motor.configPeakCurrentDuration(100, 0); - motor.enableCurrentLimit(true); - motor.configOpenloopRamp(OPEN_LOOP_RAMP_RATE); + public TalonFXConfig withFFConstants(double kS, double kV, double kA, double kG, int slot) { + switch (slot) { + case 0: + slot0Configs.kS = kS; + slot0Configs.kV = kV; + slot0Configs.kA = kA; + slot0Configs.kG = kG; + configuration.withSlot0(slot0Configs); + break; + case 1: + slot1Configs.kS = kS; + slot1Configs.kV = kV; + slot1Configs.kA = kA; + slot1Configs.kG = kG; + configuration.withSlot1(slot1Configs); + break; + case 2: + slot2Configs.kS = kS; + slot2Configs.kV = kV; + slot2Configs.kA = kA; + slot2Configs.kG = kG; + configuration.withSlot2(slot2Configs); + break; + } + return this; } - } - public static class VictorSPXConfig { - public final boolean INVERTED; - public final NeutralMode NEUTRAL_MODE; - public final double OPEN_LOOP_RAMP_RATE; - - public VictorSPXConfig( - boolean inverted, - NeutralMode neutralMode, - double openLoopRampRate) { - this.INVERTED = inverted; - this.NEUTRAL_MODE = neutralMode; - this.OPEN_LOOP_RAMP_RATE = openLoopRampRate; + public TalonFXConfig withGravityType(GravityTypeValue gravityType) { + slot0Configs.GravityType = gravityType; + slot1Configs.GravityType = gravityType; + slot2Configs.GravityType = gravityType; + + configuration.withSlot0(slot0Configs); + configuration.withSlot1(slot1Configs); + configuration.withSlot2(slot2Configs); + + return this; + } + + // MOTOR OUTPUT CONFIGS + + public TalonFXConfig withInvertedValue(InvertedValue invertedValue) { + motorOutputConfigs.Inverted = invertedValue; + + configuration.withMotorOutput(motorOutputConfigs); + + return this; } - public VictorSPXConfig(boolean inverted, NeutralMode neutralMode) { - this(inverted, neutralMode, 0.0); + public TalonFXConfig withNeutralMode(NeutralModeValue neutralMode) { + motorOutputConfigs.NeutralMode = neutralMode; + + configuration.withMotorOutput(motorOutputConfigs); + + return this; + } + + // RAMP RATE CONFIGS + + public TalonFXConfig withRampRate(double rampRate) { + closedLoopRampsConfigs.DutyCycleClosedLoopRampPeriod = rampRate; + closedLoopRampsConfigs.TorqueClosedLoopRampPeriod = rampRate; + closedLoopRampsConfigs.VoltageClosedLoopRampPeriod = rampRate; + + openLoopRampsConfigs.DutyCycleOpenLoopRampPeriod = rampRate; + openLoopRampsConfigs.TorqueOpenLoopRampPeriod = rampRate; + openLoopRampsConfigs.VoltageOpenLoopRampPeriod = rampRate; + + configuration.withClosedLoopRamps(closedLoopRampsConfigs); + configuration.withOpenLoopRamps(openLoopRampsConfigs); + + return this; } - public void configure(WPI_VictorSPX motor) { - motor.setInverted(INVERTED); - motor.setNeutralMode(NEUTRAL_MODE); - motor.configOpenloopRamp(OPEN_LOOP_RAMP_RATE); + // CURRENT LIMIT CONFIGS + + public TalonFXConfig withCurrentLimitAmps(double currentLimitAmps) { + currentLimitsConfigs.StatorCurrentLimit = currentLimitAmps; + currentLimitsConfigs.StatorCurrentLimitEnable = true; + + configuration.withCurrentLimits(currentLimitsConfigs); + + return this; + } + + public TalonFXConfig withSupplyCurrentLimitAmps(double currentLimitAmps) { + currentLimitsConfigs.SupplyCurrentLimit = currentLimitAmps; + currentLimitsConfigs.SupplyCurrentLimitEnable = true; + + configuration.withCurrentLimits(currentLimitsConfigs); + + return this; + } + + // MOTION MAGIC CONFIGS + + public TalonFXConfig withMotionProfile(double maxVelocity, double maxAcceleration) { + motionMagicConfigs.MotionMagicCruiseVelocity = maxVelocity; + motionMagicConfigs.MotionMagicAcceleration = maxAcceleration; + + configuration.withMotionMagic(motionMagicConfigs); + + return this; + } + + // FEEDBACK CONFIGS + + public TalonFXConfig withRemoteSensor( + int ID, FeedbackSensorSourceValue source, double rotorToSensorRatio) { + feedbackConfigs.FeedbackRemoteSensorID = ID; + feedbackConfigs.FeedbackSensorSource = source; + feedbackConfigs.RotorToSensorRatio = rotorToSensorRatio; + + configuration.withFeedback(feedbackConfigs); + + return this; + } + + public TalonFXConfig withSensorToMechanismRatio(double sensorToMechanismRatio) { + feedbackConfigs.SensorToMechanismRatio = sensorToMechanismRatio; + + configuration.withFeedback(feedbackConfigs); + + return this; } } } diff --git a/vendordeps/PathplannerLib.json b/vendordeps/PathplannerLib-2025.2.7.json similarity index 87% rename from vendordeps/PathplannerLib.json rename to vendordeps/PathplannerLib-2025.2.7.json index 396f92d..d3f84e5 100644 --- a/vendordeps/PathplannerLib.json +++ b/vendordeps/PathplannerLib-2025.2.7.json @@ -1,7 +1,7 @@ { - "fileName": "PathplannerLib.json", + "fileName": "PathplannerLib-2025.2.7.json", "name": "PathplannerLib", - "version": "2025.1.1", + "version": "2025.2.7", "uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786", "frcYear": "2025", "mavenUrls": [ @@ -12,7 +12,7 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-java", - "version": "2025.1.1" + "version": "2025.2.7" } ], "jniDependencies": [], @@ -20,7 +20,7 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-cpp", - "version": "2025.1.1", + "version": "2025.2.7", "libName": "PathplannerLib", "headerClassifier": "headers", "sharedLibrary": false, diff --git a/vendordeps/Phoenix5.json b/vendordeps/Phoenix5-5.35.1.json similarity index 92% rename from vendordeps/Phoenix5.json rename to vendordeps/Phoenix5-5.35.1.json index 0ab6d7c..69df8b5 100644 --- a/vendordeps/Phoenix5.json +++ b/vendordeps/Phoenix5-5.35.1.json @@ -1,7 +1,7 @@ { - "fileName": "Phoenix5-frc2025-latest.json", + "fileName": "Phoenix5-5.35.1.json", "name": "CTRE-Phoenix (v5)", - "version": "5.35.0", + "version": "5.35.1", "frcYear": "2025", "uuid": "ab676553-b602-441f-a38d-f1296eff6537", "mavenUrls": [ @@ -32,19 +32,19 @@ { "groupId": "com.ctre.phoenix", "artifactId": "api-java", - "version": "5.35.0" + "version": "5.35.1" }, { "groupId": "com.ctre.phoenix", "artifactId": "wpiapi-java", - "version": "5.35.0" + "version": "5.35.1" } ], "jniDependencies": [ { "groupId": "com.ctre.phoenix", "artifactId": "cci", - "version": "5.35.0", + "version": "5.35.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -58,7 +58,7 @@ { "groupId": "com.ctre.phoenix.sim", "artifactId": "cci-sim", - "version": "5.35.0", + "version": "5.35.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -74,7 +74,7 @@ { "groupId": "com.ctre.phoenix", "artifactId": "wpiapi-cpp", - "version": "5.35.0", + "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.35.0", + "version": "5.35.1", "libName": "CTRE_Phoenix", "headerClassifier": "headers", "sharedLibrary": true, @@ -106,7 +106,7 @@ { "groupId": "com.ctre.phoenix", "artifactId": "cci", - "version": "5.35.0", + "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.35.0", + "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.35.0", + "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.35.0", + "version": "5.35.1", "libName": "CTRE_PhoenixCCISim", "headerClassifier": "headers", "sharedLibrary": true, diff --git a/vendordeps/Phoenix6.json b/vendordeps/Phoenix6-frc2025-latest.json similarity index 75% rename from vendordeps/Phoenix6.json rename to vendordeps/Phoenix6-frc2025-latest.json index 7f4bd2e..6f40c84 100644 --- a/vendordeps/Phoenix6.json +++ b/vendordeps/Phoenix6-frc2025-latest.json @@ -1,7 +1,7 @@ { "fileName": "Phoenix6-frc2025-latest.json", "name": "CTRE-Phoenix (v6)", - "version": "25.1.0", + "version": "25.4.0", "frcYear": "2025", "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", "mavenUrls": [ @@ -19,14 +19,14 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "wpiapi-java", - "version": "25.1.0" + "version": "25.4.0" } ], "jniDependencies": [ { "groupId": "com.ctre.phoenix6", "artifactId": "api-cpp", - "version": "25.1.0", + "version": "25.4.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -40,7 +40,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "tools", - "version": "25.1.0", + "version": "25.4.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -54,7 +54,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "api-cpp-sim", - "version": "25.1.0", + "version": "25.4.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -68,7 +68,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "tools-sim", - "version": "25.1.0", + "version": "25.4.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -82,7 +82,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonSRX", - "version": "25.1.0", + "version": "25.4.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -96,7 +96,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simVictorSPX", - "version": "25.1.0", + "version": "25.4.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -110,7 +110,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simPigeonIMU", - "version": "25.1.0", + "version": "25.4.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -124,7 +124,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simCANCoder", - "version": "25.1.0", + "version": "25.4.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -138,7 +138,21 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFX", - "version": "25.1.0", + "version": "25.4.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFXS", + "version": "25.4.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -152,7 +166,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANcoder", - "version": "25.1.0", + "version": "25.4.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -166,7 +180,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProPigeon2", - "version": "25.1.0", + "version": "25.4.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -180,7 +194,35 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANrange", - "version": "25.1.0", + "version": "25.4.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANdi", + "version": "25.4.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANdle", + "version": "25.4.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -196,7 +238,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "wpiapi-cpp", - "version": "25.1.0", + "version": "25.4.0", "libName": "CTRE_Phoenix6_WPI", "headerClassifier": "headers", "sharedLibrary": true, @@ -212,7 +254,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "tools", - "version": "25.1.0", + "version": "25.4.0", "libName": "CTRE_PhoenixTools", "headerClassifier": "headers", "sharedLibrary": true, @@ -228,7 +270,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "wpiapi-cpp-sim", - "version": "25.1.0", + "version": "25.4.0", "libName": "CTRE_Phoenix6_WPISim", "headerClassifier": "headers", "sharedLibrary": true, @@ -244,7 +286,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "tools-sim", - "version": "25.1.0", + "version": "25.4.0", "libName": "CTRE_PhoenixTools_Sim", "headerClassifier": "headers", "sharedLibrary": true, @@ -260,7 +302,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonSRX", - "version": "25.1.0", + "version": "25.4.0", "libName": "CTRE_SimTalonSRX", "headerClassifier": "headers", "sharedLibrary": true, @@ -276,7 +318,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simVictorSPX", - "version": "25.1.0", + "version": "25.4.0", "libName": "CTRE_SimVictorSPX", "headerClassifier": "headers", "sharedLibrary": true, @@ -292,7 +334,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simPigeonIMU", - "version": "25.1.0", + "version": "25.4.0", "libName": "CTRE_SimPigeonIMU", "headerClassifier": "headers", "sharedLibrary": true, @@ -308,7 +350,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simCANCoder", - "version": "25.1.0", + "version": "25.4.0", "libName": "CTRE_SimCANCoder", "headerClassifier": "headers", "sharedLibrary": true, @@ -324,7 +366,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFX", - "version": "25.1.0", + "version": "25.4.0", "libName": "CTRE_SimProTalonFX", "headerClassifier": "headers", "sharedLibrary": true, @@ -337,10 +379,26 @@ ], "simMode": "swsim" }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFXS", + "version": "25.4.0", + "libName": "CTRE_SimProTalonFXS", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANcoder", - "version": "25.1.0", + "version": "25.4.0", "libName": "CTRE_SimProCANcoder", "headerClassifier": "headers", "sharedLibrary": true, @@ -356,7 +414,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProPigeon2", - "version": "25.1.0", + "version": "25.4.0", "libName": "CTRE_SimProPigeon2", "headerClassifier": "headers", "sharedLibrary": true, @@ -372,7 +430,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANrange", - "version": "25.1.0", + "version": "25.4.0", "libName": "CTRE_SimProCANrange", "headerClassifier": "headers", "sharedLibrary": true, @@ -384,6 +442,38 @@ "osxuniversal" ], "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANdi", + "version": "25.4.0", + "libName": "CTRE_SimProCANdi", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANdle", + "version": "25.4.0", + "libName": "CTRE_SimProCANdle", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" } ] } \ No newline at end of file diff --git a/vendordeps/REVLib.json b/vendordeps/REVLib.json index 2c39628..ac62be8 100644 --- a/vendordeps/REVLib.json +++ b/vendordeps/REVLib.json @@ -1,7 +1,7 @@ { "fileName": "REVLib.json", "name": "REVLib", - "version": "2025.0.0", + "version": "2025.0.3", "frcYear": "2025", "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", "mavenUrls": [ @@ -12,19 +12,18 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-java", - "version": "2025.0.0" + "version": "2025.0.3" } ], "jniDependencies": [ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2025.0.0", + "version": "2025.0.3", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ "windowsx86-64", - "windowsx86", "linuxarm64", "linuxx86-64", "linuxathena", @@ -37,14 +36,13 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-cpp", - "version": "2025.0.0", + "version": "2025.0.3", "libName": "REVLib", "headerClassifier": "headers", "sharedLibrary": false, "skipInvalidPlatforms": true, "binaryPlatforms": [ "windowsx86-64", - "windowsx86", "linuxarm64", "linuxx86-64", "linuxathena", @@ -55,14 +53,13 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2025.0.0", + "version": "2025.0.3", "libName": "REVLibDriver", "headerClassifier": "headers", "sharedLibrary": false, "skipInvalidPlatforms": true, "binaryPlatforms": [ "windowsx86-64", - "windowsx86", "linuxarm64", "linuxx86-64", "linuxathena", diff --git a/vendordeps/photonlib.json b/vendordeps/photonlib.json index 039d0a5..2d7b1d8 100644 --- a/vendordeps/photonlib.json +++ b/vendordeps/photonlib.json @@ -1,71 +1,71 @@ { "fileName": "photonlib.json", "name": "photonlib", - "version": "v2025.0.0-beta-8", + "version": "v2025.3.1", "uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004", "frcYear": "2025", "mavenUrls": [ - "https://maven.photonvision.org/repository/internal", - "https://maven.photonvision.org/repository/snapshots" + "https://maven.photonvision.org/repository/internal", + "https://maven.photonvision.org/repository/snapshots" ], "jsonUrl": "https://maven.photonvision.org/repository/internal/org/photonvision/photonlib-json/1.0/photonlib-json-1.0.json", "jniDependencies": [ - { - "groupId": "org.photonvision", - "artifactId": "photontargeting-cpp", - "version": "v2025.0.0-beta-8", - "skipInvalidPlatforms": true, - "isJar": false, - "validPlatforms": [ - "windowsx86-64", - "linuxathena", - "linuxx86-64", - "osxuniversal" - ] - } + { + "groupId": "org.photonvision", + "artifactId": "photontargeting-cpp", + "version": "v2025.3.1", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "linuxathena", + "linuxx86-64", + "osxuniversal" + ] + } ], "cppDependencies": [ - { - "groupId": "org.photonvision", - "artifactId": "photonlib-cpp", - "version": "v2025.0.0-beta-8", - "libName": "photonlib", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxathena", - "linuxx86-64", - "osxuniversal" - ] - }, - { - "groupId": "org.photonvision", - "artifactId": "photontargeting-cpp", - "version": "v2025.0.0-beta-8", - "libName": "photontargeting", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxathena", - "linuxx86-64", - "osxuniversal" - ] - } + { + "groupId": "org.photonvision", + "artifactId": "photonlib-cpp", + "version": "v2025.3.1", + "libName": "photonlib", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxathena", + "linuxx86-64", + "osxuniversal" + ] + }, + { + "groupId": "org.photonvision", + "artifactId": "photontargeting-cpp", + "version": "v2025.3.1", + "libName": "photontargeting", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxathena", + "linuxx86-64", + "osxuniversal" + ] + } ], "javaDependencies": [ - { - "groupId": "org.photonvision", - "artifactId": "photonlib-java", - "version": "v2025.0.0-beta-8" - }, - { - "groupId": "org.photonvision", - "artifactId": "photontargeting-java", - "version": "v2025.0.0-beta-8" - } + { + "groupId": "org.photonvision", + "artifactId": "photonlib-java", + "version": "v2025.3.1" + }, + { + "groupId": "org.photonvision", + "artifactId": "photontargeting-java", + "version": "v2025.3.1" + } ] - } \ No newline at end of file +} \ No newline at end of file