diff --git a/.vscode/settings.json b/.vscode/settings.json new file mode 100644 index 00000000..c5f3f6b9 --- /dev/null +++ b/.vscode/settings.json @@ -0,0 +1,3 @@ +{ + "java.configuration.updateBuildConfiguration": "interactive" +} \ No newline at end of file diff --git a/build.gradle b/build.gradle index 8cf4665a..62c8ecea 100644 --- a/build.gradle +++ b/build.gradle @@ -1,6 +1,6 @@ plugins { id "java" - id "edu.wpi.first.GradleRIO" version "2025.1.1-beta-2" + id "edu.wpi.first.GradleRIO" version "2025.1.1-beta-3" } java { diff --git a/src/main/java/frc/robot/constants/GlobalConstants.java b/src/main/java/frc/robot/constants/GlobalConstants.java index 3533337d..ad4f83a6 100644 --- a/src/main/java/frc/robot/constants/GlobalConstants.java +++ b/src/main/java/frc/robot/constants/GlobalConstants.java @@ -23,6 +23,8 @@ public class GlobalConstants { public static final Mass ROBOT_MASS = Pounds.of(150); public static final MomentOfInertia ROBOT_MOI = KilogramSquareMeters.of(6.883); + public static final double COEFFICIENT_OF_FRICTION = 1.0; + public static final DCMotor DRIVE_MOTOR = DCMotor.getKrakenX60Foc(1).withReduction(EXAMPLE_MODULE.DriveMotorGearRatio); public static final DCMotor STEER_MOTOR = DCMotor.getKrakenX60Foc(1).withReduction(EXAMPLE_MODULE.SteerMotorGearRatio); @@ -48,8 +50,10 @@ public static RobotConfig getRobotConfigPathplanner() { robotConfigPathplanner = new RobotConfig(ROBOT_MASS, ROBOT_MOI, new ModuleConfig( Meters.of(EXAMPLE_MODULE.WheelRadius), - MAX_TRANSLATIONAL_SPEED, 1, - DRIVE_MOTOR, EXAMPLE_MODULE.DriveMotorInitialConfigs.CurrentLimits.getStatorCurrentLimitMeasure(), + MAX_TRANSLATIONAL_SPEED, + COEFFICIENT_OF_FRICTION, + DRIVE_MOTOR, + EXAMPLE_MODULE.DriveMotorInitialConfigs.CurrentLimits.getStatorCurrentLimitMeasure(), 1 ), moduleOffsets); diff --git a/src/main/java/frc/robot/subsystems/FieldOrientedOrbitSwerveRequest.java b/src/main/java/frc/robot/subsystems/FieldOrientedOrbitSwerveRequest.java index 5b1a9143..ccd16dfa 100644 --- a/src/main/java/frc/robot/subsystems/FieldOrientedOrbitSwerveRequest.java +++ b/src/main/java/frc/robot/subsystems/FieldOrientedOrbitSwerveRequest.java @@ -80,7 +80,7 @@ public StatusCode apply(SwerveControlParameters parameters, SwerveModule... modu double yAcceleration = toApplyY - slewedFieldChassisSpeeds.vyMetersPerSecond; ChassisSpeeds accelerations = new ChassisSpeeds(xAcceleration, yAcceleration, 0); - accelerations.toRobotRelativeSpeeds(parameters.currentPose.getRotation()); + accelerations = ChassisSpeeds.fromFieldRelativeSpeeds(accelerations,parameters.currentPose.getRotation()); if (accelerations.vxMetersPerSecond > forwardXRateLimit*timestep) { if (maintainStraightStopping) accelerations.vyMetersPerSecond = accelerations.vyMetersPerSecond * forwardXRateLimit*timestep / accelerations.vxMetersPerSecond; @@ -98,13 +98,13 @@ public StatusCode apply(SwerveControlParameters parameters, SwerveModule... modu accelerations.vyMetersPerSecond = -backwardYRateLimit*timestep; } - accelerations.toFieldRelativeSpeeds(parameters.currentPose.getRotation()); + accelerations = ChassisSpeeds.fromFieldRelativeSpeeds(accelerations,parameters.currentPose.getRotation()); slewedFieldChassisSpeeds = slewedFieldChassisSpeeds.plus(accelerations); ChassisSpeeds robotRelativeSpeeds = new ChassisSpeeds(slewedFieldChassisSpeeds.vxMetersPerSecond, slewedFieldChassisSpeeds.vyMetersPerSecond, chassisSpeeds.omegaRadiansPerSecond); - robotRelativeSpeeds.toRobotRelativeSpeeds(parameters.currentPose.getRotation()); + robotRelativeSpeeds = ChassisSpeeds.fromFieldRelativeSpeeds(robotRelativeSpeeds,parameters.currentPose.getRotation()); // Keep the robot from tipping over // robotRelativeSpeeds.vxMetersPerSecond = xLimiter.calculate(robotRelativeSpeeds.vxMetersPerSecond); diff --git a/vendordeps/PathplannerLib-beta.json b/vendordeps/PathplannerLib-beta.json index e79fe1ae..4be80014 100644 --- a/vendordeps/PathplannerLib-beta.json +++ b/vendordeps/PathplannerLib-beta.json @@ -1,7 +1,7 @@ { "fileName": "PathplannerLib-beta.json", "name": "PathplannerLib", - "version": "2025.0.0-beta-5", + "version": "2025.0.0-beta-6.1", "uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786", "frcYear": "2025", "mavenUrls": [ @@ -12,7 +12,7 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-java", - "version": "2025.0.0-beta-5" + "version": "2025.0.0-beta-6.1" } ], "jniDependencies": [], @@ -20,7 +20,7 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-cpp", - "version": "2025.0.0-beta-5", + "version": "2025.0.0-beta-6.1", "libName": "PathplannerLib", "headerClassifier": "headers", "sharedLibrary": false,