Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update to 2025 #24

Merged
merged 3 commits into from
Jan 11, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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
Original file line number Diff line number Diff line change
@@ -1,34 +1,34 @@
{
"fileName": "PathplannerLib-beta.json",
"fileName": "PathplannerLib.json",
"name": "PathplannerLib",
"version": "2025.0.0-beta-4",
"version": "2025.1.1",
"uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786",
"frcYear": "2025",
"mavenUrls": [
"https://3015rangerrobotics.github.io/pathplannerlib/repo"
],
"jsonUrl": "https://3015rangerrobotics.github.io/pathplannerlib/PathplannerLib-beta.json",
"jsonUrl": "https://3015rangerrobotics.github.io/pathplannerlib/PathplannerLib.json",
"javaDependencies": [
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-java",
"version": "2025.0.0-beta-4"
"version": "2025.1.1"
}
],
"jniDependencies": [],
"cppDependencies": [
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-cpp",
"version": "2025.0.0-beta-4",
"version": "2025.1.1",
"libName": "PathplannerLib",
"headerClassifier": "headers",
"sharedLibrary": false,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"osxuniversal",
"linuxx86-64",
"osxuniversal",
"linuxathena",
"linuxarm32",
"linuxarm64"
Expand Down
Original file line number Diff line number Diff line change
@@ -1,50 +1,50 @@
{
"fileName": "Phoenix5-frc2025-beta-latest.json",
"fileName": "Phoenix5-frc2025-latest.json",
"name": "CTRE-Phoenix (v5)",
"version": "5.34.0-beta-3",
"version": "5.35.0",
"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-frc2025-beta-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-frc2025-beta-latest.json",
"onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-beta-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-beta-latest.json"
"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-beta-latest.json"
"offlineFileName": "Phoenix5-replay-frc2025-latest.json"
}
],
"javaDependencies": [
{
"groupId": "com.ctre.phoenix",
"artifactId": "api-java",
"version": "5.34.0-beta-3"
"version": "5.35.0"
},
{
"groupId": "com.ctre.phoenix",
"artifactId": "wpiapi-java",
"version": "5.34.0-beta-3"
"version": "5.35.0"
}
],
"jniDependencies": [
{
"groupId": "com.ctre.phoenix",
"artifactId": "cci",
"version": "5.34.0-beta-3",
"version": "5.35.0",
"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.35.0",
"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.35.0",
"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.35.0",
"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.35.0",
"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.35.0",
"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.35.0",
"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.35.0",
"libName": "CTRE_PhoenixCCISim",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand Down
Loading
Loading