diff --git a/src/main/java/frc/robot/subsystems/SwerveSubsystem.java b/src/main/java/frc/robot/subsystems/SwerveSubsystem.java index f0593c9..6a5b706 100644 --- a/src/main/java/frc/robot/subsystems/SwerveSubsystem.java +++ b/src/main/java/frc/robot/subsystems/SwerveSubsystem.java @@ -241,8 +241,7 @@ public ChassisSpeeds getTargetSpeeds(double xInput, double yInput, double headin { xInput = Math.pow(xInput, 3); yInput = Math.pow(yInput, 3); - return swerveDrive.swerveController.getTargetSpeeds(xInput, yInput, headingX, headingY, getHeading().getRadians()); - } + return swerveDrive.swerveController.getTargetSpeeds(xInput, yInput, headingX, headingY, getHeading().getRadians(), maximumSpeed); } /** * Get the chassis speeds based on controller input of 1 joystick and one angle.