Skip to content

Commit

Permalink
Upgraded libraries and WPILib to Beta 3
Browse files Browse the repository at this point in the history
  • Loading branch information
mmilunicmobile committed Dec 21, 2024
1 parent 2699742 commit 6edcaf9
Show file tree
Hide file tree
Showing 5 changed files with 16 additions and 9 deletions.
3 changes: 3 additions & 0 deletions .vscode/settings.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
{
"java.configuration.updateBuildConfiguration": "interactive"
}
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
@@ -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 {
Expand Down
8 changes: 6 additions & 2 deletions src/main/java/frc/robot/constants/GlobalConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -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);

Expand All @@ -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);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -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);
Expand Down
6 changes: 3 additions & 3 deletions vendordeps/PathplannerLib-beta.json
Original file line number Diff line number Diff line change
@@ -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": [
Expand All @@ -12,15 +12,15 @@
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-java",
"version": "2025.0.0-beta-5"
"version": "2025.0.0-beta-6.1"
}
],
"jniDependencies": [],
"cppDependencies": [
{
"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,
Expand Down

0 comments on commit 6edcaf9

Please sign in to comment.