Skip to content

Commit

Permalink
Update everything to 2025 versions
Browse files Browse the repository at this point in the history
  • Loading branch information
CoffeeCoder1 committed Jan 6, 2025
1 parent 82e4f8c commit 873824d
Show file tree
Hide file tree
Showing 10 changed files with 149 additions and 75 deletions.
5 changes: 3 additions & 2 deletions src/main/java/frc/robot/subsystems/Arm.java
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
import java.util.function.Supplier;

import com.revrobotics.RelativeEncoder;
import com.revrobotics.spark.ClosedLoopSlot;
import com.revrobotics.spark.SparkAbsoluteEncoder;
import com.revrobotics.spark.SparkClosedLoopController;
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
Expand Down Expand Up @@ -362,7 +363,7 @@ public void periodic() {
double armFeedFowardValue = armFeedFoward.calculate(Units.degreesToRadians(currentArmTarget), velocity);
// System.out.println("arm feed foward: " + armFeedFowardValue);

armPIDController.setReference(currentArmTarget, SparkMax.ControlType.kPosition, 0, armFeedFowardValue, ArbFFUnits.kVoltage);
armPIDController.setReference(currentArmTarget, SparkMax.ControlType.kPosition, ClosedLoopSlot.kSlot0, armFeedFowardValue, ArbFFUnits.kVoltage);
lastAcutalArmTarget = currentArmTarget;
}
if (!ElevatorConstants.KILL_IT_ALL) {
Expand All @@ -378,7 +379,7 @@ public void periodic() {

if (currentElevatorTarget != lastAcutalElevatorTarget) {
double elevatorFeedFowardValue = getElevatorFeedforward().calculate(elevatorEncoder.getVelocity());
elevatorPIDController.setReference(currentElevatorTarget, SparkMax.ControlType.kPosition, 0, elevatorFeedFowardValue, ArbFFUnits.kVoltage);
elevatorPIDController.setReference(currentElevatorTarget, SparkMax.ControlType.kPosition, ClosedLoopSlot.kSlot0, elevatorFeedFowardValue, ArbFFUnits.kVoltage);
lastAcutalElevatorTarget = currentElevatorTarget;
}

Expand Down
20 changes: 10 additions & 10 deletions src/main/java/frc/robot/subsystems/Drivetrain.java
Original file line number Diff line number Diff line change
Expand Up @@ -168,7 +168,7 @@ public Command getAutonomousCommand(String pathName, boolean setOdomToStart) {
}

public Command driveToPose(Pose2d pose) {
PathConstraints constraints = new PathConstraints(swerveDrive.getMaximumVelocity(), 4.0, swerveDrive.getMaximumAngularVelocity(), Units.degreesToRadians(720));
PathConstraints constraints = new PathConstraints(swerveDrive.getMaximumChassisVelocity(), 4.0, swerveDrive.getMaximumChassisAngularVelocity(), Units.degreesToRadians(720));
return AutoBuilder.pathfindToPose(pose, constraints, 0.0);
}

Expand All @@ -190,7 +190,7 @@ public Command driveCommand(DoubleSupplier translationX, DoubleSupplier translat
double xInput = translationX.getAsDouble();
double yInput = translationY.getAsDouble();
// Make the robot move
driveFieldOriented(swerveDrive.swerveController.getTargetSpeeds(xInput, yInput, headingX.getAsDouble(), headingY.getAsDouble(), swerveDrive.getOdometryHeading().getRadians(), swerveDrive.getMaximumVelocity()));
driveFieldOriented(swerveDrive.swerveController.getTargetSpeeds(xInput, yInput, headingX.getAsDouble(), headingY.getAsDouble(), swerveDrive.getOdometryHeading().getRadians(), swerveDrive.getMaximumChassisVelocity()));
});
}

Expand All @@ -208,7 +208,7 @@ public Command driveCommand(DoubleSupplier translationX, DoubleSupplier translat
public Command simDriveCommand(DoubleSupplier translationX, DoubleSupplier translationY, DoubleSupplier rotation) {
return run(() -> {
// Make the robot move
driveFieldOriented(swerveDrive.swerveController.getTargetSpeeds(translationX.getAsDouble(), translationY.getAsDouble(), rotation.getAsDouble() * Math.PI, swerveDrive.getOdometryHeading().getRadians(), swerveDrive.getMaximumVelocity()));
driveFieldOriented(swerveDrive.swerveController.getTargetSpeeds(translationX.getAsDouble(), translationY.getAsDouble(), rotation.getAsDouble() * Math.PI, swerveDrive.getOdometryHeading().getRadians(), swerveDrive.getMaximumChassisVelocity()));
});
}

Expand All @@ -225,7 +225,7 @@ public Command simDriveCommand(DoubleSupplier translationX, DoubleSupplier trans
*/
public Command driveCommand(DoubleSupplier translationX, DoubleSupplier translationY, DoubleSupplier angularRotationX) {
return run(() -> {
swerveDrive.drive(new Translation2d(translationX.getAsDouble() * swerveDrive.getMaximumVelocity(), translationY.getAsDouble() * swerveDrive.getMaximumVelocity()), angularRotationX.getAsDouble() * swerveDrive.getMaximumAngularVelocity(), true, false);
swerveDrive.drive(new Translation2d(translationX.getAsDouble() * swerveDrive.getMaximumChassisVelocity(), translationY.getAsDouble() * swerveDrive.getMaximumChassisVelocity()), angularRotationX.getAsDouble() * swerveDrive.getMaximumChassisAngularVelocity(), true, false);
}).finallyDo(() -> {
swerveDrive.swerveController.lastAngleScalar = getHeading().getRadians();
});
Expand Down Expand Up @@ -416,7 +416,7 @@ public void doVisionUpdates(boolean doVisionUpdates) {
* @return {@link ChassisSpeeds} which can be sent to th Swerve Drive.
*/
public ChassisSpeeds getTargetSpeeds(double xInput, double yInput, double headingX, double headingY) {
return swerveDrive.swerveController.getTargetSpeeds(xInput, yInput, headingX, headingY, getHeading().getRadians(), swerveDrive.getMaximumVelocity());
return swerveDrive.swerveController.getTargetSpeeds(xInput, yInput, headingX, headingY, getHeading().getRadians(), swerveDrive.getMaximumChassisVelocity());
}

/**
Expand All @@ -434,9 +434,9 @@ public void setHeadingCorrection(boolean doHeadingCorrection) {
}

public ChassisSpeeds getTargetSpeeds(double xInput, double yInput, double thetaInput) {
xInput = xInput * swerveDrive.getMaximumVelocity();
yInput = yInput * swerveDrive.getMaximumVelocity();
thetaInput = Math.pow(thetaInput, 3) * swerveDrive.getMaximumAngularVelocity();
xInput = xInput * swerveDrive.getMaximumChassisVelocity();
yInput = yInput * swerveDrive.getMaximumChassisVelocity();
thetaInput = Math.pow(thetaInput, 3) * swerveDrive.getMaximumChassisAngularVelocity();

return swerveDrive.swerveController.getRawTargetSpeeds(xInput, yInput, thetaInput);
}
Expand All @@ -454,7 +454,7 @@ public ChassisSpeeds getTargetSpeeds(double xInput, double yInput, double thetaI
* @return {@link ChassisSpeeds} which can be sent to th Swerve Drive.
*/
public ChassisSpeeds getTargetSpeeds(double xInput, double yInput, Rotation2d angle) {
return swerveDrive.swerveController.getTargetSpeeds(xInput, yInput, angle.getRadians(), getHeading().getRadians(), swerveDrive.getMaximumVelocity());
return swerveDrive.swerveController.getTargetSpeeds(xInput, yInput, angle.getRadians(), getHeading().getRadians(), swerveDrive.getMaximumChassisVelocity());
}

/**
Expand Down Expand Up @@ -485,7 +485,7 @@ public SwerveController getSwerveController() {
}

public double getMaximumVelocity() {
return swerveDrive.getMaximumVelocity();
return swerveDrive.getMaximumChassisVelocity();
}

/**
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-4",
"version": "2025.0.0-beta-5",
"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-4"
"version": "2025.0.0-beta-5"
}
],
"jniDependencies": [],
"cppDependencies": [
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-cpp",
"version": "2025.0.0-beta-4",
"version": "2025.0.0-beta-5",
"libName": "PathplannerLib",
"headerClassifier": "headers",
"sharedLibrary": false,
Expand Down
22 changes: 11 additions & 11 deletions vendordeps/Phoenix5-frc2025-beta-latest.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"fileName": "Phoenix5-frc2025-beta-latest.json",
"name": "CTRE-Phoenix (v5)",
"version": "5.34.0-beta-3",
"version": "5.34.0-beta-4",
"frcYear": "2025",
"uuid": "ab676553-b602-441f-a38d-f1296eff6537",
"mavenUrls": [
Expand Down Expand Up @@ -32,19 +32,19 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "api-java",
"version": "5.34.0-beta-3"
"version": "5.34.0-beta-4"
},
{
"groupId": "com.ctre.phoenix",
"artifactId": "wpiapi-java",
"version": "5.34.0-beta-3"
"version": "5.34.0-beta-4"
}
],
"jniDependencies": [
{
"groupId": "com.ctre.phoenix",
"artifactId": "cci",
"version": "5.34.0-beta-3",
"version": "5.34.0-beta-4",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
Expand All @@ -58,7 +58,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "cci-sim",
"version": "5.34.0-beta-3",
"version": "5.34.0-beta-4",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
Expand All @@ -74,7 +74,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "wpiapi-cpp",
"version": "5.34.0-beta-3",
"version": "5.34.0-beta-4",
"libName": "CTRE_Phoenix_WPI",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -90,7 +90,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "api-cpp",
"version": "5.34.0-beta-3",
"version": "5.34.0-beta-4",
"libName": "CTRE_Phoenix",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -106,7 +106,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "cci",
"version": "5.34.0-beta-3",
"version": "5.34.0-beta-4",
"libName": "CTRE_PhoenixCCI",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -122,7 +122,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "wpiapi-cpp-sim",
"version": "5.34.0-beta-3",
"version": "5.34.0-beta-4",
"libName": "CTRE_Phoenix_WPISim",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -138,7 +138,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "api-cpp-sim",
"version": "5.34.0-beta-3",
"version": "5.34.0-beta-4",
"libName": "CTRE_PhoenixSim",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -154,7 +154,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "cci-sim",
"version": "5.34.0-beta-3",
"version": "5.34.0-beta-4",
"libName": "CTRE_PhoenixCCISim",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand Down
Loading

0 comments on commit 873824d

Please sign in to comment.