diff --git a/src/main/java/frc/robot/generated/TunerConstants.java b/src/main/java/frc/robot/generated/TunerConstants.java index fa8fc30..a658766 100644 --- a/src/main/java/frc/robot/generated/TunerConstants.java +++ b/src/main/java/frc/robot/generated/TunerConstants.java @@ -11,6 +11,7 @@ import com.ctre.phoenix6.configs.Pigeon2Configuration; import com.ctre.phoenix6.configs.Slot0Configs; import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.signals.StaticFeedforwardSignValue; import com.ctre.phoenix6.swerve.SwerveDrivetrainConstants; import com.ctre.phoenix6.swerve.SwerveModuleConstants; import com.ctre.phoenix6.swerve.SwerveModuleConstants.ClosedLoopOutputType; @@ -27,11 +28,18 @@ public class TunerConstants { // The steer motor uses any SwerveModule.SteerRequestType control request with the // output type specified by SwerveModuleConstants.SteerMotorClosedLoopOutput private static final Slot0Configs steerGains = - new Slot0Configs().withKP(100).withKI(0).withKD(2.0).withKS(0.2).withKV(1.5).withKA(0); + new Slot0Configs() + .withKP(100) + .withKI(0) + .withKD(2.0) + .withKS(0.2) + .withKV(1.59) + .withKA(0) + .withStaticFeedforwardSign(StaticFeedforwardSignValue.UseClosedLoopSign); // When using closed-loop control, the drive motor uses the control // output type specified by SwerveModuleConstants.DriveMotorClosedLoopOutput private static final Slot0Configs driveGains = - new Slot0Configs().withKP(0.1).withKI(0).withKD(0).withKS(0).withKV(0.12); + new Slot0Configs().withKP(0.1).withKI(0).withKD(0).withKS(0).withKV(0.124); // The closed-loop output type to use for the steer motors; // This affects the PID/FF gains for the steer motors @@ -64,9 +72,13 @@ public class TunerConstants { // Configs for the Pigeon 2; leave this null to skip applying Pigeon 2 configs private static final Pigeon2Configuration pigeonConfigs = null; + // CAN bus that the devices are located on; + // All swerve devices must share the same CAN bus + public static final CANBus kCANBus = new CANBus("rio", "./logs/example.hoot"); + // Theoretical free speed (m/s) at 12 V applied output; // This needs to be tuned to your individual robot - public static final LinearVelocity kSpeedAt12Volts = MetersPerSecond.of(4.70); + public static final LinearVelocity kSpeedAt12Volts = MetersPerSecond.of(4.55); // Every 1 rotation of the azimuth results in kCoupleRatio drive motor turns; // This may need to be tuned to your individual robot @@ -79,7 +91,6 @@ public class TunerConstants { private static final boolean kInvertLeftSide = false; private static final boolean kInvertRightSide = true; - private static final CANBus kCANBus = new CANBus("rio", "./logs/example.hoot"); private static final int kPigeonId = 1; // These are only used for simulation @@ -122,6 +133,7 @@ public class TunerConstants { private static final int kFrontLeftEncoderId = 2; private static final Angle kFrontLeftEncoderOffset = Rotations.of(-0.83544921875); private static final boolean kFrontLeftSteerMotorInverted = true; + private static final boolean kFrontLeftCANcoderInverted = false; private static final Distance kFrontLeftXPos = Inches.of(10.5); private static final Distance kFrontLeftYPos = Inches.of(10.5); @@ -132,6 +144,7 @@ public class TunerConstants { private static final int kFrontRightEncoderId = 3; private static final Angle kFrontRightEncoderOffset = Rotations.of(-0.15234375); private static final boolean kFrontRightSteerMotorInverted = true; + private static final boolean kFrontRightCANcoderInverted = false; private static final Distance kFrontRightXPos = Inches.of(10.5); private static final Distance kFrontRightYPos = Inches.of(-10.5); @@ -142,6 +155,7 @@ public class TunerConstants { private static final int kBackLeftEncoderId = 0; private static final Angle kBackLeftEncoderOffset = Rotations.of(-0.4794921875); private static final boolean kBackLeftSteerMotorInverted = true; + private static final boolean kBackLeftCANcoderInverted = false; private static final Distance kBackLeftXPos = Inches.of(-10.5); private static final Distance kBackLeftYPos = Inches.of(10.5); @@ -152,6 +166,7 @@ public class TunerConstants { private static final int kBackRightEncoderId = 1; private static final Angle kBackRightEncoderOffset = Rotations.of(-0.84130859375); private static final boolean kBackRightSteerMotorInverted = true; + private static final boolean kBackRightCANcoderInverted = false; private static final Distance kBackRightXPos = Inches.of(-10.5); private static final Distance kBackRightYPos = Inches.of(-10.5); @@ -165,7 +180,8 @@ public class TunerConstants { kFrontLeftXPos, kFrontLeftYPos, kInvertLeftSide, - kFrontLeftSteerMotorInverted); + kFrontLeftSteerMotorInverted, + kFrontLeftCANcoderInverted); public static final SwerveModuleConstants FrontRight = ConstantCreator.createModuleConstants( kFrontRightSteerMotorId, @@ -175,7 +191,8 @@ public class TunerConstants { kFrontRightXPos, kFrontRightYPos, kInvertRightSide, - kFrontRightSteerMotorInverted); + kFrontRightSteerMotorInverted, + kFrontRightCANcoderInverted); public static final SwerveModuleConstants BackLeft = ConstantCreator.createModuleConstants( kBackLeftSteerMotorId, @@ -185,7 +202,8 @@ public class TunerConstants { kBackLeftXPos, kBackLeftYPos, kInvertLeftSide, - kBackLeftSteerMotorInverted); + kBackLeftSteerMotorInverted, + kBackLeftCANcoderInverted); public static final SwerveModuleConstants BackRight = ConstantCreator.createModuleConstants( kBackRightSteerMotorId, @@ -195,7 +213,8 @@ public class TunerConstants { kBackRightXPos, kBackRightYPos, kInvertRightSide, - kBackRightSteerMotorInverted); + kBackRightSteerMotorInverted, + kBackRightCANcoderInverted); /** * Creates a CommandSwerveDrivetrain instance. This should only be called once in your robot diff --git a/src/main/java/frc/robot/subsystems/CommandSwerveDrivetrain.java b/src/main/java/frc/robot/subsystems/CommandSwerveDrivetrain.java index 78e1479..4b69b29 100644 --- a/src/main/java/frc/robot/subsystems/CommandSwerveDrivetrain.java +++ b/src/main/java/frc/robot/subsystems/CommandSwerveDrivetrain.java @@ -244,15 +244,13 @@ public void drive(double velX, double velY, double velOmega) { ChassisSpeeds tempSpeeds = _driverChassisSpeeds; SwerveModuleState[] tempStates; - if (_isFieldOriented) - tempSpeeds = ChassisSpeeds.fromFieldRelativeSpeeds(tempSpeeds, getHeading()); + if (_isFieldOriented) tempSpeeds.toRobotRelativeSpeeds(getHeading()); tempStates = getKinematics().toSwerveModuleStates(tempSpeeds); SwerveDriveKinematics.desaturateWheelSpeeds(tempStates, SwerveConstants.maxTranslationalSpeed); tempSpeeds = getKinematics().toChassisSpeeds(tempStates); - if (_isFieldOriented) - tempSpeeds = ChassisSpeeds.fromRobotRelativeSpeeds(tempSpeeds, getHeading()); + if (_isFieldOriented) tempSpeeds.toFieldRelativeSpeeds(getHeading()); velX = tempSpeeds.vxMetersPerSecond; velY = tempSpeeds.vyMetersPerSecond; diff --git a/vendordeps/DogLog.json b/vendordeps/DogLog.json index 3bc6550..0e0fc5a 100644 --- a/vendordeps/DogLog.json +++ b/vendordeps/DogLog.json @@ -3,7 +3,7 @@ { "groupId": "com.github.jonahsnider", "artifactId": "doglog", - "version": "2025.1.0" + "version": "2025.1.1" } ], "fileName": "DogLog.json", @@ -15,6 +15,6 @@ "https://jitpack.io" ], "cppDependencies": [], - "version": "2025.1.0", + "version": "2025.1.1", "uuid": "65592ce1-2251-4a31-8e4b-2df20dacebe4" } \ No newline at end of file diff --git a/vendordeps/Phoenix6-25.0.0-beta-2.json b/vendordeps/Phoenix6-frc2025-beta-latest.json similarity index 85% rename from vendordeps/Phoenix6-25.0.0-beta-2.json rename to vendordeps/Phoenix6-frc2025-beta-latest.json index c56e61a..ff0b8c9 100644 --- a/vendordeps/Phoenix6-25.0.0-beta-2.json +++ b/vendordeps/Phoenix6-frc2025-beta-latest.json @@ -1,7 +1,7 @@ { - "fileName": "Phoenix6-25.0.0-beta-2.json", + "fileName": "Phoenix6-frc2025-beta-latest.json", "name": "CTRE-Phoenix (v6)", - "version": "25.0.0-beta-2", + "version": "25.0.0-beta-3", "frcYear": "2025", "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", "mavenUrls": [ @@ -9,11 +9,6 @@ ], "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-beta-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.", @@ -24,19 +19,20 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "wpiapi-java", - "version": "25.0.0-beta-2" + "version": "25.0.0-beta-3" } ], "jniDependencies": [ { "groupId": "com.ctre.phoenix6", "artifactId": "api-cpp", - "version": "25.0.0-beta-2", + "version": "25.0.0-beta-3", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "linuxathena" ], "simMode": "hwsim" @@ -44,12 +40,13 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "tools", - "version": "25.0.0-beta-2", + "version": "25.0.0-beta-3", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "linuxathena" ], "simMode": "hwsim" @@ -57,12 +54,13 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "api-cpp-sim", - "version": "25.0.0-beta-2", + "version": "25.0.0-beta-3", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -70,12 +68,13 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "tools-sim", - "version": "25.0.0-beta-2", + "version": "25.0.0-beta-3", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -83,12 +82,13 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonSRX", - "version": "25.0.0-beta-2", + "version": "25.0.0-beta-3", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -96,12 +96,13 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simVictorSPX", - "version": "25.0.0-beta-2", + "version": "25.0.0-beta-3", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -109,12 +110,13 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simPigeonIMU", - "version": "25.0.0-beta-2", + "version": "25.0.0-beta-3", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -122,12 +124,13 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simCANCoder", - "version": "25.0.0-beta-2", + "version": "25.0.0-beta-3", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -135,12 +138,13 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFX", - "version": "25.0.0-beta-2", + "version": "25.0.0-beta-3", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -148,12 +152,13 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANcoder", - "version": "25.0.0-beta-2", + "version": "25.0.0-beta-3", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -161,12 +166,13 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProPigeon2", - "version": "25.0.0-beta-2", + "version": "25.0.0-beta-3", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -176,7 +182,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "wpiapi-cpp", - "version": "25.0.0-beta-2", + "version": "25.0.0-beta-3", "libName": "CTRE_Phoenix6_WPI", "headerClassifier": "headers", "sharedLibrary": true, @@ -184,6 +190,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "linuxathena" ], "simMode": "hwsim" @@ -191,7 +198,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "tools", - "version": "25.0.0-beta-2", + "version": "25.0.0-beta-3", "libName": "CTRE_PhoenixTools", "headerClassifier": "headers", "sharedLibrary": true, @@ -199,6 +206,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "linuxathena" ], "simMode": "hwsim" @@ -206,7 +214,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "wpiapi-cpp-sim", - "version": "25.0.0-beta-2", + "version": "25.0.0-beta-3", "libName": "CTRE_Phoenix6_WPISim", "headerClassifier": "headers", "sharedLibrary": true, @@ -214,6 +222,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -221,7 +230,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "tools-sim", - "version": "25.0.0-beta-2", + "version": "25.0.0-beta-3", "libName": "CTRE_PhoenixTools_Sim", "headerClassifier": "headers", "sharedLibrary": true, @@ -229,6 +238,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -236,7 +246,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonSRX", - "version": "25.0.0-beta-2", + "version": "25.0.0-beta-3", "libName": "CTRE_SimTalonSRX", "headerClassifier": "headers", "sharedLibrary": true, @@ -244,6 +254,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -251,7 +262,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simVictorSPX", - "version": "25.0.0-beta-2", + "version": "25.0.0-beta-3", "libName": "CTRE_SimVictorSPX", "headerClassifier": "headers", "sharedLibrary": true, @@ -259,6 +270,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -266,7 +278,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simPigeonIMU", - "version": "25.0.0-beta-2", + "version": "25.0.0-beta-3", "libName": "CTRE_SimPigeonIMU", "headerClassifier": "headers", "sharedLibrary": true, @@ -274,6 +286,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -281,7 +294,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simCANCoder", - "version": "25.0.0-beta-2", + "version": "25.0.0-beta-3", "libName": "CTRE_SimCANCoder", "headerClassifier": "headers", "sharedLibrary": true, @@ -289,6 +302,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -296,7 +310,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFX", - "version": "25.0.0-beta-2", + "version": "25.0.0-beta-3", "libName": "CTRE_SimProTalonFX", "headerClassifier": "headers", "sharedLibrary": true, @@ -304,6 +318,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -311,7 +326,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANcoder", - "version": "25.0.0-beta-2", + "version": "25.0.0-beta-3", "libName": "CTRE_SimProCANcoder", "headerClassifier": "headers", "sharedLibrary": true, @@ -319,6 +334,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim" @@ -326,7 +342,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProPigeon2", - "version": "25.0.0-beta-2", + "version": "25.0.0-beta-3", "libName": "CTRE_SimProPigeon2", "headerClassifier": "headers", "sharedLibrary": true, @@ -334,6 +350,7 @@ "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", + "linuxarm64", "osxuniversal" ], "simMode": "swsim"