Skip to content
This repository has been archived by the owner on May 19, 2024. It is now read-only.

Commit

Permalink
refactor: Use lambdas for configuration.
Browse files Browse the repository at this point in the history
  • Loading branch information
haydenheroux committed Jan 23, 2024
1 parent fc3c8ab commit a240c1f
Show file tree
Hide file tree
Showing 7 changed files with 51 additions and 29 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -7,26 +7,40 @@
import com.ctre.phoenix6.configs.Pigeon2Configurator;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.configs.TalonFXConfigurator;
import com.revrobotics.REVLibError;
import java.util.function.Supplier;

/** Applies hardware configurations. */
public class ConfigApplier {
public class Configurator {

/** Number of retries for configuring Phoenix hardware. */
private static final int PHOENIX_RETRY_COUNT = 10;

/** Number of retries for configuring REV hardware. */
private static final int REV_RETRY_COUNT = 10;

/**
* Configures a Phoenix device.
*
* @param config a lambda that configures a Phoenix device.
*/
public static void configurePhoenix(Supplier<StatusCode> config) {
for (int i = 0; i < PHOENIX_RETRY_COUNT; i++) {
if (config.get() == StatusCode.OK) {
return;
}
}
}

/**
* Configures a CANcoder.
*
* @param configurator the CANcoder's configurator.
* @param config the config to apply.
*/
public static void applyCANcoderConfig(
public static void configureCANcoder(
CANcoderConfigurator configurator, CANcoderConfiguration config) {
for (int i = 0; i < PHOENIX_RETRY_COUNT; i++) {
if (configurator.apply(config) == StatusCode.OK) {
break;
}
}
configurePhoenix(() -> configurator.apply(config));
}

/**
Expand All @@ -35,13 +49,9 @@ public static void applyCANcoderConfig(
* @param configurator the TalonFX's configurator.
* @param config the config to apply.
*/
public static void applyTalonFXConfig(
public static void configureTalonFX(
TalonFXConfigurator configurator, TalonFXConfiguration config) {
for (int i = 0; i < PHOENIX_RETRY_COUNT; i++) {
if (configurator.apply(config) == StatusCode.OK) {
break;
}
}
configurePhoenix(() -> configurator.apply(config));
}

/**
Expand All @@ -50,11 +60,20 @@ public static void applyTalonFXConfig(
* @param configurator the Pigeon 2's configurator.
* @param config the config to apply.
*/
public static void applyPigeon2Config(
public static void configurePigeon2(
Pigeon2Configurator configurator, Pigeon2Configuration config) {
for (int i = 0; i < PHOENIX_RETRY_COUNT; i++) {
if (configurator.apply(config) == StatusCode.OK) {
break;
configurePhoenix(() -> configurator.apply(config));
}

/**
* Configures a REV device.
*
* @param config a lambda that configures a REV device.
*/
public static void configureREV(Supplier<REVLibError> config) {
for (int i = 0; i < REV_RETRY_COUNT; i++) {
if (config.get() == REVLibError.kOk) {
return;
}
}
}
Expand Down
7 changes: 5 additions & 2 deletions src/main/java/frc/robot/intake/IntakeMotorIOSparkMax.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

import com.revrobotics.CANSparkLowLevel.MotorType;
import com.revrobotics.CANSparkMax;
import frc.lib.Configurator;
import frc.robot.intake.IntakeConstants.IntakeMotorConstants;

/** Intake motor using a Spark Max. */
Expand All @@ -16,11 +17,13 @@ public IntakeMotorIOSparkMax() {

@Override
public void configure() {
sparkMax.restoreFactoryDefaults();
Configurator.configureREV(sparkMax::restoreFactoryDefaults);

sparkMax.setInverted(IntakeMotorConstants.IS_INVERTED);

sparkMax.setSmartCurrentLimit((int) IntakeMotorConstants.CURRENT_LIMITS.breakerAmps());
Configurator.configureREV(
() ->
sparkMax.setSmartCurrentLimit((int) IntakeMotorConstants.CURRENT_LIMITS.breakerAmps()));
}

@Override
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/odometry/GyroscopeIOPigeon2.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
import com.ctre.phoenix6.hardware.Pigeon2;
import edu.wpi.first.math.util.Units;
import frc.lib.CAN;
import frc.lib.ConfigApplier;
import frc.lib.Configurator;

/** Pigeon 2 gyroscope. */
public class GyroscopeIOPigeon2 implements GyroscopeIO {
Expand Down Expand Up @@ -33,7 +33,7 @@ public GyroscopeIOPigeon2(CAN gyroscopeCAN) {
public void configure() {
Pigeon2Configuration config = OdometryFactory.createGyroscopeConfig();

ConfigApplier.applyPigeon2Config(pigeon2.getConfigurator(), config);
Configurator.configurePigeon2(pigeon2.getConfigurator(), config);
}

@Override
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/swerve/AzimuthEncoderIOCANcoder.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
import com.ctre.phoenix6.hardware.CANcoder;
import edu.wpi.first.math.geometry.Rotation2d;
import frc.lib.CAN;
import frc.lib.ConfigApplier;
import frc.lib.Configurator;

/** CANcoder azimuth encoder. */
public class AzimuthEncoderIOCANcoder implements AzimuthEncoderIO {
Expand Down Expand Up @@ -39,7 +39,7 @@ public void configure() {

config.MagnetSensor.MagnetOffset = magnetOffset.getRotations();

ConfigApplier.applyCANcoderConfig(cancoder.getConfigurator(), config);
Configurator.configureCANcoder(cancoder.getConfigurator(), config);
}

@Override
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/swerve/DriveMotorIOTalonFXPID.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import frc.lib.CAN;
import frc.lib.ConfigApplier;
import frc.lib.Configurator;
import frc.robot.RobotConstants;
import frc.robot.swerve.SwerveConstants.DriveMotorConstants;
import frc.robot.swerve.SwerveConstants.MK4iConstants;
Expand Down Expand Up @@ -35,7 +35,7 @@ public DriveMotorIOTalonFXPID(CAN can) {
public void configure() {
TalonFXConfiguration config = SwerveFactory.createDriveMotorConfig();

ConfigApplier.applyTalonFXConfig(talonFX.getConfigurator(), config);
Configurator.configureTalonFX(talonFX.getConfigurator(), config);
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.controls.MotionMagicVoltage;
import frc.lib.CAN;
import frc.lib.ConfigApplier;
import frc.lib.Configurator;
import frc.robot.swerve.SwerveConstants.MK4iConstants;

/** TalonFX steer motor controlled by an internal controller. */
Expand All @@ -28,7 +28,7 @@ public void configure() {
config.MotionMagic.MotionMagicCruiseVelocity = 100.0 / MK4iConstants.STEER_GEARING;
config.MotionMagic.MotionMagicAcceleration = config.MotionMagic.MotionMagicCruiseVelocity * 10;

ConfigApplier.applyTalonFXConfig(talonFX.getConfigurator(), config);
Configurator.configureTalonFX(talonFX.getConfigurator(), config);
}

@Override
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/swerve/SteerMotorIOTalonFXPIDF.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
import com.ctre.phoenix6.controls.VoltageOut;
import edu.wpi.first.math.geometry.Rotation2d;
import frc.lib.CAN;
import frc.lib.ConfigApplier;
import frc.lib.Configurator;
import frc.robot.swerve.SwerveConstants.MK4iConstants;

/** TalonFX steer motor controlled by an external PIDF controller. */
Expand Down Expand Up @@ -33,7 +33,7 @@ public void configure() {

config.Feedback.SensorToMechanismRatio = MK4iConstants.STEER_GEARING;

ConfigApplier.applyTalonFXConfig(talonFX.getConfigurator(), config);
Configurator.configureTalonFX(talonFX.getConfigurator(), config);
}

@Override
Expand Down

0 comments on commit a240c1f

Please sign in to comment.