diff --git a/WPILib-License.md b/WPILib-License.md index 43b62ec2..645e5425 100644 --- a/WPILib-License.md +++ b/WPILib-License.md @@ -1,4 +1,4 @@ -Copyright (c) 2009-2023 FIRST and other WPILib contributors +Copyright (c) 2009-2024 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 1481bab4..67f117ba 100644 --- a/build.gradle +++ b/build.gradle @@ -1,6 +1,6 @@ plugins { id "java" - id "edu.wpi.first.GradleRIO" version "2024.3.1" + id "edu.wpi.first.GradleRIO" version "2025.2.1" id "maven-publish" id "eclipse" } @@ -11,7 +11,6 @@ java { } group 'org.carlmontrobotics' - def ROBOT_MAIN_CLASS = "" // Define my targets (RoboRIO) and artifacts (deployable files) @@ -37,6 +36,8 @@ deploy { frcStaticFileDeploy(getArtifactTypeClass('FileTreeArtifact')) { files = project.fileTree('src/main/deploy') directory = '/home/lvuser/deploy' + deleteOldFiles = false // Change to true to delete files on roboRIO that no + // longer exist in deploy directory of this project } } } @@ -54,6 +55,7 @@ def includeDesktopSupport = true // Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries. // Also defines JUnit 5. dependencies { + annotationProcessor wpi.java.deps.wpilibAnnotations() implementation wpi.java.deps.wpilib() implementation wpi.java.vendor.java() @@ -71,17 +73,23 @@ dependencies { nativeRelease wpi.java.vendor.jniRelease(wpi.platforms.desktop) simulationRelease wpi.sim.enableRelease() - testImplementation 'junit:junit:4.13.2' + testImplementation 'org.junit.jupiter:junit-jupiter:5.10.1' + testRuntimeOnly 'org.junit.platform:junit-platform-launcher' implementation 'org.mockito:mockito-core:5.11.0' implementation group: 'org.apache.commons', name: 'commons-csv', version: '1.6' } +test { + useJUnitPlatform() + systemProperty 'junit.jupiter.extensions.autodetection.enabled', 'true' +} + // Simulation configuration (e.g. environment variables). wpi.sim.addGui().defaultEnabled = true wpi.sim.addDriverstation() -// Setting up my Jar File. +// Setting up my Jar File. jar { // Note: Do NOT add all the libraries to the jar. Doing so will cause robot programs to have // 2 copies of each of the libraries classes, one from lib199 and one from the robot program. @@ -111,11 +119,6 @@ deployArtifact.jarTask = jar wpi.java.configureExecutableTasks(jar) wpi.java.configureTestTasks(test) -// Configure string concat to always inline compile -tasks.withType(JavaCompile) { - options.compilerArgs.add '-XDstringConcat=inline' -} - // Allow the generated javadocs to link to the documentation of WPILib and vendor libraries javadoc { options.with { @@ -129,3 +132,7 @@ javadoc { } } +// Configure string concat to always inline compile +tasks.withType(JavaCompile) { + options.compilerArgs.add '-XDstringConcat=inline' +} diff --git a/gradle/wrapper/gradle-wrapper.jar b/gradle/wrapper/gradle-wrapper.jar index d64cd491..a4b76b95 100644 Binary files a/gradle/wrapper/gradle-wrapper.jar and b/gradle/wrapper/gradle-wrapper.jar differ diff --git a/gradle/wrapper/gradle-wrapper.properties b/gradle/wrapper/gradle-wrapper.properties index 5e82d67b..34bd9ce9 100644 --- a/gradle/wrapper/gradle-wrapper.properties +++ b/gradle/wrapper/gradle-wrapper.properties @@ -1,6 +1,6 @@ distributionBase=GRADLE_USER_HOME distributionPath=permwrapper/dists -distributionUrl=https\://services.gradle.org/distributions/gradle-8.5-bin.zip +distributionUrl=https\://services.gradle.org/distributions/gradle-8.11-bin.zip networkTimeout=10000 validateDistributionUrl=true zipStoreBase=GRADLE_USER_HOME diff --git a/gradlew b/gradlew index 1aa94a42..f5feea6d 100755 --- a/gradlew +++ b/gradlew @@ -15,6 +15,8 @@ # See the License for the specific language governing permissions and # limitations under the License. # +# SPDX-License-Identifier: Apache-2.0 +# ############################################################################## # @@ -55,7 +57,7 @@ # Darwin, MinGW, and NonStop. # # (3) This script is generated from the Groovy template -# https://github.com/gradle/gradle/blob/HEAD/subprojects/plugins/src/main/resources/org/gradle/api/internal/plugins/unixStartScript.txt +# https://github.com/gradle/gradle/blob/HEAD/platforms/jvm/plugins-application/src/main/resources/org/gradle/api/internal/plugins/unixStartScript.txt # within the Gradle project. # # You can find Gradle at https://github.com/gradle/gradle/. @@ -84,7 +86,8 @@ done # shellcheck disable=SC2034 APP_BASE_NAME=${0##*/} # Discard cd standard output in case $CDPATH is set (https://github.com/gradle/gradle/issues/25036) -APP_HOME=$( cd "${APP_HOME:-./}" > /dev/null && pwd -P ) || exit +APP_HOME=$( cd -P "${APP_HOME:-./}" > /dev/null && printf '%s +' "$PWD" ) || exit # Use the maximum available, or set MAX_FD != -1 to use that value. MAX_FD=maximum diff --git a/gradlew.bat b/gradlew.bat index 93e3f59f..9d21a218 100644 --- a/gradlew.bat +++ b/gradlew.bat @@ -13,6 +13,8 @@ @rem See the License for the specific language governing permissions and @rem limitations under the License. @rem +@rem SPDX-License-Identifier: Apache-2.0 +@rem @if "%DEBUG%"=="" @echo off @rem ########################################################################## @@ -43,11 +45,11 @@ set JAVA_EXE=java.exe %JAVA_EXE% -version >NUL 2>&1 if %ERRORLEVEL% equ 0 goto execute -echo. -echo ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. -echo. -echo Please set the JAVA_HOME variable in your environment to match the -echo location of your Java installation. +echo. 1>&2 +echo ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. 1>&2 +echo. 1>&2 +echo Please set the JAVA_HOME variable in your environment to match the 1>&2 +echo location of your Java installation. 1>&2 goto fail @@ -57,11 +59,11 @@ set JAVA_EXE=%JAVA_HOME%/bin/java.exe if exist "%JAVA_EXE%" goto execute -echo. -echo ERROR: JAVA_HOME is set to an invalid directory: %JAVA_HOME% -echo. -echo Please set the JAVA_HOME variable in your environment to match the -echo location of your Java installation. +echo. 1>&2 +echo ERROR: JAVA_HOME is set to an invalid directory: %JAVA_HOME% 1>&2 +echo. 1>&2 +echo Please set the JAVA_HOME variable in your environment to match the 1>&2 +echo location of your Java installation. 1>&2 goto fail diff --git a/settings.gradle b/settings.gradle index d94f73c6..c493958a 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') @@ -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/org/carlmontrobotics/lib199/CachedSparkMax.java b/src/main/java/org/carlmontrobotics/lib199/CachedSparkMax.java deleted file mode 100644 index 34a090ae..00000000 --- a/src/main/java/org/carlmontrobotics/lib199/CachedSparkMax.java +++ /dev/null @@ -1,29 +0,0 @@ -package org.carlmontrobotics.lib199; - -import com.revrobotics.CANSparkMax; -import com.revrobotics.RelativeEncoder; -import com.revrobotics.SparkPIDController; - -@Deprecated -public class CachedSparkMax extends CANSparkMax { - - private RelativeEncoder encoder; - private SparkPIDController pidController; - - public CachedSparkMax(int deviceId, MotorType type) { - super(deviceId, type); - this.encoder = null; - this.pidController = null; - } - - @Override - public RelativeEncoder getEncoder() { - return encoder == null ? (encoder = super.getEncoder()) : encoder; - } - - @Override - public SparkPIDController getPIDController() { - return pidController == null ? (pidController = super.getPIDController()) : pidController; - } - -} diff --git a/src/main/java/org/carlmontrobotics/lib199/DummySparkMaxAnswer.java b/src/main/java/org/carlmontrobotics/lib199/DummySparkMaxAnswer.java deleted file mode 100644 index d3fd177a..00000000 --- a/src/main/java/org/carlmontrobotics/lib199/DummySparkMaxAnswer.java +++ /dev/null @@ -1,53 +0,0 @@ -package org.carlmontrobotics.lib199; - -import com.revrobotics.CANSparkMax; -import com.revrobotics.RelativeEncoder; -import com.revrobotics.SparkAbsoluteEncoder; -import com.revrobotics.SparkAnalogSensor; -import com.revrobotics.SparkLimitSwitch; -import com.revrobotics.SparkPIDController; -import com.revrobotics.CANSparkBase.IdleMode; -import com.revrobotics.CANSparkLowLevel.MotorType; -import com.revrobotics.SparkPIDController.AccelStrategy; - -import org.mockito.invocation.InvocationOnMock; - -public class DummySparkMaxAnswer extends REVLibErrorAnswer { - - private static final long serialVersionUID = 2284848703213263465L; - - public static final DummySparkMaxAnswer ANSWER = new DummySparkMaxAnswer(); - - public static final CANSparkMax DUMMY_SPARK_MAX = Mocks.mock(CANSparkMax.class, ANSWER); - - public static final RelativeEncoder DUMMY_ENCODER = Mocks.mock(RelativeEncoder.class, REVLibErrorAnswer.ANSWER); - public static final SparkAnalogSensor DUMMY_ANALOG_SENSOR = Mocks.mock(SparkAnalogSensor.class, REVLibErrorAnswer.ANSWER); - public static final SparkLimitSwitch DUMMY_LIMIT_SWITCH = Mocks.mock(SparkLimitSwitch.class, REVLibErrorAnswer.ANSWER); - public static final SparkPIDController DUMMY_PID_CONTROLLER = Mocks.mock(SparkPIDController.class, ANSWER); - public static final SparkAbsoluteEncoder DUMMY_ABSOLUTE_ENCODER = Mocks.mock(SparkAbsoluteEncoder.class, ANSWER); - - - @Override - public Object answer(InvocationOnMock invocation) throws Throwable { - Class returnType = invocation.getMethod().getReturnType(); - if(returnType == RelativeEncoder.class) { - return DUMMY_ENCODER; - } else if(returnType == SparkAnalogSensor.class) { - return DUMMY_ANALOG_SENSOR; - } else if(returnType == SparkLimitSwitch.class) { - return DUMMY_LIMIT_SWITCH; - } else if(returnType == SparkPIDController.class) { - return DUMMY_PID_CONTROLLER; - } else if(returnType == MotorType.class) { - return MotorType.kBrushless; - } else if(returnType == IdleMode.class) { - return IdleMode.kBrake; - } else if(returnType == AccelStrategy.class) { - return AccelStrategy.kTrapezoidal; - } else if(returnType == SparkAbsoluteEncoder.class) { - return DUMMY_ABSOLUTE_ENCODER; - } - return super.answer(invocation); - } - -} \ No newline at end of file diff --git a/src/main/java/org/carlmontrobotics/lib199/MotorConfig.java b/src/main/java/org/carlmontrobotics/lib199/MotorConfig.java index 0c12de1a..9693498f 100644 --- a/src/main/java/org/carlmontrobotics/lib199/MotorConfig.java +++ b/src/main/java/org/carlmontrobotics/lib199/MotorConfig.java @@ -11,7 +11,6 @@ public class MotorConfig { // See: https://www.chiefdelphi.com/t/rev-robotics-spark-flex-and-neo-vortex/442595/349?u=brettle // As a result I think 100C should be safe. I wouldn't increase it past 120. --Dean public static final MotorConfig NEO_VORTEX = new MotorConfig(100, 60); - public final int temperatureLimitCelsius, currentLimitAmps; public MotorConfig(int temperatureLimitCelsius, int currentLimitAmps) { diff --git a/src/main/java/org/carlmontrobotics/lib199/MotorControllerFactory.java b/src/main/java/org/carlmontrobotics/lib199/MotorControllerFactory.java index 0cd62ee7..9269724e 100644 --- a/src/main/java/org/carlmontrobotics/lib199/MotorControllerFactory.java +++ b/src/main/java/org/carlmontrobotics/lib199/MotorControllerFactory.java @@ -11,16 +11,21 @@ import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX; import com.ctre.phoenix.motorcontrol.can.WPI_VictorSPX; import com.ctre.phoenix6.hardware.CANcoder; -import com.revrobotics.CANSparkMax; -import com.revrobotics.CANSparkBase.ExternalFollower; -import com.revrobotics.CANSparkBase.IdleMode; -import com.revrobotics.CANSparkBase; -import com.revrobotics.CANSparkFlex; -import com.revrobotics.CANSparkLowLevel; -import com.revrobotics.SparkPIDController; - -import org.carlmontrobotics.lib199.sim.MockSparkFlex; -import org.carlmontrobotics.lib199.sim.MockSparkMax; +import com.revrobotics.spark.SparkMax; +import com.revrobotics.spark.SparkBase.PersistMode; +import com.revrobotics.spark.config.SparkBaseConfig; +import com.revrobotics.spark.config.SparkFlexConfig; +import com.revrobotics.spark.config.SparkBaseConfig.IdleMode; +import com.revrobotics.spark.config.SparkMaxConfig; +import com.revrobotics.servohub.ServoHub.ResetMode; +import com.revrobotics.spark.ClosedLoopSlot; +import com.revrobotics.spark.SparkBase; +import com.revrobotics.spark.SparkFlex; +import com.revrobotics.spark.SparkLowLevel; +import com.revrobotics.spark.SparkClosedLoopController; + +// import org.carlmontrobotics.lib199.sim.MockSparkFlex; +// import org.carlmontrobotics.lib199.sim.MockSparkMax; import org.carlmontrobotics.lib199.sim.MockTalonSRX; import org.carlmontrobotics.lib199.sim.MockVictorSPX; import org.carlmontrobotics.lib199.sim.MockedCANCoder; @@ -78,86 +83,163 @@ public static WPI_TalonSRX createTalon(int id) { return talon; } - //checks for spark max errors - - @Deprecated - public static CANSparkMax createSparkMax(int id, MotorErrors.TemperatureLimit temperatureLimit) { - return createSparkMax(id, temperatureLimit.limit); - } - - @Deprecated - public static CANSparkMax createSparkMax(int id, int temperatureLimit) { - CANSparkMax spark; + /** + * Create a default sparkMax controller (NEO or 550). + * + * @param id the port of the motor controller + * @param motorConfig either MotorConfig.NEO or MotorConfig.NEO_550 + */ + public static SparkMax createSparkMax(int id, MotorConfig motorConfig) { + SparkMax spark=null; if (RobotBase.isReal()) { - spark = new CANSparkMax(id, CANSparkLowLevel.MotorType.kBrushless); + spark = new SparkMax(id, SparkLowLevel.MotorType.kBrushless); } else { - spark = MockSparkMax.createMockSparkMax(id, CANSparkLowLevel.MotorType.kBrushless); + System.err.println("heyy... lib199 doesn't have sim support sorri"); + // spark = MockSparkMax.createMockSparkMax(id, SparkLowLevel.MotorType.kBrushless); } - spark.setPeriodicFramePeriod(CANSparkLowLevel.PeriodicFrame.kStatus0, 1); - MotorErrors.reportSparkMaxTemp(spark, temperatureLimit); + // config.setPeriodicFramePeriod(SparkLowLevel.PeriodicFrame.kStatus0, 1); + if (spark!=null) + MotorErrors.reportSparkMaxTemp(spark, motorConfig.temperatureLimitCelsius); + + MotorErrors.checkSparkMaxErrors(spark); - MotorErrors.reportError(spark.restoreFactoryDefaults()); - MotorErrors.reportError(spark.follow(ExternalFollower.kFollowerDisabled, 0)); - MotorErrors.reportError(spark.setIdleMode(IdleMode.kBrake)); - MotorErrors.reportError(spark.enableVoltageCompensation(12)); - MotorErrors.reportError(spark.setSmartCurrentLimit(50)); + if (motorConfig==MotorConfig.NEO || motorConfig==MotorConfig.NEO_550) + spark.configure(baseSparkMaxConfig(), SparkBase.ResetMode.kResetSafeParameters, SparkBase.PersistMode.kPersistParameters); + else if (motorConfig==MotorConfig.NEO_VORTEX) + spark.configure(baseSparkFlexConfig(), SparkBase.ResetMode.kResetSafeParameters, SparkBase.PersistMode.kPersistParameters); + else + spark.configure(baseSparkConfig(), SparkBase.ResetMode.kResetSafeParameters, SparkBase.PersistMode.kPersistParameters); - MotorErrors.checkSparkMaxErrors(spark); - SparkPIDController controller = spark.getPIDController(); - MotorErrors.reportError(controller.setOutputRange(-1, 1)); - MotorErrors.reportError(controller.setP(0)); - MotorErrors.reportError(controller.setI(0)); - MotorErrors.reportError(controller.setD(0)); - MotorErrors.reportError(controller.setFF(0)); + return spark; + } + /** + * Create a sparkMax controller (NEO or 550) with custom settings. + * + * @param id the port of the motor controller + * @param config the custom config to set + */ + public static SparkMax createSparkMax(int id, SparkBaseConfig config) { + SparkMax spark = null; + if (RobotBase.isReal()) { + spark = new SparkMax(id, SparkLowLevel.MotorType.kBrushless); + } else { + System.err.println("heyy... lib199 doesn't have sim support sorri"); + // spark = MockSparkMax.createMockSparkMax(id, SparkLowLevel.MotorType.kBrushless); + } + if (spark!=null) + spark.configure( + config, + SparkBase.ResetMode.kResetSafeParameters, + SparkBase.PersistMode.kNoPersistParameters + ); return spark; } + /** + * Create a default sparkFlex-Vortex controller. + * + * @param id the port of the motor controller + */ + public static SparkFlex createSparkFlex(int id) { + MotorConfig motorConfig = MotorConfig.NEO_VORTEX; - public static CANSparkMax createSparkMax(int id, MotorConfig config) { - CANSparkMax spark; + SparkFlex spark=null; if (RobotBase.isReal()) { - spark = new CANSparkMax(id, CANSparkLowLevel.MotorType.kBrushless); + spark = new SparkFlex(id, SparkLowLevel.MotorType.kBrushless); } else { - spark = MockSparkMax.createMockSparkMax(id, CANSparkLowLevel.MotorType.kBrushless); + System.err.println("heyy... lib199 doesn't have sim support sorri"); + // spark = MockSparkMax.createMockSparkMax(id, SparkLowLevel.MotorType.kBrushless); } - configureSpark(spark, config); + // config.setPeriodicFramePeriod(SparkLowLevel.PeriodicFrame.kStatus0, 1); + if (spark!=null) + MotorErrors.reportSparkTemp(spark, motorConfig.temperatureLimitCelsius); + + MotorErrors.checkSparkErrors(spark); + + spark.configure(baseSparkFlexConfig(), SparkBase.ResetMode.kResetSafeParameters, SparkBase.PersistMode.kPersistParameters); return spark; } - - public static CANSparkFlex createSparkFlex(int id, MotorConfig config) { - CANSparkFlex spark; + /** + * Create a sparkFlex controller (VORTEX) with custom settings. + * + * @param id the port of the motor controller + * @param config the custom config to set + */ + public static SparkFlex createSparkFlex(int id, SparkBaseConfig config) { + SparkFlex spark = null; if (RobotBase.isReal()) { - spark = new CANSparkFlex(id, CANSparkLowLevel.MotorType.kBrushless); + spark = new SparkFlex(id, SparkLowLevel.MotorType.kBrushless); } else { - spark = MockSparkFlex.createMockSparkFlex(id, CANSparkLowLevel.MotorType.kBrushless); + System.err.println("heyy... lib199 doesn't have sim support sorri"); + // spark = MockSparkFlex.createMockSparkFlex(id, SparkLowLevel.MotorType.kBrushless); } - - configureSpark(spark, config); + if (spark!=null) + spark.configure( + config, + SparkBase.ResetMode.kResetSafeParameters, + SparkBase.PersistMode.kNoPersistParameters + ); return spark; } - private static void configureSpark(CANSparkBase spark, MotorConfig config) { - MotorErrors.reportSparkTemp(spark, config.temperatureLimitCelsius); - MotorErrors.reportError(spark.restoreFactoryDefaults()); - //MotorErrors.reportError(spark.follow(ExternalFollower.kFollowerDisabled, 0)); - MotorErrors.reportError(spark.setIdleMode(IdleMode.kBrake)); - MotorErrors.reportError(spark.enableVoltageCompensation(12)); - MotorErrors.reportError(spark.setSmartCurrentLimit(config.currentLimitAmps)); + public static SparkBaseConfig baseSparkConfig() { + SparkMaxConfig config = new SparkMaxConfig(); - MotorErrors.checkSparkErrors(spark); + config.idleMode(IdleMode.kBrake); + + config.voltageCompensation(12);//FIXME does this need to be different for different motors? + config.smartCurrentLimit(50); + + config.closedLoop + .minOutput(-1) + .maxOutput(1) + .pid(0,0,0) + .velocityFF(0); - SparkPIDController controller = spark.getPIDController(); - MotorErrors.reportError(controller.setOutputRange(-1, 1)); - MotorErrors.reportError(controller.setP(0)); - MotorErrors.reportError(controller.setI(0)); - MotorErrors.reportError(controller.setD(0)); - MotorErrors.reportError(controller.setFF(0)); + return config; + } + /** + * Overrides an old config - but does not change other settings. + */ + public static SparkBaseConfig baseSparkConfig(SparkMaxConfig config) { + config.idleMode(IdleMode.kBrake); + + config.voltageCompensation(12);//FIXME does this need to be different for different motors? + config.smartCurrentLimit(50); + + config.closedLoop + .minOutput(-1) + .maxOutput(1) + .pid(0,0,0) + .velocityFF(0); + + return config; + } + /** + * Overrides an old config - but does not change other settings. + */ + public static SparkMaxConfig baseSparkMaxConfig(SparkMaxConfig config){ + //typical operating voltage: 12V. + return (SparkMaxConfig) baseSparkConfig(config);//FIXME apply needed config changes for each controller + } + public static SparkMaxConfig baseSparkMaxConfig(){ + return (SparkMaxConfig) baseSparkConfig(); + } + /** + * Overrides an old config - but does not change other settings. + */ + public static SparkFlexConfig baseSparkFlexConfig(SparkMaxConfig config){ + //typical operating voltage: 12V. ( same as sparkMax ) + return (SparkFlexConfig) baseSparkConfig(config);//criminal casting usage + } + public static SparkFlexConfig baseSparkFlexConfig(){//why? no Se. + return (SparkFlexConfig) baseSparkConfig(); } /** diff --git a/src/main/java/org/carlmontrobotics/lib199/MotorErrors.java b/src/main/java/org/carlmontrobotics/lib199/MotorErrors.java index 5d5a0655..076d30d8 100644 --- a/src/main/java/org/carlmontrobotics/lib199/MotorErrors.java +++ b/src/main/java/org/carlmontrobotics/lib199/MotorErrors.java @@ -6,22 +6,25 @@ import java.util.concurrent.ConcurrentSkipListMap; import com.ctre.phoenix.ErrorCode; -import com.revrobotics.CANSparkBase; -import com.revrobotics.CANSparkFlex; -import com.revrobotics.CANSparkMax; -import com.revrobotics.CANSparkBase.FaultID; +import com.revrobotics.spark.SparkBase; +import com.revrobotics.spark.SparkFlex; +import com.revrobotics.spark.SparkLowLevel; +import com.revrobotics.spark.SparkMax; +import com.revrobotics.spark.SparkBase.Faults; +import com.revrobotics.spark.config.SparkBaseConfig; +import com.revrobotics.spark.config.SparkMaxConfig; import com.revrobotics.REVLibError; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; public final class MotorErrors { - private static final Map temperatureSparks = new ConcurrentSkipListMap<>(); + private static final Map temperatureSparks = new ConcurrentSkipListMap<>(); private static final Map sparkTemperatureLimits = new ConcurrentHashMap<>(); private static final Map overheatedSparks = new ConcurrentHashMap<>(); - private static final Map flags = new ConcurrentSkipListMap<>( + private static final Map flags = new ConcurrentSkipListMap<>( (spark1, spark2) -> (spark1.getDeviceId() - spark2.getDeviceId())); - private static final Map stickyFlags = new ConcurrentSkipListMap<>( + private static final Map stickyFlags = new ConcurrentSkipListMap<>( (spark1, spark2) -> (spark1.getDeviceId() - spark2.getDeviceId())); public static final int kOverheatTripCount = 5; @@ -65,18 +68,19 @@ private static > void reportError(String vendor, T error, T ok System.err.println(Arrays.toString(stack)); } - public static void checkSparkErrors(CANSparkBase spark) { + public static void checkSparkErrors(SparkBase spark) { //Purposely obviously impersonal to differentiate from actual computer generated errors - short faults = spark.getFaults(); - short stickyFaults = spark.getStickyFaults(); - short prevFaults = flags.containsKey(spark) ? flags.get(spark) : 0; - short prevStickyFaults = stickyFlags.containsKey(spark) ? stickyFlags.get(spark) : 0; - - if (spark.getFaults() != 0 && prevFaults != faults) { - System.err.println("Whoops, big oopsie : fault error(s) with spark id : " + spark.getDeviceId() + ": [ " + formatFaults(spark) + "], ooF!"); + // short faults = spark.getFaults(); + Faults faults = spark.getFaults(); + Faults stickyFaults = spark.getStickyFaults(); + Faults prevFaults = flags.containsKey(spark) ? flags.get(spark) : null; + Faults prevStickyFaults = stickyFlags.containsKey(spark) ? stickyFlags.get(spark) : null; + + if (spark.hasActiveFault() && prevFaults!=null && prevFaults.rawBits != faults.rawBits) { + System.err.println("Fault Errors! (spark id " + spark.getDeviceId() + "): [" + formatFaults(spark) + "], ooF!"); } - if (spark.getStickyFaults() != 0 && prevStickyFaults != stickyFaults) { - System.err.println("Bruh, you did an Error : sticky fault(s) error with spark id : " + spark.getDeviceId() + ": " + formatStickyFaults(spark) + ", Ouch!"); + if (spark.hasStickyFault() && prevStickyFaults!=null && prevStickyFaults.rawBits != stickyFaults.rawBits) { + System.err.println("Sticky Faults! (spark id " + spark.getDeviceId() + "): [" + formatStickyFaults(spark) + "], Ouch!"); } spark.clearFaults(); flags.put(spark, faults); @@ -84,28 +88,36 @@ public static void checkSparkErrors(CANSparkBase spark) { } @Deprecated - public static void checkSparkMaxErrors(CANSparkMax spark) { - checkSparkErrors((CANSparkBase)spark); - } - - private static String formatFaults(CANSparkBase spark) { - String out = ""; - for(FaultID fault: FaultID.values()) { - if(spark.getFault(fault)) { - out += (fault.name() + " "); - } - } - return out; - } - - private static String formatStickyFaults(CANSparkBase spark) { - String out = ""; - for(FaultID fault: FaultID.values()) { - if(spark.getStickyFault(fault)) { - out += (fault.name() + " "); - } - } - return out; + public static void checkSparkMaxErrors(SparkMax spark) { + checkSparkErrors((SparkBase)spark); + } + + private static String formatFaults(SparkBase spark) { + Faults f = spark.getFaults(); + return "" //i hope this makes you proud of yourself, REVLib + + (f.can ? "CAN " : "") + + (f.escEeprom ? "Flash ROM " : "") + + (f.firmware ? "Firmware " : "") + + (f.gateDriver ? "Gate Driver " : "") + + (f.motorType ? "Motor Type " : "") + + (f.other ? "Other " : "") + + (f.sensor ? "Sensor " : "") + + (f.temperature ? "Temperature " : "") + ; + } + + private static String formatStickyFaults(SparkBase spark) { + Faults f = spark.getStickyFaults(); + return "" + + (f.can ? "CAN " : "") + + (f.escEeprom ? "Flash ROM " : "") + + (f.firmware ? "Firmware " : "") + + (f.gateDriver ? "Gate Driver " : "") + + (f.motorType ? "Motor Type " : "") + + (f.other ? "Other " : "") + + (f.sensor ? "Sensor " : "") + + (f.temperature ? "Temperature " : "") + ; } @Deprecated @@ -125,27 +137,28 @@ static void reportNextNSparkErrors(int n) { lastSparkErrorIndexReported = (lastSparkErrorIndexReported + n) % flags.size(); } - public static CANSparkMax createDummySparkMax() { - return DummySparkMaxAnswer.DUMMY_SPARK_MAX; + //what does this even supposed to do?? + public static SparkMax createDummySparkMax() { + return Mocks.mock(SparkMax.class, new REVLibErrorAnswer()); } @Deprecated - public static void reportSparkMaxTemp(CANSparkMax spark, TemperatureLimit temperatureLimit) { + public static void reportSparkMaxTemp(SparkMax spark, TemperatureLimit temperatureLimit) { reportSparkMaxTemp(spark, temperatureLimit.limit); } - public static boolean isSparkMaxOverheated(CANSparkMax spark){ + public static boolean isSparkMaxOverheated(SparkMax spark){ int id = spark.getDeviceId(); int motorMaxTemp = sparkTemperatureLimits.get(id); return ( spark.getMotorTemperature() >= motorMaxTemp ); } @Deprecated - public static void reportSparkMaxTemp(CANSparkMax spark, int temperatureLimit) { - reportSparkTemp((CANSparkBase) spark, temperatureLimit); + public static void reportSparkMaxTemp(SparkMax spark, int temperatureLimit) { + reportSparkTemp((SparkBase) spark, temperatureLimit); } - public static void reportSparkTemp(CANSparkBase spark, int temperatureLimit) { + public static void reportSparkTemp(SparkBase spark, int temperatureLimit) { int id = spark.getDeviceId(); temperatureSparks.put(id, spark); sparkTemperatureLimits.put(id, temperatureLimit); @@ -169,14 +182,14 @@ static void reportNextNSparkTemps(int n) { lastSparkTempIndexReported = (lastSparkTempIndexReported + n) % temperatureSparks.size(); } - private static void reportSparkTemp(int port, CANSparkBase spark) { + private static void reportSparkTemp(int port, SparkBase spark) { double temp = spark.getMotorTemperature(); double limit = sparkTemperatureLimits.get(port); int numTrips = overheatedSparks.get(port); String sparkType = "of unknown type"; - if (spark instanceof CANSparkMax) { + if (spark instanceof SparkMax) { sparkType = "Max"; - } else if (spark instanceof CANSparkFlex) { + } else if (spark instanceof SparkFlex) { sparkType = "Flex"; } SmartDashboard.putNumber(String.format("Port %d Spark %s Temp", port, sparkType), temp); @@ -202,7 +215,10 @@ private static void reportSparkTemp(int port, CANSparkBase spark) { System.err.println("Port " + port + " spark is operating at " + temp + " degrees Celsius! It will be disabled until the robot code is restarted."); } - spark.setSmartCurrentLimit(1); + spark.configure( + new SparkMaxConfig().smartCurrentLimit(1), + SparkBase.ResetMode.kResetSafeParameters, + SparkBase.PersistMode.kNoPersistParameters); } } diff --git a/src/main/java/org/carlmontrobotics/lib199/SparkVelocityPIDController.java b/src/main/java/org/carlmontrobotics/lib199/SparkVelocityPIDController.java index f95efbed..66bb7c03 100644 --- a/src/main/java/org/carlmontrobotics/lib199/SparkVelocityPIDController.java +++ b/src/main/java/org/carlmontrobotics/lib199/SparkVelocityPIDController.java @@ -1,9 +1,17 @@ package org.carlmontrobotics.lib199; -import com.revrobotics.CANSparkMax; -import com.revrobotics.CANSparkBase.ControlType; +import com.revrobotics.spark.SparkMax; +import com.revrobotics.spark.config.ClosedLoopConfig; +import com.revrobotics.spark.config.SparkBaseConfig; +import com.revrobotics.spark.config.SparkMaxConfig; +// import com.revrobotics.SparkBase.ControlType; import com.revrobotics.RelativeEncoder; -import com.revrobotics.SparkPIDController; +import com.revrobotics.spark.ClosedLoopSlot; +import com.revrobotics.spark.SparkBase; +import com.revrobotics.spark.SparkBase.ControlType; +import com.revrobotics.spark.SparkBase.PersistMode; +import com.revrobotics.spark.SparkBase.ResetMode; +import com.revrobotics.spark.SparkClosedLoopController; import edu.wpi.first.util.sendable.Sendable; import edu.wpi.first.util.sendable.SendableBuilder; @@ -12,27 +20,33 @@ public class SparkVelocityPIDController implements Sendable { @SuppressWarnings("unused") - private final CANSparkMax spark; - private final SparkPIDController pidController; + private final SparkMax spark; + private final SparkClosedLoopController pidController; private final RelativeEncoder encoder; private final String name; private double targetSpeed, tolerance; private double currentP, currentI, currentD, kS, kV; - public SparkVelocityPIDController(String name, CANSparkMax spark, double defaultP, double defaultI, double defaultD, double kS, double kV, double targetSpeed, double tolerance) { + public SparkVelocityPIDController(String name, SparkMax spark, double defaultP, double defaultI, double defaultD, double kS, double kV, double targetSpeed, double tolerance) { this.spark = spark; - this.pidController = spark.getPIDController(); + this.pidController = spark.getClosedLoopController(); this.encoder = spark.getEncoder(); this.name = name; this.targetSpeed = targetSpeed; this.tolerance = tolerance; - pidController.setP(this.currentP = defaultP); - pidController.setI(this.currentI = defaultI); - pidController.setD(this.currentD = defaultD); + + spark.configure(new SparkMaxConfig().apply( + new ClosedLoopConfig().pid( + this.currentP = defaultP, + this.currentI = defaultI, + this.currentD = defaultD + )), + SparkBase.ResetMode.kNoResetSafeParameters,//we only want to change pid params + SparkBase.PersistMode.kNoPersistParameters); this.kS = kS; this.kV = kV; - pidController.setReference(targetSpeed, ControlType.kVelocity, 0, calculateFF(targetSpeed)); + pidController.setReference(targetSpeed, ControlType.kVelocity, ClosedLoopSlot.kSlot0, calculateFF(targetSpeed)); SendableRegistry.addLW(this, "SparkVelocityPIDController", spark.getDeviceId()); } @@ -56,7 +70,7 @@ public double getTargetSpeed() { public void setTargetSpeed(double targetSpeed) { if(targetSpeed == this.targetSpeed) return; this.targetSpeed = targetSpeed; - pidController.setReference(targetSpeed, ControlType.kVelocity, 0, calculateFF(targetSpeed)); + pidController.setReference(targetSpeed, ControlType.kVelocity, ClosedLoopSlot.kSlot0, calculateFF(targetSpeed)); } public double getTolerance() { @@ -71,25 +85,26 @@ public double calculateFF(double velocity) { return kS * Math.signum(velocity) + kV * velocity; } + private void instantClosedLoopConfig(ClosedLoopConfig clConfig) { + spark.configure(new SparkMaxConfig().apply(clConfig), ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters); + } + @Override public void initSendable(SendableBuilder builder) { builder.setActuator(true); builder.setSmartDashboardType("SparkVelocityPIDController"); builder.addDoubleProperty("P", () -> currentP, p -> { - pidController.setP(p); - currentP = p; + instantClosedLoopConfig(new ClosedLoopConfig().p(currentP = p)); }); builder.addDoubleProperty("I", () -> currentI, i -> { - pidController.setI(i); - currentI = i; + instantClosedLoopConfig(new ClosedLoopConfig().i(currentI = i)); }); builder.addDoubleProperty("D", () -> currentD, d -> { - pidController.setD(d); - currentD = d; + instantClosedLoopConfig(new ClosedLoopConfig().d(currentD = d)); }); builder.addDoubleProperty("Target Speed", () -> targetSpeed, newSpeed -> { if(newSpeed == targetSpeed) return; - pidController.setReference(newSpeed, ControlType.kVelocity, 0, calculateFF(newSpeed)); + pidController.setReference(newSpeed, ControlType.kVelocity, ClosedLoopSlot.kSlot0, calculateFF(newSpeed)); targetSpeed = newSpeed; }); builder.addDoubleProperty("Tolerance", () -> tolerance, newTolerance -> tolerance = newTolerance); diff --git a/src/main/java/org/carlmontrobotics/lib199/path/DifferentialDriveInterface.java b/src/main/java/org/carlmontrobotics/lib199/path/DifferentialDriveInterface.java deleted file mode 100644 index b17930f8..00000000 --- a/src/main/java/org/carlmontrobotics/lib199/path/DifferentialDriveInterface.java +++ /dev/null @@ -1,98 +0,0 @@ -package org.carlmontrobotics.lib199.path; - -import java.util.function.Supplier; -import java.util.stream.DoubleStream; - -import edu.wpi.first.math.controller.RamseteController; -import edu.wpi.first.math.controller.SimpleMotorFeedforward; -import edu.wpi.first.math.geometry.Rotation2d; -import edu.wpi.first.math.kinematics.DifferentialDriveKinematics; -import edu.wpi.first.math.trajectory.Trajectory; -import edu.wpi.first.math.trajectory.TrajectoryConfig; -import edu.wpi.first.math.trajectory.constraint.DifferentialDriveVoltageConstraint; -import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.RamseteCommand; - -public interface DifferentialDriveInterface extends DrivetrainInterface { - - /** - * Drives - * - * @param left power to left motor m/s - * @param right power to right motor m/s - */ - public void drive(double left, double right); - - /** - * Gets Differential Drive kinematics - * - * @return kinematics - */ - public DifferentialDriveKinematics getKinematics(); - - /** - * Gets max volts - * - * @return max volts - */ - public double getMaxVolt(); - - /** - * Gets characterization values in the form { kVolts, kVels, kAccels } - * - * @return characterization values in the form { kVolts, kVels, kAccels } - */ - public double[][] getCharacterizationValues(); - - /** - * @return The left encoder position in meters - */ - public double getLeftEncoderPosition(); - - /** - * @return The right encoder position in meters - */ - public double getRightEncoderPosition(); - - /** - * Creates Ramsete Controller - * - * @return Ramsete Controller - */ - public default RamseteController createRamsete() { - return new RamseteController(); - } - - /** - * Configures Trajectory - * - * @param path RobotPath object - */ - @Override - public default void configureAutoPath(RobotPath path) { - TrajectoryConfig config = path.getTrajectoryConfig(); - config.setKinematics(getKinematics()); - - double[][] charVals = getCharacterizationValues(); - config.addConstraint(new DifferentialDriveVoltageConstraint( - // new SimpleMotorFeedforward(Utils199.average(charVals[0]), - // Utils199.average(charVals[1]), Utils199.average(charVals[2])), - new SimpleMotorFeedforward(DoubleStream.of(charVals[0]).average().getAsDouble(), - DoubleStream.of(charVals[1]).average().getAsDouble(), - DoubleStream.of(charVals[2]).average().getAsDouble()), - getKinematics(), getMaxVolt())); - } - - /** - * Creates Ramsete Command - * - * @param trajectory Trajectory object - * @param desiredHeading Desired Heading - * @return Ramsete Command - */ - @Override - public default Command createAutoCommand(Trajectory trajectory, Supplier desiredHeading) { - return new RamseteCommand(trajectory, this::getPose, createRamsete(), getKinematics(), this::drive, this); - } - -} diff --git a/src/main/java/org/carlmontrobotics/lib199/path/DrivetrainInterface.java b/src/main/java/org/carlmontrobotics/lib199/path/DrivetrainInterface.java deleted file mode 100644 index e4023a08..00000000 --- a/src/main/java/org/carlmontrobotics/lib199/path/DrivetrainInterface.java +++ /dev/null @@ -1,69 +0,0 @@ -package org.carlmontrobotics.lib199.path; - -import java.util.function.Supplier; - -import edu.wpi.first.math.geometry.Pose2d; -import edu.wpi.first.math.geometry.Rotation2d; -import edu.wpi.first.math.trajectory.Trajectory; -import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.Subsystem; - -public interface DrivetrainInterface extends Subsystem { - - /** - * Configures the constants for generating a trajectory - * - * @param path The configuration for generating a trajectory - */ - public void configureAutoPath(RobotPath path); - - /** - * Constructs a new autonomous Command that, when executed, will follow the - * provided trajectory. - * - * @param trajectory The trajectory to follow. - * @param desiredHeading A function that supplies the robot pose - use one of - * the odometry classes to provide this. - * @return Command - */ - public Command createAutoCommand(Trajectory trajectory, Supplier desiredHeading); - - /** - * Gets the max acceleration in m/s^2 - * - * @return max acceleration in m/s^2 - */ - public double getMaxAccelMps2(); - - /** - * Gets the max speed in m/s - * - * @return max speed in m/s - */ - public double getMaxSpeedMps(); - - /** - * Gets the current heading in degrees - * - * @return current heading in degrees - */ - public double getHeadingDeg(); - - /** - * @return The current position of the robot - */ - public Pose2d getPose(); - - /** - * Sets odometry to the specified pose - * - * @param initialPose The starting position of the robot on the field. - */ - public void setPose(Pose2d initialPose); - - /** - * Stops the drivetrain - */ - public void stop(); - -} diff --git a/src/main/java/org/carlmontrobotics/lib199/path/RobotPath.java b/src/main/java/org/carlmontrobotics/lib199/path/RobotPath.java deleted file mode 100644 index be65a34b..00000000 --- a/src/main/java/org/carlmontrobotics/lib199/path/RobotPath.java +++ /dev/null @@ -1,322 +0,0 @@ -package org.carlmontrobotics.lib199.path; - -import java.io.File; -import java.io.FileNotFoundException; -import java.io.FileReader; -import java.io.IOException; -import java.nio.file.Paths; -import java.util.ArrayList; -import java.util.Collections; -import java.util.List; -import java.util.concurrent.atomic.AtomicReference; -import java.util.function.Supplier; - -import org.apache.commons.csv.CSVFormat; -import org.apache.commons.csv.CSVParser; -import org.apache.commons.csv.CSVRecord; - -import edu.wpi.first.math.geometry.Pose2d; -import edu.wpi.first.math.geometry.Rotation2d; -import edu.wpi.first.math.geometry.Translation2d; -import edu.wpi.first.math.trajectory.Trajectory; -import edu.wpi.first.math.trajectory.TrajectoryConfig; -import edu.wpi.first.math.trajectory.TrajectoryGenerator; -import edu.wpi.first.wpilibj.Filesystem; -import edu.wpi.first.wpilibj.Timer; -import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; -import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.InstantCommand; - -//Findd Me -public class RobotPath { - - private List poses; - private Trajectory trajectory; - private TrajectoryConfig config; - private DrivetrainInterface dt; - private HeadingSupplier hs; - private double maxAccelMps2; - private double maxSpeedMps; - private boolean isInverted; - - /** - * Constructs a RobotPath Object - * - * @param pathName Name of the path - * @param dt Drivetrain object - * @param isInverted Whether the path is inverted - * @param initPos Initial position - * @throws IOException If an error occured loading the path - */ - public RobotPath(String pathName, DrivetrainInterface dt, boolean isInverted, Translation2d initPos) - throws IOException { - this(getPointsFromFile(pathName, dt, isInverted, initPos), isInverted, dt); - - } - - /** - * Constructs a RobotPath Object - * - * @param poses List of points in the .path file - * @param isInverted Whether the path is inverted - * @param dt Drivetrain object - */ - public RobotPath(List poses, boolean isInverted, DrivetrainInterface dt) { - this.poses = poses; - this.dt = dt; - this.isInverted = isInverted; - this.maxAccelMps2 = dt.getMaxAccelMps2(); - this.maxSpeedMps = dt.getMaxSpeedMps(); - } - - public Rotation2d getRotation2d(int index){ - return poses.get(index).getRotation(); - } - - /** - * Gets a path command for the given path - * - * @param faceInPathDirection Only for swerve drive, unless otherwise stated. - * Determines whether robot stays facing path - * @param stopAtEnd whether the robot should stop at the end - * @return PathCommand - */ - public Command getPathCommand(boolean faceInPathDirection, boolean stopAtEnd) { - if (trajectory == null) { - generateTrajectory(); - } - // We want the robot to stay facing the same direction (in this case), so save - // the current heading (make sure to update at the start of the command) - AtomicReference headingRef = new AtomicReference<>(dt.getPose().getRotation()); - Supplier desiredHeading = (!faceInPathDirection) ? () -> headingRef.get() : () -> hs.sample(); - Command command = dt.createAutoCommand(trajectory, desiredHeading); - command = new InstantCommand(hs::reset).andThen(command, new InstantCommand(hs::stop)); - if (stopAtEnd) { - command = command.andThen(new InstantCommand(dt::stop, dt)); - } - if (!faceInPathDirection) { - command = new InstantCommand(() -> headingRef.set(dt.getPose().getRotation())).andThen(command); - SmartDashboard.putNumber("Desired Path Heading", headingRef.get().getDegrees()); - } - return command; - } - - /** - * Tells the drivetrain to assume that the robot is at the starting position of - * this path. - */ - public void initializeDrivetrainPosition() { - if (trajectory == null) { - generateTrajectory(); - } - dt.setPose(trajectory.getInitialPose()); - } - - /** - * Generates trajectory using List of poses and TrajectoryConfig objects - */ - private void generateTrajectory() { - if (config == null) { - createConfig(); - } - trajectory = TrajectoryGenerator.generateTrajectory(poses, config); - hs = new HeadingSupplier(trajectory); - } - - /** - * Retrieves the TrajectoryConfig object for this path, creating it if it does - * not already exist - * - * @return the TrajectoryConfig object - */ - public TrajectoryConfig getTrajectoryConfig() { - if (config == null) { - createConfig(); - } - return config; - } - - private void createConfig() { - config = new TrajectoryConfig(this.getMaxSpeedMps(), this.getMaxAccelMps2()); - dt.configureAutoPath(this); - if (isInverted) { - config.setReversed(true); - } - } - - /** - * Inverts the robot path - * - * @return inverted robot path - */ - public RobotPath reversed() { - List newPoses = new ArrayList<>(poses); - Collections.reverse(newPoses); - return new RobotPath(newPoses, true, dt); - } - - /** - * Get points of a path from name of a .path file - * - * @param pathName Path name - * @param dt Drivetrain object - * @param isInverted Whether the path is inverted - * @param initPos Initial position - * @return List of points in path - * @throws IOException If an error occured loading the path - */ - public static List getPointsFromFile(String pathName, DrivetrainInterface dt, boolean isInverted, - Translation2d initPos) throws IOException { - return getPointsFromFile(getPathFile(pathName), dt, isInverted, initPos); - } - - /** - * Get points of a path from a .path file - * - * @param file Filename - * @param dt Drivetrain object - * @param isInverted Whether the path is inverted - * @param initPos Initial position - * @return List of points in path - * @throws IOException If an error occured loading the path - */ - public static List getPointsFromFile(File file, DrivetrainInterface dt, boolean isInverted, - Translation2d initPos) throws IOException { - ArrayList poses = new ArrayList(); - - try { - CSVParser csvParser = CSVFormat.DEFAULT.parse(new FileReader(file)); - double x, y, tanx, tany; - Rotation2d rot; - List records = csvParser.getRecords(); - - for (int i = 1; i < records.size(); i++) { - CSVRecord record = records.get(i); - x = Double.parseDouble(record.get(0)) + initPos.getX(); - y = Double.parseDouble(record.get(1)) + initPos.getY(); - tanx = Double.parseDouble(record.get(2)); - tany = Double.parseDouble(record.get(3)); - rot = new Rotation2d(tanx, tany); - if (isInverted) { - rot = rot.rotateBy(new Rotation2d(Math.PI)); - } - poses.add(new Pose2d(x, y, rot)); - } - csvParser.close(); - } catch (FileNotFoundException e) { - System.out.println("File named: " + file.getAbsolutePath() + " not found."); - e.printStackTrace(); - } - - return poses; - } - - /** - * Gets max acceleration for path - * - * @return Max acceleration mps2 - */ - public double getMaxAccelMps2() { - return this.maxAccelMps2; - } - - /** - * Gets max speed for path - * - * @return Max speed mps - */ - public double getMaxSpeedMps() { - return this.maxSpeedMps; - } - - /** - * Sets max acceleration for path - * - * @param maxAccelMps2 New max acceleration mps2 - * @return The robot path - */ - public RobotPath setMaxAccelMps2(double maxAccelMps2) { - checkConfig("maxAccelMps2"); - this.maxAccelMps2 = maxAccelMps2; - return this; - } - - /** - * Sets max speed for path - * - * @param maxSpeedMps New max speed mps - * @return The robot path - */ - public RobotPath setMaxSpeedMps(double maxSpeedMps) { - checkConfig("maxSpeedMps"); - this.maxSpeedMps = maxSpeedMps; - return this; - } - - private void checkConfig(String varName) { - if (config != null) { - System.out.println( - "Warning: Config has already been created. The changes to " + varName + " will not affect it"); - } - } - - /** - * Gets .path file given filename - * - * @param pathName name of file - * @return .path file - */ - public static File getPathFile(String pathName) { - return Filesystem.getDeployDirectory().toPath().resolve(Paths.get("PathWeaver/Paths/" + pathName + ".path")) - .toFile(); - } - - private static class HeadingSupplier { - private Trajectory trajectory; - private Timer timer; - private boolean timerStarted; - - /** - * Constructs a HeadingSupplier object - * - * @param trajectory Represents a time-parameterized trajectory. The trajectory - * contains of various States that represent the pose, - * curvature, time elapsed, velocity, and acceleration at that - * point. - */ - public HeadingSupplier(Trajectory trajectory) { - this.trajectory = trajectory; - timer = new Timer(); - timerStarted = false; - } - - /** - * Gets the trajectory rotation at current point in time - * - * @return current trajectory rotation at current point in time - */ - public Rotation2d sample() { - if (!timerStarted) { - timerStarted = true; - timer.start(); - } - return trajectory.sample(timer.get()).poseMeters.getRotation(); - } - - /** - * Reset the timer - */ - public void reset() { - timerStarted = false; - timer.reset(); - } - - /** - * Stops the timer - */ - public void stop() { - timer.stop(); - reset(); - } - } -} diff --git a/src/main/java/org/carlmontrobotics/lib199/sim/MockSparkBase.java b/src/main/java/org/carlmontrobotics/lib199/sim/MockSparkBase.java index 3ad8f1f6..45ab3d8c 100644 --- a/src/main/java/org/carlmontrobotics/lib199/sim/MockSparkBase.java +++ b/src/main/java/org/carlmontrobotics/lib199/sim/MockSparkBase.java @@ -6,20 +6,29 @@ import org.carlmontrobotics.lib199.Mocks; import org.carlmontrobotics.lib199.REVLibErrorAnswer; -import com.revrobotics.CANSparkBase; -import com.revrobotics.CANSparkBase.ExternalFollower; -import com.revrobotics.CANSparkBase.IdleMode; -import com.revrobotics.CANSparkLowLevel.MotorType; +import com.revrobotics.spark.config.ClosedLoopConfig; +import com.revrobotics.spark.config.SparkMaxConfig; +import com.revrobotics.spark.config.SparkBaseConfig.IdleMode; +import com.revrobotics.spark.SparkClosedLoopController; +import com.revrobotics.spark.SparkFlex; +import com.revrobotics.spark.SparkLowLevel; +import com.revrobotics.spark.SparkLowLevel.MotorType; +import com.revrobotics.spark.SparkMax; import com.revrobotics.REVLibError; import com.revrobotics.RelativeEncoder; -import com.revrobotics.SparkAbsoluteEncoder; -import com.revrobotics.SparkMaxAlternateEncoder; -import com.revrobotics.SparkAnalogSensor; -import com.revrobotics.SparkPIDController; -import com.revrobotics.SparkRelativeEncoder; -import com.revrobotics.SparkRelativeEncoder.Type; +import com.revrobotics.sim.SparkAnalogSensorSim; +import com.revrobotics.sim.SparkMaxAlternateEncoderSim; +import com.revrobotics.sim.SparkAbsoluteEncoderSim; +import com.revrobotics.spark.SparkAbsoluteEncoder; +import com.revrobotics.spark.SparkMaxAlternateEncoder; +import com.revrobotics.spark.SparkAnalogSensor; +import com.revrobotics.spark.SparkBase; +import com.revrobotics.spark.SparkRelativeEncoder; +import com.revrobotics.spark.SparkSim; +import com.revrobotics.spark.SparkLowLevel; import edu.wpi.first.hal.SimDevice; +import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.wpilibj.motorcontrol.MotorController; /** @@ -31,15 +40,30 @@ public class MockSparkBase extends MockedMotorBase { public final MotorType type; private final MockedEncoder encoder; - private final SparkPIDController pidController; + private final SparkBase motor; + private final SparkSim spark; + private final SparkClosedLoopController pidController; private final MockedSparkMaxPIDController pidControllerImpl; private SparkAbsoluteEncoder absoluteEncoder = null; - private MockedEncoder absoluteEncoderImpl = null; - private MockedEncoder alternateEncoder = null; + private SparkAbsoluteEncoderSim absoluteEncoderImpl = null; + private SparkMaxAlternateEncoder alternateEncoder = null; + private SparkMaxAlternateEncoderSim alternateEncoderImpl = null; private SparkAnalogSensor analogSensor = null; - private MockedEncoder analogSensorImpl = null; + private SparkAnalogSensorSim analogSensorImpl = null; private final String name; + enum NEOType { + NEO(DCMotor.getNEO(1)), + NEO550(DCMotor.getNeo550(1)), + Vortex(DCMotor.getNeoVortex(1)), + UNKNOWN(DCMotor.getNEO(1)); + + public DCMotor dcMotor; + private NEOType(DCMotor dcmotordata){ + this.dcMotor=dcmotordata; + } + } + /** * Initializes a new {@link SimDevice} with the given parameters and creates the necessary sim values, and * registers this class's {@link #run()} method to be called via {@link Lib199Subsystem#registerSimulationPeriodic(Runnable)}. @@ -47,30 +71,45 @@ public class MockSparkBase extends MockedMotorBase { * @param port the port to associate this {@code MockSparkMax} with. Will be used to create the {@link SimDevice} and facilitate motor following. * @param type the type of the simulated motor. If this is set to {@link MotorType#kBrushless}, the builtin encoder simulation will be configured * to follow the inversion state of the motor and its {@code setInverted} method will be disabled. - * @param name the name of the type of controller ("CANSparkMax" or "CANSparkFlex") + * @param name the name of the type of controller ("SparkMax" or "SparkFlex") * @param countsPerRev the number of counts per revolution of this controller's built-in encoder. */ - public MockSparkBase(int port, MotorType type, String name, int countsPerRev) { + public MockSparkBase(int port, MotorType type, String name, int countsPerRev, NEOType neoType) { super(name, port); this.type = type; this.name = name; + if (neoType != NEOType.Vortex){ //WARNING can't initialize a sparkbase without an actual spark... + this.motor = new SparkMax(port,type); + this.spark = new SparkSim( + this.motor, + neoType.dcMotor + ); + } else { //only vortex uses sparkflex + this.motor = new SparkFlex(port,type); + this.spark = new SparkSim( + this.motor, + neoType.dcMotor + ); + } + if(type == MotorType.kBrushless) { encoder = new MockedEncoder(SimDevice.create("CANEncoder:" + name, port), countsPerRev, false, false) { - @Override - public REVLibError setInverted(boolean inverted) { - System.err.println( - "(MockedEncoder) SparkRelativeEncoder cannot be inverted separately from the motor in brushless mode!"); - return REVLibError.kParamInvalid; - } + // @Override + // public REVLibError setInverted(boolean inverted) { + // System.err.println( + // "(MockedEncoder) SparkRelativeEncoder cannot be inverted separately from the motor in brushless mode!"); + // return REVLibError.kParamInvalid; + // } }; } else { encoder = new MockedEncoder(SimDevice.create("CANEncoder:" + name, port), countsPerRev, false, false); } pidControllerImpl = new MockedSparkMaxPIDController(this); - pidController = Mocks.createMock(SparkPIDController.class, pidControllerImpl, new REVLibErrorAnswer()); - pidController.setFeedbackDevice(encoder); + pidController = Mocks.createMock(SparkClosedLoopController.class, pidControllerImpl, new REVLibErrorAnswer()); + // pidController.feedbackSensor(encoder); + controllers.put(port, this); @@ -96,21 +135,30 @@ public void set(double speed) { pidControllerImpl.setDutyCycle(speed); } - public REVLibError follow(CANSparkBase leader) { + public REVLibError follow(SparkBase leader) { return follow(leader, false); } - public REVLibError follow(CANSparkBase leader, boolean invert) { + public REVLibError follow(SparkBase leader, boolean invert) { pidControllerImpl.follow(leader, invert); // No need to lookup the spark max if we already have it return REVLibError.kOk; } - public REVLibError follow(ExternalFollower leader, int deviceID) { + public REVLibError follow(SparkBase leader, int deviceID) { return follow(leader, deviceID, false); } - public REVLibError follow(ExternalFollower leader, int deviceID, boolean invert) { + public REVLibError follow(SparkBase leader, int deviceID, boolean invert) { MotorController controller = null; + //ERROR: no way to check if leader is sending following frames or not + controller = getControllerWithId(deviceID); + if(controller == null) { + System.err.println("Error: Attempted to follow unknown motor controller: " + leader + " " + deviceID); + return REVLibError.kFollowConfigMismatch; + } + pidControllerImpl.follow(controller, invert); + return REVLibError.kOk; + /* // Because ExternalFollower does not implement equals, this could result in bugs if the user passes in a custom ExternalFollower object, // but I think that it's unlikely and users should use the builtin definitions anyway if(leader.equals(ExternalFollower.kFollowerDisabled)) { @@ -128,6 +176,7 @@ public REVLibError follow(ExternalFollower leader, int deviceID, boolean invert) pidControllerImpl.follow(controller, invert); } return REVLibError.kOk; + */ } public boolean isFollower() { @@ -142,14 +191,6 @@ public RelativeEncoder getEncoder() { return encoder; } - public RelativeEncoder getEncoder(SparkRelativeEncoder.Type type, int countsPerRev) { - if(type != Type.kHallSensor) { - System.err.println("Error: MockSparkMax only supports hall effect encoders"); - return null; - } - return getEncoder(); - } - @Override public void setInverted(boolean inverted) { super.setInverted(inverted); @@ -168,7 +209,7 @@ public REVLibError disableVoltageCompensation() { return REVLibError.kOk; } - public SparkPIDController getPIDController() { + public SparkClosedLoopController getPIDController() { return pidController; } @@ -188,15 +229,10 @@ public void close() { if (encoder != null) { encoder.close(); } - if (absoluteEncoderImpl != null) { - absoluteEncoderImpl.close(); - } - if (analogSensorImpl != null) { - analogSensorImpl.close(); - } - if (alternateEncoder != null) { - alternateEncoder.close(); - } + //simply drop all references for garbage collection (?) + absoluteEncoderImpl=null; + analogSensorImpl=null; + alternateEncoder=null; super.close(); } @@ -205,14 +241,15 @@ public void close() { * After this method has been called once, its output is cached for future invocations. * For this reason, the method is also {@code synchronized}. * - * @param encoderType ignored * @return the simulated encoder */ - public synchronized SparkAbsoluteEncoder getAbsoluteEncoder(SparkAbsoluteEncoder.Type encoderType) { + public synchronized SparkAbsoluteEncoder getAbsoluteEncoder() { if(absoluteEncoder == null) { - absoluteEncoderImpl = new MockedEncoder( - SimDevice.create("CANDutyCycle:" + name, port), 0, false, - true, true); + if (motor instanceof SparkFlex){ + absoluteEncoderImpl = new SparkAbsoluteEncoderSim((SparkFlex)motor); + } else { + absoluteEncoderImpl = new SparkAbsoluteEncoderSim((SparkMax)motor); + } absoluteEncoder = Mocks.createMock(SparkAbsoluteEncoder.class, absoluteEncoderImpl, new REVLibErrorAnswer()); } return absoluteEncoder; @@ -227,21 +264,15 @@ public synchronized SparkAbsoluteEncoder getAbsoluteEncoder(SparkAbsoluteEncoder * @param countsPerRev the CPR of the absolute encoder * @return the simulated encoder */ - public RelativeEncoder getAlternateEncoder(int countsPerRev) { - return getAlternateEncoder(SparkMaxAlternateEncoder.Type.kQuadrature, countsPerRev); - } - - /** - * Creates a simulated {@link SparkMaxAlternateEncoder} linked to this simulated controller. - * After this method has been called once, its output is cached for future invocations. - * For this reason, the method is also {@code synchronized}. - * - * @param encoderType ignored - * @return the simulated encoder - */ - public synchronized RelativeEncoder getAlternateEncoder(SparkMaxAlternateEncoder.Type encoderType, int countsPerRev) { + public synchronized RelativeEncoder getAlternateEncoder(int countsPerRev) { + // return getAlternateEncoder(SparkMaxAlternateEncoder.Type.kQuadrature, countsPerRev); if(alternateEncoder == null) { - alternateEncoder = new MockedEncoder(SimDevice.create("CANEncoder:%s[%d]-alternate".formatted(name, port)), 0, false, false); + if (motor instanceof SparkFlex){ + System.err.println("Error: Attempted to get Alternate Encoder of a SparkFlex: " + motor.getDeviceId()); + return encoder; + } + alternateEncoderImpl = new SparkMaxAlternateEncoderSim((SparkMax)motor); + alternateEncoder = Mocks.createMock(SparkMaxAlternateEncoder.class, absoluteEncoderImpl, new REVLibErrorAnswer()); } return alternateEncoder; } @@ -251,14 +282,15 @@ public synchronized RelativeEncoder getAlternateEncoder(SparkMaxAlternateEncoder * After this method has been called once, its output is cached for future invocations. * For this reason, the method is also {@code synchronized}. * - * @param mode setting this to {@link SparkAnalogSensor.Mode#kAbsolute} makes the position relative to the position on startup. - * We will assume that this value is always zero, so this parameter has no effect. * @return the simulated encoder */ - public synchronized SparkAnalogSensor getAnalog(SparkAnalogSensor.Mode mode) { + public synchronized SparkAnalogSensor getAnalog() { if(analogSensor == null) { - analogSensorImpl = new MockedEncoder( - SimDevice.create("CANAIn:" + name, port), 0, true, true); + if (motor instanceof SparkFlex){ + analogSensorImpl = new SparkAnalogSensorSim((SparkFlex)motor); + } else { + analogSensorImpl = new SparkAnalogSensorSim((SparkMax)motor); + } analogSensor = Mocks.createMock(SparkAnalogSensor.class, analogSensorImpl, new REVLibErrorAnswer()); } return analogSensor; @@ -293,7 +325,7 @@ public double getOutputCurrent() { @Override public void disable() { - // CANSparkBase sets the motor speed to zero rather than actually disabling the motor + // SparkBase sets the motor speed to zero rather than actually disabling the motor set(0); } diff --git a/src/main/java/org/carlmontrobotics/lib199/sim/MockSparkFlex.java b/src/main/java/org/carlmontrobotics/lib199/sim/MockSparkFlex.java index 47fb3a11..78a46f71 100644 --- a/src/main/java/org/carlmontrobotics/lib199/sim/MockSparkFlex.java +++ b/src/main/java/org/carlmontrobotics/lib199/sim/MockSparkFlex.java @@ -1,18 +1,18 @@ package org.carlmontrobotics.lib199.sim; -import org.carlmontrobotics.lib199.DummySparkMaxAnswer; import org.carlmontrobotics.lib199.Mocks; +import org.carlmontrobotics.lib199.REVLibErrorAnswer; -import com.revrobotics.CANSparkLowLevel.MotorType; -import com.revrobotics.CANSparkFlex; +import com.revrobotics.spark.SparkLowLevel.MotorType; +import com.revrobotics.spark.SparkFlex; public class MockSparkFlex extends MockSparkBase { public MockSparkFlex(int port, MotorType type) { - super(port, type, "CANSparkFlex", 7168); + super(port, type, "CANSparkFlex", 7168, NEOType.Vortex); } - public static CANSparkFlex createMockSparkFlex(int portPWM, MotorType type) { - return Mocks.createMock(CANSparkFlex.class, new MockSparkFlex(portPWM, type), new DummySparkMaxAnswer()); + public static SparkFlex createMockSparkFlex(int portPWM, MotorType type) { + return Mocks.createMock(SparkFlex.class, new MockSparkFlex(portPWM, type), new REVLibErrorAnswer()); } } diff --git a/src/main/java/org/carlmontrobotics/lib199/sim/MockSparkMax.java b/src/main/java/org/carlmontrobotics/lib199/sim/MockSparkMax.java index 653862e9..3bb57362 100644 --- a/src/main/java/org/carlmontrobotics/lib199/sim/MockSparkMax.java +++ b/src/main/java/org/carlmontrobotics/lib199/sim/MockSparkMax.java @@ -1,18 +1,18 @@ package org.carlmontrobotics.lib199.sim; -import org.carlmontrobotics.lib199.DummySparkMaxAnswer; import org.carlmontrobotics.lib199.Mocks; +import org.carlmontrobotics.lib199.REVLibErrorAnswer; -import com.revrobotics.CANSparkLowLevel.MotorType; -import com.revrobotics.CANSparkMax; +import com.revrobotics.spark.SparkLowLevel.MotorType; +import com.revrobotics.spark.SparkMax; public class MockSparkMax extends MockSparkBase { - public MockSparkMax(int port, MotorType type) { - super(port, type, "CANSparkMax", 42); + public MockSparkMax(int port, MotorType type, NEOType neoType) { + super(port, type, "CANSparkMax", 42, neoType); } - public static CANSparkMax createMockSparkMax(int portPWM, MotorType type) { - return Mocks.createMock(CANSparkMax.class, new MockSparkMax(portPWM, type), new DummySparkMaxAnswer()); + public static SparkMax createMockSparkMax(int portPWM, MotorType type, NEOType neoType) { + return Mocks.createMock(SparkMax.class, new MockSparkMax(portPWM, type, neoType), new REVLibErrorAnswer()); } } diff --git a/src/main/java/org/carlmontrobotics/lib199/sim/MockedEncoder.java b/src/main/java/org/carlmontrobotics/lib199/sim/MockedEncoder.java index 0520b7da..ed813502 100644 --- a/src/main/java/org/carlmontrobotics/lib199/sim/MockedEncoder.java +++ b/src/main/java/org/carlmontrobotics/lib199/sim/MockedEncoder.java @@ -88,22 +88,22 @@ public REVLibError setPosition(double newPosition) { return REVLibError.kOk; } - @Override - public REVLibError setMeasurementPeriod(int period_ms) { - System.err.println("(MockedEncoder) setMeasurementPeriod not implemented"); - return REVLibError.kNotImplemented; - } - - @Override - public int getMeasurementPeriod() { - System.err.println("(MockedEncoder) getMeasurementPeriod not implemented"); - return 0; - } - - @Override - public int getCountsPerRevolution() { - return countsPerRev; - } + // @Override + // public REVLibError setMeasurementPeriod(int period_ms) { + // System.err.println("(MockedEncoder) setMeasurementPeriod not implemented"); + // return REVLibError.kNotImplemented; + // } + + // @Override + // public int getMeasurementPeriod() { + // System.err.println("(MockedEncoder) getMeasurementPeriod not implemented"); + // return 0; + // } + + // @Override + // public int getCountsPerRevolution() { + // return countsPerRev; + // } /** * @return The current position of the encoder, not accounting for the position offset ({@link #setPosition(double)} and {@link #setZeroOffset(double)}) @@ -128,65 +128,65 @@ public double getVelocity() { * velocityConversionFactor; } - @Override - public REVLibError setPositionConversionFactor(double factor) { - positionConversionFactor = factor; - return REVLibError.kOk; - } - - @Override - public double getPositionConversionFactor() { - return positionConversionFactor; - } - - @Override - public REVLibError setVelocityConversionFactor(double factor) { - velocityConversionFactor = factor; - return REVLibError.kOk; - } - - @Override - public double getVelocityConversionFactor() { - return velocityConversionFactor; - } - - @Override - public REVLibError setInverted(boolean inverted) { - this.inverted = inverted; - return REVLibError.kOk; - } - - @Override - public boolean getInverted() { - return inverted; - } - - @Override - public REVLibError setAverageDepth(int depth) { - System.err.println("(MockedEncoder) setAverageDepth not implemented"); - return REVLibError.kNotImplemented; - } - - @Override - public int getAverageDepth() { - System.err.println("(MockedEncoder) getAverageDepth not implemented"); - return 0; - } - - @Override - public REVLibError setZeroOffset(double offset) { - if (!absolute) { - System.err.println("(MockedEncoder) setZeroOffset cannot be called on a relative encoder"); - return REVLibError.kParamAccessMode; - } - positionOffset = offset; - return REVLibError.kOk; - } - - @Override - public double getZeroOffset() { - return positionOffset; - } + // @Override + // public REVLibError setPositionConversionFactor(double factor) { + // positionConversionFactor = factor; + // return REVLibError.kOk; + // } + + // @Override + // public double getPositionConversionFactor() { + // return positionConversionFactor; + // } + + // @Override + // public REVLibError setVelocityConversionFactor(double factor) { + // velocityConversionFactor = factor; + // return REVLibError.kOk; + // } + + // @Override + // public double getVelocityConversionFactor() { + // return velocityConversionFactor; + // } + + // @Override + // public REVLibError setInverted(boolean inverted) { + // this.inverted = inverted; + // return REVLibError.kOk; + // } + + // @Override + // public boolean getInverted() { + // return inverted; + // } + + // @Override + // public REVLibError setAverageDepth(int depth) { + // System.err.println("(MockedEncoder) setAverageDepth not implemented"); + // return REVLibError.kNotImplemented; + // } + + // @Override + // public int getAverageDepth() { + // System.err.println("(MockedEncoder) getAverageDepth not implemented"); + // return 0; + // } + + // @Override + // public REVLibError setZeroOffset(double offset) { + // if (!absolute) { + // System.err.println("(MockedEncoder) setZeroOffset cannot be called on a relative encoder"); + // return REVLibError.kParamAccessMode; + // } + // positionOffset = offset; + // return REVLibError.kOk; + // } + + // @Override + // public double getZeroOffset() { + // return positionOffset; + // } @Override public void close() { diff --git a/src/main/java/org/carlmontrobotics/lib199/sim/MockedSparkMaxPIDController.java b/src/main/java/org/carlmontrobotics/lib199/sim/MockedSparkMaxPIDController.java index 13629f0f..c4720aa7 100644 --- a/src/main/java/org/carlmontrobotics/lib199/sim/MockedSparkMaxPIDController.java +++ b/src/main/java/org/carlmontrobotics/lib199/sim/MockedSparkMaxPIDController.java @@ -3,14 +3,15 @@ import java.util.Map; import java.util.concurrent.ConcurrentHashMap; -import com.revrobotics.CANSparkMax; -import com.revrobotics.MotorFeedbackSensor; import com.revrobotics.REVLibError; -import com.revrobotics.SparkAbsoluteEncoder; -import com.revrobotics.SparkMaxAlternateEncoder; -import com.revrobotics.SparkAnalogSensor; -import com.revrobotics.SparkPIDController; -import com.revrobotics.SparkRelativeEncoder; +import com.revrobotics.spark.SparkAbsoluteEncoder; +import com.revrobotics.spark.SparkAnalogSensor; +import com.revrobotics.spark.SparkClosedLoopController; +import com.revrobotics.spark.SparkMax; +import com.revrobotics.spark.SparkMaxAlternateEncoder; +import com.revrobotics.spark.SparkRelativeEncoder; +import com.revrobotics.spark.config.ClosedLoopConfig; +import com.revrobotics.spark.config.MAXMotionConfig; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.controller.PIDController; @@ -24,7 +25,7 @@ public class MockedSparkMaxPIDController { public final Map slots = new ConcurrentHashMap<>(); public final MockedMotorBase motor; public Slot activeSlot; - public CANSparkMax.ControlType controlType = CANSparkMax.ControlType.kDutyCycle; + public SparkMax.ControlType controlType = SparkMax.ControlType.kDutyCycle; public MotorController leader = null; public boolean invertLeader = false; public double setpoint = 0.0; @@ -54,16 +55,16 @@ public double calculate(double currentDraw) { case kVelocity: output = activeSlot.pidController.calculate(feedbackDevice.getVelocity(), setpoint); break; - case kSmartMotion: + case kMAXMotionPositionControl: output = activeSlot.profiledPIDController.calculate(feedbackDevice.getPosition(), setpoint); if(Math.abs(activeSlot.profiledPIDController.getGoal().velocity) < activeSlot.smartMotionMinVelocity) { - output = 0; + output = 0;//FIXME max motion doesn't have min velocity!!! } break; case kCurrent: output = activeSlot.pidController.calculate(currentDraw, setpoint); break; - case kSmartVelocity: + case kMAXMotionVelocityControl: default: throw new IllegalArgumentException("Unsupported ControlType: " + controlType); } @@ -74,7 +75,7 @@ public double calculate(double currentDraw) { public void setDutyCycle(double speed) { setpoint = speed; - controlType = CANSparkMax.ControlType.kDutyCycle; + controlType = SparkMax.ControlType.kDutyCycle; stopFollowing(); motor.setClosedLoopControl(false); } @@ -214,8 +215,8 @@ public double getP(int slotID) { return slot.pidController.getP(); } - public SparkPIDController.AccelStrategy getSmartMotionAccelStrategy(int slotID) { - return SparkPIDController.AccelStrategy.kTrapezoidal; + public MAXMotionConfig.MAXMotionPositionMode getSmartMotionAccelStrategy(int slotID) { + return MAXMotionConfig.MAXMotionPositionMode.kMAXMotionTrapezoidal; } public double getSmartMotionAllowedClosedLoopError(int slotID) { @@ -245,8 +246,8 @@ public REVLibError setD(double gain, int slotID) { return REVLibError.kOk; } - public REVLibError setFeedbackDevice(MotorFeedbackSensor sensor) { - if (sensor instanceof SparkRelativeEncoder + public REVLibError setFeedbackDevice(Object sensor) { + if ( sensor instanceof SparkRelativeEncoder || sensor instanceof SparkMaxAlternateEncoder || sensor instanceof SparkAnalogSensor || sensor instanceof SparkAbsoluteEncoder @@ -386,20 +387,20 @@ public REVLibError setP(double gain, int slotID) { return REVLibError.kOk; } - public REVLibError setReference(double value, CANSparkMax.ControlType ctrl) { + public REVLibError setReference(double value, SparkMax.ControlType ctrl) { return setReference(value, ctrl, 0); } - public REVLibError setReference(double value, CANSparkMax.ControlType ctrl, int pidSlot) { + public REVLibError setReference(double value, SparkMax.ControlType ctrl, int pidSlot) { return setReference(value, ctrl, pidSlot, 0); } - public REVLibError setReference(double value, CANSparkMax.ControlType ctrl, int pidSlot, double arbFeedforward) { - return setReference(value, ctrl, pidSlot, arbFeedforward, SparkPIDController.ArbFFUnits.kVoltage); + public REVLibError setReference(double value, SparkMax.ControlType ctrl, int pidSlot, double arbFeedforward) { + return setReference(value, ctrl, pidSlot, arbFeedforward, SparkClosedLoopController.ArbFFUnits.kVoltage); } - public REVLibError setReference(double value, CANSparkMax.ControlType ctrl, int pidSlot, double arbFeedforward, SparkPIDController.ArbFFUnits arbFFUnits) { - if(ctrl == CANSparkMax.ControlType.kSmartVelocity) { + public REVLibError setReference(double value, SparkMax.ControlType ctrl, int pidSlot, double arbFeedforward, SparkClosedLoopController.ArbFFUnits arbFFUnits) { + if(ctrl == SparkMax.ControlType.kSmartVelocity) { System.err.println("(MockedSparkMaxPIDController): setReference() with ControlType.kSmartVelocity is not currently implemented"); return REVLibError.kNotImplemented; } @@ -440,8 +441,8 @@ public REVLibError setReference(double value, CANSparkMax.ControlType ctrl, int return REVLibError.kOk; } - public REVLibError setSmartMotionAccelStrategy(SparkPIDController.AccelStrategy accelStrategy, int slotID) { - if(accelStrategy != SparkPIDController.AccelStrategy.kTrapezoidal) { + public REVLibError setSmartMotionAccelStrategy(MAXMotionConfig.MAXMotionPositionMode accelStrategy, int slotID) { + if(accelStrategy != MAXMotionConfig.MAXMotionPositionMode.kMAXMotionTrapezoidal) { System.err.println("(MockedSparkMaxPIDController) Ignoring command to set accel strategy on slot " + slotID + " to " + accelStrategy + ". Only AccelStrategy.kTrapezoidal is supported."); return REVLibError.kParamNotImplementedDeprecated; } diff --git a/src/main/java/org/carlmontrobotics/lib199/swerve/SwerveModule.java b/src/main/java/org/carlmontrobotics/lib199/swerve/SwerveModule.java index d39dc473..b83c112d 100644 --- a/src/main/java/org/carlmontrobotics/lib199/swerve/SwerveModule.java +++ b/src/main/java/org/carlmontrobotics/lib199/swerve/SwerveModule.java @@ -8,11 +8,15 @@ import org.mockito.internal.reporting.SmartPrinter; -import com.ctre.phoenix6.signals.AbsoluteSensorRangeValue; +// import com.ctre.phoenix6.signals.AbsoluteSensorRangeValue; import com.ctre.phoenix6.configs.CANcoderConfiguration; import com.ctre.phoenix6.hardware.CANcoder; -import com.revrobotics.CANSparkMax; -import com.revrobotics.CANSparkBase.IdleMode; +import com.revrobotics.spark.SparkMax; +import com.revrobotics.spark.SparkBase.PersistMode; +import com.revrobotics.spark.SparkBase.ResetMode; +import com.revrobotics.spark.config.SparkBaseConfig.IdleMode; +import com.revrobotics.spark.config.SparkBaseConfig; +import com.revrobotics.spark.config.SparkMaxConfig; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.controller.PIDController; @@ -23,11 +27,12 @@ import edu.wpi.first.math.kinematics.SwerveModuleState; import edu.wpi.first.math.trajectory.TrapezoidProfile; import edu.wpi.first.math.util.Units; -import edu.wpi.first.units.Mass; +import edu.wpi.first.units.measure.Mass; import edu.wpi.first.units.Measure; import edu.wpi.first.util.sendable.Sendable; import edu.wpi.first.util.sendable.SendableBuilder; import edu.wpi.first.util.sendable.SendableRegistry; +import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab; @@ -41,8 +46,11 @@ public class SwerveModule implements Sendable { public enum ModuleType {FL, FR, BL, BR}; private SwerveConfig config; + private SparkMaxConfig turnConfig = new SparkMaxConfig(); + private SparkMaxConfig driveConfig = new SparkMaxConfig(); + private ModuleType type; - private CANSparkMax drive, turn; + private SparkMax drive, turn; private CANcoder turnEncoder; private PIDController drivePIDController; private ProfiledPIDController turnPIDController; @@ -57,7 +65,7 @@ public enum ModuleType {FL, FR, BL, BR}; private double turnSpeedCorrectionVolts, turnFFVolts, turnVolts; private double maxTurnVelocityWithoutTippingRps; - public SwerveModule(SwerveConfig config, ModuleType type, CANSparkMax drive, CANSparkMax turn, CANcoder turnEncoder, + public SwerveModule(SwerveConfig config, ModuleType type, SparkMax drive, SparkMax turn, CANcoder turnEncoder, int arrIndex, Supplier pitchDegSupplier, Supplier rollDegSupplier) { //SmartDashboard.putNumber("Target Angle (deg)", 0.0); String moduleString = type.toString(); @@ -69,11 +77,15 @@ public SwerveModule(SwerveConfig config, ModuleType type, CANSparkMax drive, CAN this.type = type; this.drive = drive; - double positionConstant = config.wheelDiameterMeters * Math.PI / config.driveGearing; - drive.setInverted(config.driveInversion[arrIndex]); - drive.getEncoder().setPositionConversionFactor(positionConstant); - drive.getEncoder().setVelocityConversionFactor(positionConstant / 60); - turn.setInverted(config.turnInversion[arrIndex]); + driveConfig.inverted(config.driveInversion[arrIndex]); + turnConfig.inverted(config.turnInversion[arrIndex]); + + double drivePositionFactor = config.wheelDiameterMeters * Math.PI / config.driveGearing; + final double driveVelocityFactor = drivePositionFactor / 60;//why by 60? + driveConfig.encoder + .positionConversionFactor(drivePositionFactor) + .velocityConversionFactor(driveVelocityFactor); + maxControllableAccerlationRps2 = 0; final double normalForceNewtons = 83.2 /* lbf */ * 4.4482 /* N/lbf */ / 4 /* numModules */; double wheelTorqueLimitNewtonMeters = normalForceNewtons * config.mu * config.wheelDiameterMeters / 2; @@ -83,7 +95,7 @@ public SwerveModule(SwerveConfig config, ModuleType type, CANSparkMax drive, CAN final double neoStallCurrentAmps = 166; double currentLimitAmps = neoFreeCurrentAmps + 2*motorTorqueLimitNewtonMeters / neoStallTorqueNewtonMeters * (neoStallCurrentAmps-neoFreeCurrentAmps); // SmartDashboard.putNumber(type.toString() + " current limit (amps)", currentLimitAmps); - drive.setSmartCurrentLimit((int)Math.min(50, currentLimitAmps)); + driveConfig.smartCurrentLimit(Math.min(50, (int)currentLimitAmps)); this.forwardSimpleMotorFF = new SimpleMotorFeedforward(config.kForwardVolts[arrIndex], config.kForwardVels[arrIndex], @@ -96,8 +108,10 @@ public SwerveModule(SwerveConfig config, ModuleType type, CANSparkMax drive, CAN config.drivekI[arrIndex], config.drivekD[arrIndex]); - /* offset for 1 CANcoder count */ - drivetoleranceMPerS = (1.0 / (double)(drive.getEncoder().getCountsPerRevolution()) * positionConstant) / Units.millisecondsToSeconds(drive.getEncoder().getMeasurementPeriod() * drive.getEncoder().getAverageDepth()); + /* offset for 1 relative encoder count */ + drivetoleranceMPerS = (1.0 + / (double)(drive.configAccessor.encoder.getCountsPerRevolution()) * drivePositionFactor) + / Units.millisecondsToSeconds(drive.configAccessor.signals.getPrimaryEncoderPositionPeriodMs() * drive.configAccessor.encoder.getQuadratureAverageDepth()); drivePIDController.setTolerance(drivetoleranceMPerS); //System.out.println("Velocity Constant: " + (positionConstant / 60)); @@ -120,21 +134,23 @@ public SwerveModule(SwerveConfig config, ModuleType type, CANSparkMax drive, CAN turnConstraints = new TrapezoidProfile.Constraints(maxAchievableTurnVelocityRps, maxAchievableTurnAccelerationRps2); lastAngle = 0.0; - turnPIDController = new ProfiledPIDController(config.turnkP[arrIndex], - config.turnkI[arrIndex], - config.turnkD[arrIndex], - turnConstraints); + turnPIDController = new ProfiledPIDController( + config.turnkP[arrIndex], + config.turnkI[arrIndex], + config.turnkD[arrIndex], + turnConstraints); turnPIDController.enableContinuousInput(-.5, .5); turnPIDController.setTolerance(turnToleranceRot); - - CANcoderConfiguration configs = new CANcoderConfiguration(); - configs.MagnetSensor.AbsoluteSensorRange = AbsoluteSensorRangeValue.Signed_PlusMinusHalf; - this.turnEncoder = turnEncoder; - this.turnEncoder.getConfigurator().apply(configs); this.driveModifier = config.driveModifier; this.reversed = config.reversed[arrIndex]; this.turnZeroDeg = config.turnZeroDeg[arrIndex]; + + CANcoderConfiguration CANconfig = new CANcoderConfiguration(); + CANconfig.MagnetSensor.AbsoluteSensorDiscontinuityPoint = .5; + this.turnEncoder = turnEncoder; + // CANconfig.MagnetSensor.MagnetOffset=-turnZeroDeg; //done in getModuleAngle. + this.turnEncoder.getConfigurator().apply(CANconfig); turnPIDController.reset(getModuleAngle()); @@ -159,6 +175,10 @@ public SwerveModule(SwerveConfig config, ModuleType type, CANSparkMax drive, CAN SendableRegistry.addLW(this, "SwerveModule", type.toString()); + //do stuff here + drive.configure(driveConfig, ResetMode.kNoResetSafeParameters, PersistMode.kPersistParameters); + turn.configure(turnConfig, ResetMode.kNoResetSafeParameters, PersistMode.kPersistParameters); + } public ModuleType getType() { @@ -168,15 +188,20 @@ public ModuleType getType() { private double prevTurnVelocity = 0; public void periodic() { drivePeriodic(); - //updateSmartDashboard(); + updateSmartDashboard(); turnPeriodic(); } public void drivePeriodic() { String moduleString = type.toString(); double actualSpeed = getCurrentSpeed(); - double targetVoltage = (actualSpeed >= 0 ? forwardSimpleMotorFF : - backwardSimpleMotorFF).calculate(desiredSpeed, calculateAntiGravitationalA(pitchDegSupplier.get(), rollDegSupplier.get()));//clippedAcceleration); + double extraAccel = calculateAntiGravitationalA(pitchDegSupplier.get(), rollDegSupplier.get()); + double targetVoltage = (actualSpeed >= 0 ? forwardSimpleMotorFF : backwardSimpleMotorFF) + .calculateWithVelocities( + actualSpeed, + desiredSpeed + extraAccel * TimedRobot.kDefaultPeriod//m/s + ( m/s^2 * s ) + );//clippedAcceleration); + //calculateAntiGravitationalA(pitchDegSupplier.get(), rollDegSupplier.get()) // Use robot characterization as a simple physical model to account for internal resistance, frcition, etc. // Add a PID adjustment for error correction (also "drives" the actual speed to the desired speed) @@ -223,7 +248,7 @@ public void turnPeriodic() { // SmartDashboard.putNumber("previous turn Velocity", prevTurnVelocity); // SmartDashboard.putNumber("state velocity",state.velocity); - turnFFVolts = turnSimpleMotorFeedforward.calculate(state.velocity, 0);//(state.velocity-prevTurnVelocity) / period); + turnFFVolts = turnSimpleMotorFeedforward.calculate(state.velocity);//(state.velocity-prevTurnVelocity) / period); turnVolts = turnFFVolts + turnSpeedCorrectionVolts; if (!turnPIDController.atGoal()) { turn.setVoltage(MathUtil.clamp(turnVolts, -12.0, 12.0)); @@ -303,7 +328,7 @@ private void setAngle(double angle) { * @return module angle in degrees */ public double getModuleAngle() { - return MathUtil.inputModulus(Units.rotationsToDegrees(turnEncoder.getAbsolutePosition().getValue()) - turnZeroDeg, -180, 180); + return MathUtil.inputModulus(Units.rotationsToDegrees(turnEncoder.getAbsolutePosition().getValueAsDouble()) - turnZeroDeg, -180, 180); } /** @@ -339,9 +364,9 @@ public double getCurrentSpeed() { public void updateSmartDashboard() { String moduleString = type.toString(); // Display the position of the quadrature encoder. - SmartDashboard.putNumber(moduleString + " Incremental Position", turnEncoder.getPosition().getValue()); + SmartDashboard.putNumber(moduleString + " Incremental Position", turnEncoder.getPosition().getValueAsDouble()); // Display the position of the analog encoder. - SmartDashboard.putNumber(moduleString + " Absolute Angle (deg)", Units.rotationsToDegrees(turnEncoder.getAbsolutePosition().getValue())); + SmartDashboard.putNumber(moduleString + " Absolute Angle (deg)", Units.rotationsToDegrees(turnEncoder.getAbsolutePosition().getValueAsDouble())); // Display the module angle as calculated using the absolute encoder. SmartDashboard.putNumber(moduleString + " Turn Measured Pos (deg)", getModuleAngle()); SmartDashboard.putNumber(moduleString + " Encoder Position", drive.getEncoder().getPosition()); @@ -370,14 +395,14 @@ public void updateSmartDashboard() { if (drivePIDController.getD() != drivekD) { drivePIDController.setD(drivekD); } - double driveTolerance = SmartDashboard.getNumber(moduleString + " Drive Tolerance", drivePIDController.getPositionTolerance()); - if (drivePIDController.getPositionTolerance() != driveTolerance) { + double driveTolerance = SmartDashboard.getNumber(moduleString + " Drive Tolerance", drivePIDController.getErrorTolerance()); + if (drivePIDController.getErrorTolerance() != driveTolerance) { drivePIDController.setTolerance(driveTolerance); } - double drivekS = SmartDashboard.getNumber(moduleString + " Drive kS", forwardSimpleMotorFF.ks); - double drivekV = SmartDashboard.getNumber(moduleString + " Drive kV", forwardSimpleMotorFF.kv); - double drivekA = SmartDashboard.getNumber(moduleString + " Drive kA", forwardSimpleMotorFF.ka); - if (forwardSimpleMotorFF.ks != drivekS || forwardSimpleMotorFF.kv != drivekV || forwardSimpleMotorFF.ka != drivekA) { + double drivekS = SmartDashboard.getNumber(moduleString + " Drive kS", forwardSimpleMotorFF.getKs()); + double drivekV = SmartDashboard.getNumber(moduleString + " Drive kV", forwardSimpleMotorFF.getKv()); + double drivekA = SmartDashboard.getNumber(moduleString + " Drive kA", forwardSimpleMotorFF.getKa()); + if (forwardSimpleMotorFF.getKs() != drivekS || forwardSimpleMotorFF.getKv() != drivekV || forwardSimpleMotorFF.getKa() != drivekA) { forwardSimpleMotorFF = new SimpleMotorFeedforward(drivekS, drivekV, drivekA); backwardSimpleMotorFF = new SimpleMotorFeedforward(drivekS, drivekV, drivekA); } @@ -393,10 +418,10 @@ public void updateSmartDashboard() { if (turnPIDController.getPositionTolerance() != turnTolerance) { turnPIDController.setTolerance(turnTolerance); } - double kS = SmartDashboard.getNumber(moduleString + " Swerve kS", turnSimpleMotorFeedforward.ks); - double kV = SmartDashboard.getNumber(moduleString + " Swerve kV", turnSimpleMotorFeedforward.kv); - double kA = SmartDashboard.getNumber(moduleString + " Swerve kA", turnSimpleMotorFeedforward.ka); - if (turnSimpleMotorFeedforward.ks != kS || turnSimpleMotorFeedforward.kv != kV || turnSimpleMotorFeedforward.ka != kA) { + double kS = SmartDashboard.getNumber(moduleString + " Swerve kS", turnSimpleMotorFeedforward.getKs()); + double kV = SmartDashboard.getNumber(moduleString + " Swerve kV", turnSimpleMotorFeedforward.getKv()); + double kA = SmartDashboard.getNumber(moduleString + " Swerve kA", turnSimpleMotorFeedforward.getKa()); + if (turnSimpleMotorFeedforward.getKs() != kS || turnSimpleMotorFeedforward.getKv() != kV || turnSimpleMotorFeedforward.getKa() != kA) { turnSimpleMotorFeedforward = new SimpleMotorFeedforward(kS, kV, kA); maxAchievableTurnVelocityRps = 0.5 * turnSimpleMotorFeedforward.maxAchievableVelocity(12.0, 0); maxAchievableTurnAccelerationRps2 = 0.5 * turnSimpleMotorFeedforward.maxAchievableAcceleration(12.0, maxAchievableTurnVelocityRps); @@ -404,18 +429,20 @@ public void updateSmartDashboard() { } public void toggleMode() { - if (drive.getIdleMode() == IdleMode.kBrake && turn.getIdleMode() == IdleMode.kCoast) coast(); + if (drive.configAccessor.getIdleMode() == IdleMode.kBrake && turn.configAccessor.getIdleMode() == IdleMode.kCoast) coast(); else brake(); } public void brake() { - drive.setIdleMode(IdleMode.kBrake); - turn.setIdleMode(IdleMode.kBrake); + SparkBaseConfig config = new SparkMaxConfig().idleMode(IdleMode.kBrake); + drive.configure(config, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters); + turn .configure(config, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters); } public void coast() { - drive.setIdleMode(IdleMode.kCoast); - turn.setIdleMode(IdleMode.kCoast); + SparkBaseConfig config = new SparkMaxConfig().idleMode(IdleMode.kCoast); + drive.configure(config, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters); + turn .configure(config, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters); } /** @@ -434,8 +461,8 @@ public void initSendable(SendableBuilder builder) { builder.setActuator(true); builder.setSafeState(() -> setSpeed(0)); builder.setSmartDashboardType("SwerveModule"); - builder.addDoubleProperty("Incremental Position", () -> turnEncoder.getPosition().getValue(), null); - builder.addDoubleProperty("Absolute Angle (deg)", () -> Units.rotationsToDegrees(turnEncoder.getAbsolutePosition().getValue()), null); + builder.addDoubleProperty("Incremental Position", () -> turnEncoder.getPosition().getValueAsDouble(), null); + builder.addDoubleProperty("Absolute Angle (deg)", () -> Units.rotationsToDegrees(turnEncoder.getAbsolutePosition().getValueAsDouble()), null); builder.addDoubleProperty("Turn Measured Pos (deg)", this::getModuleAngle, null); builder.addDoubleProperty("Encoder Position", drive.getEncoder()::getPosition, null); // Display the speed that the robot thinks it is travelling at. @@ -463,7 +490,7 @@ public void initSendable(SendableBuilder builder) { * @param turnMoiKgM2 the moment of inertia of the part of the module turned by the turn motor (in kg m^2) * @return a SwerveModuleSim that simulates the physics of this swerve module. */ - public SwerveModuleSim createSim(Measure massOnWheel, double turnGearing, double turnMoiKgM2) { + public SwerveModuleSim createSim(Mass massOnWheel, double turnGearing, double turnMoiKgM2) { double driveMoiKgM2 = massOnWheel.in(Kilogram) * Math.pow(config.wheelDiameterMeters/2, 2); return new SwerveModuleSim(drive.getDeviceId(), config.driveGearing, driveMoiKgM2, turn.getDeviceId(), turnEncoder.getDeviceID(), turnGearing, turnMoiKgM2); diff --git a/src/main/java/org/carlmontrobotics/lib199/swerve/SwerveModuleSim.java b/src/main/java/org/carlmontrobotics/lib199/swerve/SwerveModuleSim.java index 14c52890..4987540d 100644 --- a/src/main/java/org/carlmontrobotics/lib199/swerve/SwerveModuleSim.java +++ b/src/main/java/org/carlmontrobotics/lib199/swerve/SwerveModuleSim.java @@ -4,11 +4,13 @@ import org.carlmontrobotics.lib199.sim.MockedEncoder; import edu.wpi.first.math.MathUtil; +import edu.wpi.first.math.system.LinearSystem; import edu.wpi.first.math.system.plant.DCMotor; -import edu.wpi.first.units.Distance; -import edu.wpi.first.units.Mass; +import edu.wpi.first.math.system.plant.LinearSystemId; +import edu.wpi.first.units.measure.Distance; +import edu.wpi.first.units.measure.Mass; import edu.wpi.first.units.Measure; -import edu.wpi.first.units.Mult; +import edu.wpi.first.units.measure.Mult; import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj.simulation.DCMotorSim; @@ -35,12 +37,15 @@ public SwerveModuleSim(int drivePortNum, double driveGearing, double driveMoiKgM int turnMotorPortNum, int turnEncoderPortNum, double turnGearing, double turnMoiKgM2) { driveMotorSim = new SimDeviceSim("CANMotor:CANSparkMax", drivePortNum); driveEncoderSim = new SimDeviceSim("CANEncoder:CANSparkMax", drivePortNum); - drivePhysicsSim = new DCMotorSim(DCMotor.getNEO(1), driveGearing, driveMoiKgM2); + DCMotor dcmotor = DCMotor.getNEO(1); + drivePhysicsSim = new DCMotorSim(LinearSystemId.createDCMotorSystem(dcmotor, driveMoiKgM2, driveGearing), dcmotor);//FIXME WHAT DO WE WANT THE MEASUREMENT STDDEVS TO BE? (LAST ARG) this.driveGearing = driveGearing; turnMotorSim = new SimDeviceSim("CANMotor:CANSparkMax", turnMotorPortNum); turnEncoderSim = new SimDeviceSim("CANDutyCycle:CANCoder", turnEncoderPortNum); - turnPhysicsSim = new DCMotorSim(DCMotor.getNEO(1), turnGearing, turnMoiKgM2); + turnPhysicsSim = new DCMotorSim( + LinearSystemId.createDCMotorSystem(dcmotor, turnMoiKgM2, turnGearing), + dcmotor); } /** diff --git a/vendordeps/NavX.json b/vendordeps/NavX.json deleted file mode 100644 index e978a5f7..00000000 --- a/vendordeps/NavX.json +++ /dev/null @@ -1,40 +0,0 @@ -{ - "fileName": "NavX.json", - "name": "NavX", - "version": "2024.1.0", - "uuid": "cb311d09-36e9-4143-a032-55bb2b94443b", - "frcYear": "2024", - "mavenUrls": [ - "https://dev.studica.com/maven/release/2024/" - ], - "jsonUrl": "https://dev.studica.com/releases/2024/NavX.json", - "javaDependencies": [ - { - "groupId": "com.kauailabs.navx.frc", - "artifactId": "navx-frc-java", - "version": "2024.1.0" - } - ], - "jniDependencies": [], - "cppDependencies": [ - { - "groupId": "com.kauailabs.navx.frc", - "artifactId": "navx-frc-cpp", - "version": "2024.1.0", - "headerClassifier": "headers", - "sourcesClassifier": "sources", - "sharedLibrary": false, - "libName": "navx_frc", - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "linuxathena", - "linuxraspbian", - "linuxarm32", - "linuxarm64", - "linuxx86-64", - "osxuniversal", - "windowsx86-64" - ] - } - ] -} \ No newline at end of file diff --git a/vendordeps/PathplannerLib.json b/vendordeps/PathplannerLib-2025.2.1.json similarity index 85% rename from vendordeps/PathplannerLib.json rename to vendordeps/PathplannerLib-2025.2.1.json index 6dc648db..71e25f3d 100644 --- a/vendordeps/PathplannerLib.json +++ b/vendordeps/PathplannerLib-2025.2.1.json @@ -1,9 +1,9 @@ { - "fileName": "PathplannerLib.json", + "fileName": "PathplannerLib-2025.2.1.json", "name": "PathplannerLib", - "version": "2024.2.8", + "version": "2025.2.1", "uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786", - "frcYear": "2024", + "frcYear": "2025", "mavenUrls": [ "https://3015rangerrobotics.github.io/pathplannerlib/repo" ], @@ -12,7 +12,7 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-java", - "version": "2024.2.8" + "version": "2025.2.1" } ], "jniDependencies": [], @@ -20,7 +20,7 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-cpp", - "version": "2024.2.8", + "version": "2025.2.1", "libName": "PathplannerLib", "headerClassifier": "headers", "sharedLibrary": false, diff --git a/vendordeps/Phoenix5.json b/vendordeps/Phoenix5-5.35.1.json similarity index 75% rename from vendordeps/Phoenix5.json rename to vendordeps/Phoenix5-5.35.1.json index ff7359e1..69df8b53 100644 --- a/vendordeps/Phoenix5.json +++ b/vendordeps/Phoenix5-5.35.1.json @@ -1,43 +1,56 @@ { - "fileName": "Phoenix5.json", + "fileName": "Phoenix5-5.35.1.json", "name": "CTRE-Phoenix (v5)", - "version": "5.33.1", - "frcYear": 2024, + "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-frc2024-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.json", - "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2024-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-latest.json" + }, + { + "uuid": "fbc886a4-2cec-40c0-9835-71086a8cc3df", + "errorMessage": "Users cannot have both the replay and regular Phoenix 5 vendordeps in their robot program.", + "offlineFileName": "Phoenix5-replay-frc2025-latest.json" } ], "javaDependencies": [ { "groupId": "com.ctre.phoenix", "artifactId": "api-java", - "version": "5.33.1" + "version": "5.35.1" }, { "groupId": "com.ctre.phoenix", "artifactId": "wpiapi-java", - "version": "5.33.1" + "version": "5.35.1" } ], "jniDependencies": [ { "groupId": "com.ctre.phoenix", "artifactId": "cci", - "version": "5.33.1", + "version": "5.35.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "linuxathena" ], "simMode": "hwsim" @@ -45,12 +58,13 @@ { "groupId": "com.ctre.phoenix.sim", "artifactId": "cci-sim", - "version": "5.33.1", + "version": "5.35.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -60,7 +74,7 @@ { "groupId": "com.ctre.phoenix", "artifactId": "wpiapi-cpp", - "version": "5.33.1", + "version": "5.35.1", "libName": "CTRE_Phoenix_WPI", "headerClassifier": "headers", "sharedLibrary": true, @@ -68,6 +82,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "linuxathena" ], "simMode": "hwsim" @@ -75,7 +90,7 @@ { "groupId": "com.ctre.phoenix", "artifactId": "api-cpp", - "version": "5.33.1", + "version": "5.35.1", "libName": "CTRE_Phoenix", "headerClassifier": "headers", "sharedLibrary": true, @@ -83,6 +98,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "linuxathena" ], "simMode": "hwsim" @@ -90,7 +106,7 @@ { "groupId": "com.ctre.phoenix", "artifactId": "cci", - "version": "5.33.1", + "version": "5.35.1", "libName": "CTRE_PhoenixCCI", "headerClassifier": "headers", "sharedLibrary": true, @@ -98,6 +114,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "linuxathena" ], "simMode": "hwsim" @@ -105,7 +122,7 @@ { "groupId": "com.ctre.phoenix.sim", "artifactId": "wpiapi-cpp-sim", - "version": "5.33.1", + "version": "5.35.1", "libName": "CTRE_Phoenix_WPISim", "headerClassifier": "headers", "sharedLibrary": true, @@ -113,6 +130,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -120,7 +138,7 @@ { "groupId": "com.ctre.phoenix.sim", "artifactId": "api-cpp-sim", - "version": "5.33.1", + "version": "5.35.1", "libName": "CTRE_PhoenixSim", "headerClassifier": "headers", "sharedLibrary": true, @@ -128,6 +146,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -135,7 +154,7 @@ { "groupId": "com.ctre.phoenix.sim", "artifactId": "cci-sim", - "version": "5.33.1", + "version": "5.35.1", "libName": "CTRE_PhoenixCCISim", "headerClassifier": "headers", "sharedLibrary": true, @@ -143,6 +162,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" diff --git a/vendordeps/Phoenix6.json b/vendordeps/Phoenix6-25.1.0.json similarity index 77% rename from vendordeps/Phoenix6.json rename to vendordeps/Phoenix6-25.1.0.json index 2b7d1720..473f6a89 100644 --- a/vendordeps/Phoenix6.json +++ b/vendordeps/Phoenix6-25.1.0.json @@ -1,76 +1,94 @@ { - "fileName": "Phoenix6.json", + "fileName": "Phoenix6-25.1.0.json", "name": "CTRE-Phoenix (v6)", - "version": "24.2.0", - "frcYear": 2024, + "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-frc2024-latest.json", + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-latest.json", "conflictsWith": [ { - "uuid": "3fcf3402-e646-4fa6-971e-18afe8173b1a", - "errorMessage": "The combined Phoenix-6-And-5 vendordep is no longer supported. Please remove the vendordep and instead add both the latest Phoenix 6 vendordep and Phoenix 5 vendordep.", - "offlineFileName": "Phoenix6And5.json" + "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" } ], "javaDependencies": [ { "groupId": "com.ctre.phoenix6", "artifactId": "wpiapi-java", - "version": "24.2.0" + "version": "25.1.0" } ], "jniDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "api-cpp", + "version": "25.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, { "groupId": "com.ctre.phoenix6", "artifactId": "tools", - "version": "24.2.0", + "version": "25.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "linuxathena" ], "simMode": "hwsim" }, { "groupId": "com.ctre.phoenix6.sim", - "artifactId": "tools-sim", - "version": "24.2.0", + "artifactId": "api-cpp-sim", + "version": "25.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" }, { "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simTalonSRX", - "version": "24.2.0", + "artifactId": "tools-sim", + "version": "25.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" }, { "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simTalonFX", - "version": "24.2.0", + "artifactId": "simTalonSRX", + "version": "25.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -78,12 +96,13 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simVictorSPX", - "version": "24.2.0", + "version": "25.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -91,12 +110,13 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simPigeonIMU", - "version": "24.2.0", + "version": "25.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -104,12 +124,13 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simCANCoder", - "version": "24.2.0", + "version": "25.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -117,12 +138,13 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFX", - "version": "24.2.0", + "version": "25.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -130,12 +152,13 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANcoder", - "version": "24.2.0", + "version": "25.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -143,12 +166,27 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProPigeon2", - "version": "24.2.0", + "version": "25.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANrange", + "version": "25.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -158,7 +196,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "wpiapi-cpp", - "version": "24.2.0", + "version": "25.1.0", "libName": "CTRE_Phoenix6_WPI", "headerClassifier": "headers", "sharedLibrary": true, @@ -166,6 +204,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "linuxathena" ], "simMode": "hwsim" @@ -173,7 +212,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "tools", - "version": "24.2.0", + "version": "25.1.0", "libName": "CTRE_PhoenixTools", "headerClassifier": "headers", "sharedLibrary": true, @@ -181,6 +220,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "linuxathena" ], "simMode": "hwsim" @@ -188,7 +228,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "wpiapi-cpp-sim", - "version": "24.2.0", + "version": "25.1.0", "libName": "CTRE_Phoenix6_WPISim", "headerClassifier": "headers", "sharedLibrary": true, @@ -196,6 +236,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -203,7 +244,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "tools-sim", - "version": "24.2.0", + "version": "25.1.0", "libName": "CTRE_PhoenixTools_Sim", "headerClassifier": "headers", "sharedLibrary": true, @@ -211,6 +252,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -218,7 +260,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonSRX", - "version": "24.2.0", + "version": "25.1.0", "libName": "CTRE_SimTalonSRX", "headerClassifier": "headers", "sharedLibrary": true, @@ -226,21 +268,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simTalonFX", - "version": "24.2.0", - "libName": "CTRE_SimTalonFX", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -248,7 +276,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simVictorSPX", - "version": "24.2.0", + "version": "25.1.0", "libName": "CTRE_SimVictorSPX", "headerClassifier": "headers", "sharedLibrary": true, @@ -256,6 +284,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -263,7 +292,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simPigeonIMU", - "version": "24.2.0", + "version": "25.1.0", "libName": "CTRE_SimPigeonIMU", "headerClassifier": "headers", "sharedLibrary": true, @@ -271,6 +300,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -278,7 +308,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simCANCoder", - "version": "24.2.0", + "version": "25.1.0", "libName": "CTRE_SimCANCoder", "headerClassifier": "headers", "sharedLibrary": true, @@ -286,6 +316,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -293,7 +324,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFX", - "version": "24.2.0", + "version": "25.1.0", "libName": "CTRE_SimProTalonFX", "headerClassifier": "headers", "sharedLibrary": true, @@ -301,6 +332,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -308,7 +340,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANcoder", - "version": "24.2.0", + "version": "25.1.0", "libName": "CTRE_SimProCANcoder", "headerClassifier": "headers", "sharedLibrary": true, @@ -316,6 +348,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -323,7 +356,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProPigeon2", - "version": "24.2.0", + "version": "25.1.0", "libName": "CTRE_SimProPigeon2", "headerClassifier": "headers", "sharedLibrary": true, @@ -331,6 +364,23 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANrange", + "version": "25.1.0", + "libName": "CTRE_SimProCANrange", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" diff --git a/vendordeps/playingwithfusion2024.json b/vendordeps/PlayingWithFusion-2025.01.04.json similarity index 75% rename from vendordeps/playingwithfusion2024.json rename to vendordeps/PlayingWithFusion-2025.01.04.json index c8c51493..580c1217 100644 --- a/vendordeps/playingwithfusion2024.json +++ b/vendordeps/PlayingWithFusion-2025.01.04.json @@ -1,10 +1,10 @@ { - "fileName": "playingwithfusion2024.json", + "fileName": "PlayingWithFusion-2025.01.04.json", "name": "PlayingWithFusion", - "version": "2024.03.09", + "version": "2025.01.04", "uuid": "14b8ad04-24df-11ea-978f-2e728ce88125", - "frcYear": "2024", - "jsonUrl": "https://www.playingwithfusion.com/frc/playingwithfusion2024.json", + "frcYear": "2025", + "jsonUrl": "https://www.playingwithfusion.com/frc/playingwithfusion2025.json", "mavenUrls": [ "https://www.playingwithfusion.com/frc/maven/" ], @@ -12,23 +12,22 @@ { "groupId": "com.playingwithfusion.frc", "artifactId": "PlayingWithFusion-java", - "version": "2024.03.09" + "version": "2025.01.04" } ], "jniDependencies": [ { "groupId": "com.playingwithfusion.frc", "artifactId": "PlayingWithFusion-driver", - "version": "2024.03.09", - "isJar": false, + "version": "2025.01.04", "skipInvalidPlatforms": true, + "isJar": false, "validPlatforms": [ - "linuxathena", "windowsx86-64", + "linuxarm64", "linuxx86-64", - "osxuniversal", - "linuxarm32", - "linuxarm64" + "linuxathena", + "osxuniversal" ] } ], @@ -36,35 +35,33 @@ { "groupId": "com.playingwithfusion.frc", "artifactId": "PlayingWithFusion-cpp", - "version": "2024.03.09", + "version": "2025.01.04", "headerClassifier": "headers", "sharedLibrary": false, "libName": "PlayingWithFusion", "skipInvalidPlatforms": true, "binaryPlatforms": [ - "linuxathena", "windowsx86-64", + "linuxarm64", "linuxx86-64", - "osxuniversal", - "linuxarm32", - "linuxarm64" + "linuxathena", + "osxuniversal" ] }, { "groupId": "com.playingwithfusion.frc", "artifactId": "PlayingWithFusion-driver", - "version": "2024.03.09", + "version": "2025.01.04", "headerClassifier": "headers", "sharedLibrary": true, "libName": "PlayingWithFusionDriver", "skipInvalidPlatforms": true, "binaryPlatforms": [ - "linuxathena", "windowsx86-64", + "linuxarm64", "linuxx86-64", - "osxuniversal", - "linuxarm32", - "linuxarm64" + "linuxathena", + "osxuniversal" ] } ] diff --git a/vendordeps/REVLib.json b/vendordeps/REVLib-2025.0.0.json similarity index 88% rename from vendordeps/REVLib.json rename to vendordeps/REVLib-2025.0.0.json index f85acd40..cde60117 100644 --- a/vendordeps/REVLib.json +++ b/vendordeps/REVLib-2025.0.0.json @@ -1,25 +1,25 @@ { - "fileName": "REVLib.json", + "fileName": "REVLib-2025.0.0.json", "name": "REVLib", - "version": "2024.2.4", - "frcYear": "2024", + "version": "2025.0.0", + "frcYear": "2025", "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", "mavenUrls": [ "https://maven.revrobotics.com/" ], - "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2024.json", + "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2025.json", "javaDependencies": [ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-java", - "version": "2024.2.4" + "version": "2025.0.0" } ], "jniDependencies": [ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2024.2.4", + "version": "2025.0.0", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ @@ -37,7 +37,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-cpp", - "version": "2024.2.4", + "version": "2025.0.0", "libName": "REVLib", "headerClassifier": "headers", "sharedLibrary": false, @@ -55,7 +55,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2024.2.4", + "version": "2025.0.0", "libName": "REVLibDriver", "headerClassifier": "headers", "sharedLibrary": false, diff --git a/vendordeps/Studica-2025.0.0.json b/vendordeps/Studica-2025.0.0.json new file mode 100644 index 00000000..ddb0e44b --- /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" + } + ] +} \ No newline at end of file diff --git a/vendordeps/WPILibNewCommands.json b/vendordeps/WPILibNewCommands.json index 67bf3898..3718e0ac 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": "2024", + "frcYear": "2025", "mavenUrls": [], "jsonUrl": "", "javaDependencies": [