Skip to content

Commit

Permalink
Replace custom swerve current limit config code with new Phoenix init…
Browse files Browse the repository at this point in the history
…ialConfigs feature
  • Loading branch information
jonahsnider committed Jul 16, 2024
1 parent b881cac commit c5164ed
Show file tree
Hide file tree
Showing 6 changed files with 48 additions and 64 deletions.
18 changes: 1 addition & 17 deletions src/main/java/frc/robot/config/CompConfig.java
Original file line number Diff line number Diff line change
Expand Up @@ -252,24 +252,8 @@ class CompConfig {
.withClosedLoopRamps(CLOSED_LOOP_RAMP)
.withOpenLoopRamps(OPEN_LOOP_RAMP)),
new SwerveConfig(
new CurrentLimitsConfigs()
.withSupplyCurrentLimit(20)
.withStatorCurrentLimit(70)
.withSupplyCurrentLimitEnable(true)
.withStatorCurrentLimitEnable(true),
new CurrentLimitsConfigs()
.withSupplyCurrentLimit(120)
.withStatorCurrentLimit(70)
.withSupplyCurrentLimitEnable(true)
.withStatorCurrentLimitEnable(true),
new TorqueCurrentConfigs()
.withPeakForwardTorqueCurrent(80)
.withPeakReverseTorqueCurrent(-80),
// new PhoenixPIDController(50, 0, 5),
new PhoenixPIDController(20, 0, 2),
true,
true,
true),
new PhoenixPIDController(20, 0, 2), true, true, true),
new IMUConfig(
1,
distanceToAngleTolerance -> {
Expand Down
19 changes: 1 addition & 18 deletions src/main/java/frc/robot/config/PracticeConfig.java
Original file line number Diff line number Diff line change
Expand Up @@ -247,24 +247,7 @@ class PracticeConfig {
new MotorOutputConfigs().withInverted(InvertedValue.Clockwise_Positive))
.withClosedLoopRamps(CLOSED_LOOP_RAMP)
.withOpenLoopRamps(OPEN_LOOP_RAMP)),
new SwerveConfig(
new CurrentLimitsConfigs()
.withSupplyCurrentLimit(20)
.withStatorCurrentLimit(70)
.withSupplyCurrentLimitEnable(true)
.withStatorCurrentLimitEnable(true),
new CurrentLimitsConfigs()
.withSupplyCurrentLimit(150)
.withStatorCurrentLimit(70)
.withSupplyCurrentLimitEnable(true)
.withStatorCurrentLimitEnable(true),
new TorqueCurrentConfigs()
.withPeakForwardTorqueCurrent(80)
.withPeakReverseTorqueCurrent(-80),
new PhoenixPIDController(10, 0, 1),
true,
true,
true),
new SwerveConfig(new PhoenixPIDController(10, 0, 1), true, true, true),
new IMUConfig(
1,
distanceToAngleTolerance -> {
Expand Down
5 changes: 0 additions & 5 deletions src/main/java/frc/robot/config/RobotConfig.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,9 +4,7 @@

package frc.robot.config;

import com.ctre.phoenix6.configs.CurrentLimitsConfigs;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.configs.TorqueCurrentConfigs;
import com.ctre.phoenix6.mechanisms.swerve.utility.PhoenixPIDController;
import edu.wpi.first.math.filter.Debouncer;
import edu.wpi.first.math.geometry.Rotation2d;
Expand Down Expand Up @@ -92,9 +90,6 @@ public record IMUConfig(
public record LightsConfig(int deviceID) {}

public record SwerveConfig(
CurrentLimitsConfigs steerMotorCurrentLimits,
CurrentLimitsConfigs driveMotorCurrentLimits,
TorqueCurrentConfigs driveMotorTorqueCurrentLimits,
PhoenixPIDController snapController,
boolean invertRotation,
boolean invertX,
Expand Down
23 changes: 23 additions & 0 deletions src/main/java/frc/robot/generated/CompBotTunerConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,10 @@

package frc.robot.generated;

import com.ctre.phoenix6.configs.CurrentLimitsConfigs;
import com.ctre.phoenix6.configs.Slot0Configs;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.configs.TorqueCurrentConfigs;
import com.ctre.phoenix6.mechanisms.swerve.SwerveDrivetrainConstants;
import com.ctre.phoenix6.mechanisms.swerve.SwerveModule.ClosedLoopOutputType;
import com.ctre.phoenix6.mechanisms.swerve.SwerveModuleConstants;
Expand Down Expand Up @@ -69,6 +72,26 @@ public class CompBotTunerConstants {

private static final SwerveModuleConstantsFactory ConstantCreator =
new SwerveModuleConstantsFactory()
.withDriveMotorInitialConfigs(
new TalonFXConfiguration()
.withCurrentLimits(
new CurrentLimitsConfigs()
.withSupplyCurrentLimit(120)
.withStatorCurrentLimit(70)
.withSupplyCurrentLimitEnable(true)
.withStatorCurrentLimitEnable(true))
.withTorqueCurrent(
new TorqueCurrentConfigs()
.withPeakForwardTorqueCurrent(80)
.withPeakReverseTorqueCurrent(-80)))
.withSteerMotorInitialConfigs(
new TalonFXConfiguration()
.withCurrentLimits(
new CurrentLimitsConfigs()
.withSupplyCurrentLimit(20)
.withStatorCurrentLimit(70)
.withSupplyCurrentLimitEnable(true)
.withStatorCurrentLimitEnable(true)))
.withDriveMotorGearRatio(kDriveGearRatio)
.withSteerMotorGearRatio(kSteerGearRatio)
.withWheelRadius(kWheelRadiusInches)
Expand Down
23 changes: 23 additions & 0 deletions src/main/java/frc/robot/generated/PracticeBotTunerConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,10 @@

package frc.robot.generated;

import com.ctre.phoenix6.configs.CurrentLimitsConfigs;
import com.ctre.phoenix6.configs.Slot0Configs;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.configs.TorqueCurrentConfigs;
import com.ctre.phoenix6.mechanisms.swerve.SwerveDrivetrainConstants;
import com.ctre.phoenix6.mechanisms.swerve.SwerveModule.ClosedLoopOutputType;
import com.ctre.phoenix6.mechanisms.swerve.SwerveModuleConstants;
Expand Down Expand Up @@ -69,6 +72,26 @@ public class PracticeBotTunerConstants {

private static final SwerveModuleConstantsFactory ConstantCreator =
new SwerveModuleConstantsFactory()
.withDriveMotorInitialConfigs(
new TalonFXConfiguration()
.withCurrentLimits(
new CurrentLimitsConfigs()
.withSupplyCurrentLimit(150)
.withStatorCurrentLimit(70)
.withSupplyCurrentLimitEnable(true)
.withStatorCurrentLimitEnable(true))
.withTorqueCurrent(
new TorqueCurrentConfigs()
.withPeakForwardTorqueCurrent(80)
.withPeakReverseTorqueCurrent(-80)))
.withSteerMotorInitialConfigs(
new TalonFXConfiguration()
.withCurrentLimits(
new CurrentLimitsConfigs()
.withSupplyCurrentLimit(20)
.withStatorCurrentLimit(70)
.withSupplyCurrentLimitEnable(true)
.withStatorCurrentLimitEnable(true)))
.withDriveMotorGearRatio(kDriveGearRatio)
.withSteerMotorGearRatio(kSteerGearRatio)
.withWheelRadius(kWheelRadiusInches)
Expand Down
24 changes: 0 additions & 24 deletions src/main/java/frc/robot/swerve/SwerveSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -67,25 +67,6 @@ public class SwerveSubsystem extends LifecycleSubsystem {
private final double AccelerationLimit = 3.2;
private Translation2d previousVelocity = new Translation2d();

/**
* Helper for applying current limits to swerve modules, since the CTR swerve builder API doesn't
* support it.
*/
private static void applyCurrentLimits(SwerveModule module) {
module
.getDriveMotor()
.getConfigurator()
.apply(RobotConfig.get().swerve().driveMotorCurrentLimits());
module
.getSteerMotor()
.getConfigurator()
.apply(RobotConfig.get().swerve().steerMotorCurrentLimits());
module
.getDriveMotor()
.getConfigurator()
.apply(RobotConfig.get().swerve().driveMotorTorqueCurrentLimits());
}

private final SwerveRequest.SwerveDriveBrake brake = new SwerveRequest.SwerveDriveBrake();
private final SwerveRequest.PointWheelsAt point = new SwerveRequest.PointWheelsAt();
private boolean snapToAngle = false;
Expand Down Expand Up @@ -131,11 +112,6 @@ public SwerveSubsystem(CommandXboxController driveController) {
driveToAngle.HeadingController.enableContinuousInput(-Math.PI, Math.PI);
driveToAngle.HeadingController.setTolerance(0.02);

applyCurrentLimits(frontLeft);
applyCurrentLimits(frontRight);
applyCurrentLimits(backLeft);
applyCurrentLimits(backRight);

omegaPid.enableContinuousInput(-Math.PI, Math.PI);
}

Expand Down

0 comments on commit c5164ed

Please sign in to comment.