From 650405edab876866fe75143f1cfd2d5df95d9aa5 Mon Sep 17 00:00:00 2001 From: Hayden Heroux Date: Thu, 25 Apr 2024 16:16:56 -0400 Subject: [PATCH] refactor(config): Remove old motor current limits class. --- src/main/java/frc/lib/MotorCurrentLimits.java | 56 ------------------- .../frc/robot/swerve/DriveMotorIOTalonFX.java | 5 +- .../robot/swerve/SteerMotorIOTalonFXPIDF.java | 5 +- 3 files changed, 4 insertions(+), 62 deletions(-) delete mode 100644 src/main/java/frc/lib/MotorCurrentLimits.java diff --git a/src/main/java/frc/lib/MotorCurrentLimits.java b/src/main/java/frc/lib/MotorCurrentLimits.java deleted file mode 100644 index 9a2056d..0000000 --- a/src/main/java/frc/lib/MotorCurrentLimits.java +++ /dev/null @@ -1,56 +0,0 @@ -package frc.lib; - -import com.ctre.phoenix6.configs.CurrentLimitsConfigs; -import java.util.Objects; - -/** Constants for motor current limiting. */ -public record MotorCurrentLimits( - double motorAmps, double breakerAmps, double breakerPeakAmps, double peakDurationSeconds) { - - /** - * Creates motor current limiting constants. - * - * @param motorAmps the amount of current allowed in the motor. - * @param breakerAmps the amount of current allowed at the breaker for an extended duration. - * @param breakerPeakAmps the peak amount of supply current allowed for a short duration. - * @param peakDurationSeconds the duration of the current peak. - */ - public MotorCurrentLimits { - Objects.requireNonNull(motorAmps); - Objects.requireNonNull(breakerAmps); - Objects.requireNonNull(breakerPeakAmps); - Objects.requireNonNull(peakDurationSeconds); - } - - /** - * Creates motor current limiting constants. - * - * @param breakerAmps the amount of current allowed at the breaker for an extended duration. - */ - public MotorCurrentLimits(double breakerAmps) { - this(0.0, breakerAmps, 0.0, 0.0); - } - - /** - * Creates a Phoenix current limiting configuration using the current limiting constants. - * - * @return a Phoenix current limiting configuration. - */ - public CurrentLimitsConfigs asCurrentLimitsConfigs() { - CurrentLimitsConfigs config = new CurrentLimitsConfigs(); - - if (motorAmps > 0.0) { - config.StatorCurrentLimit = motorAmps; - config.StatorCurrentLimitEnable = true; - } - - if (breakerAmps > 0.0 && breakerPeakAmps >= 0.0 && peakDurationSeconds >= 0.0) { - config.SupplyCurrentLimit = breakerAmps; - config.SupplyCurrentThreshold = breakerPeakAmps; - config.SupplyTimeThreshold = peakDurationSeconds; - config.SupplyCurrentLimitEnable = true; - } - - return config; - } -} diff --git a/src/main/java/frc/robot/swerve/DriveMotorIOTalonFX.java b/src/main/java/frc/robot/swerve/DriveMotorIOTalonFX.java index a48f30e..3b45eb7 100644 --- a/src/main/java/frc/robot/swerve/DriveMotorIOTalonFX.java +++ b/src/main/java/frc/robot/swerve/DriveMotorIOTalonFX.java @@ -7,7 +7,6 @@ import com.ctre.phoenix6.signals.InvertedValue; import com.ctre.phoenix6.signals.NeutralModeValue; import frc.lib.CAN; -import frc.lib.MotorCurrentLimits; import frc.robot.swerve.SwerveConstants.MK4iConstants; /** TalonFX drive motor. */ @@ -35,8 +34,8 @@ public DriveMotorIOTalonFX(CAN driveMotorCAN) { talonFXBaseConfig.Feedback.SensorToMechanismRatio = MK4iConstants.DRIVE_GEARING; - talonFXBaseConfig.CurrentLimits = - new MotorCurrentLimits(80.0, 30.0, 60.0, 0.1).asCurrentLimitsConfigs(); + // talonFXBaseConfig.CurrentLimits = + // new MotorCurrentLimits(80.0, 30.0, 60.0, 0.1).asCurrentLimitsConfigs(); positionRotations = talonFX.getPosition(); velocityRotationsPerSecond = talonFX.getVelocity(); diff --git a/src/main/java/frc/robot/swerve/SteerMotorIOTalonFXPIDF.java b/src/main/java/frc/robot/swerve/SteerMotorIOTalonFXPIDF.java index eaca1e6..98fe0cb 100644 --- a/src/main/java/frc/robot/swerve/SteerMotorIOTalonFXPIDF.java +++ b/src/main/java/frc/robot/swerve/SteerMotorIOTalonFXPIDF.java @@ -6,7 +6,6 @@ import com.ctre.phoenix6.signals.InvertedValue; import edu.wpi.first.math.geometry.Rotation2d; import frc.lib.CAN; -import frc.lib.MotorCurrentLimits; import frc.lib.config.Configurator; import frc.robot.swerve.SwerveConstants.MK4iConstants; @@ -42,8 +41,8 @@ public void configure() { talonFXPIDFConfig.ClosedLoopGeneral.ContinuousWrap = true; - talonFXPIDFConfig.CurrentLimits = - new MotorCurrentLimits(35.0, 15.0, 25.0, 0.1).asCurrentLimitsConfigs(); + // talonFXPIDFConfig.CurrentLimits = + // new MotorCurrentLimits(35.0, 15.0, 25.0, 0.1).asCurrentLimitsConfigs(); talonFXPIDFConfig.Feedback.SensorToMechanismRatio = MK4iConstants.STEER_GEARING;