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

Commit

Permalink
refactor(config): Use device-specific config appliers.
Browse files Browse the repository at this point in the history
  • Loading branch information
haydenheroux committed May 13, 2024
1 parent b489e2b commit 29d6355
Show file tree
Hide file tree
Showing 11 changed files with 306 additions and 232 deletions.
33 changes: 0 additions & 33 deletions src/main/java/frc/lib/config/AbsoluteEncoderConfig.java
Original file line number Diff line number Diff line change
@@ -1,8 +1,5 @@
package frc.lib.config;

import com.ctre.phoenix6.configs.CANcoderConfiguration;
import com.ctre.phoenix6.configs.MagnetSensorConfigs;
import com.ctre.phoenix6.signals.SensorDirectionValue;
import edu.wpi.first.math.geometry.Rotation2d;
import java.util.Objects;

Expand Down Expand Up @@ -63,34 +60,4 @@ public AbsoluteEncoderConfig build() {
return new AbsoluteEncoderConfig(ccwPositive, sensorToMechanismRatio, offset);
}
}

/**
* Creates Phoenix 6 magnet sensor configs.
*
* @return Phoenix 6 magnet sensor configs.
*/
private MagnetSensorConfigs createMagnetSensorConfigs() {
final MagnetSensorConfigs magnetSensorConfigs = new MagnetSensorConfigs();

magnetSensorConfigs.MagnetOffset = offset().getRotations();
magnetSensorConfigs.SensorDirection =
ccwPositive()
? SensorDirectionValue.CounterClockwise_Positive
: SensorDirectionValue.Clockwise_Positive;

return magnetSensorConfigs;
}

/**
* Creates a Phoenix 6 CANcoder config.
*
* @return a Phoenix 6 CANcoder config.
*/
public CANcoderConfiguration createCANcoderConfig() {
final CANcoderConfiguration cancoderConfig = new CANcoderConfiguration();

cancoderConfig.MagnetSensor = createMagnetSensorConfigs();

return cancoderConfig;
}
}
112 changes: 0 additions & 112 deletions src/main/java/frc/lib/config/ConfigApplier.java

This file was deleted.

61 changes: 0 additions & 61 deletions src/main/java/frc/lib/config/MotorConfig.java
Original file line number Diff line number Diff line change
@@ -1,10 +1,5 @@
package frc.lib.config;

import com.ctre.phoenix6.configs.CurrentLimitsConfigs;
import com.ctre.phoenix6.configs.MotorOutputConfigs;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.NeutralModeValue;
import java.util.Objects;

/** Motor config. */
Expand Down Expand Up @@ -90,60 +85,4 @@ public MotorConfig build() {
neutralBrake, ccwPositive, motorToMechanismRatio, statorCurrentLimit, supplyCurrentLimit);
}
}

/**
* Creates Phoenix 6 current limit configs.
*
* @return Phoenix 6 current limit configs.
*/
private CurrentLimitsConfigs createCurrentLimitsConfigs() {
final CurrentLimitsConfigs currentLimitsConfigs = new CurrentLimitsConfigs();

// Stator current is a measure of the current inside of the motor and is typically higher than
// supply (breaker) current
currentLimitsConfigs.StatorCurrentLimit = statorCurrentLimit;
currentLimitsConfigs.StatorCurrentLimitEnable = true;

currentLimitsConfigs.SupplyCurrentLimit = supplyCurrentLimit;
// TODO Determine if spikes should be eliminated to preserve battery
// Allow higher current spikes (150%) for a very brief duration (tenth second)
currentLimitsConfigs.SupplyCurrentThreshold = supplyCurrentLimit * 1.5;
currentLimitsConfigs.SupplyTimeThreshold = 0.1;
currentLimitsConfigs.SupplyCurrentLimitEnable = true;

return currentLimitsConfigs;
}

/**
* Creates Phoenix 6 motor output configs.
*
* @return Phoenix 6 motor output configs.
*/
private MotorOutputConfigs createMotorOutputConfigs() {
final MotorOutputConfigs motorOutputConfigs = new MotorOutputConfigs();

motorOutputConfigs.Inverted =
ccwPositive() ? InvertedValue.CounterClockwise_Positive : InvertedValue.Clockwise_Positive;
motorOutputConfigs.NeutralMode =
neutralBrake() ? NeutralModeValue.Brake : NeutralModeValue.Coast;

return motorOutputConfigs;
}

/**
* Creates a Phoenix 6 TalonFX config.
*
* @return a Phoenix 6 TalonFX config.
*/
public TalonFXConfiguration createTalonFXConfig() {
final TalonFXConfiguration talonFXConfig = new TalonFXConfiguration();

talonFXConfig.MotorOutput = createMotorOutputConfigs();

talonFXConfig.CurrentLimits = createCurrentLimitsConfigs();

talonFXConfig.Feedback.SensorToMechanismRatio = motorToMechanismRatio();

return talonFXConfig;
}
}
73 changes: 73 additions & 0 deletions src/main/java/frc/lib/config/applier/CANcoderConfigApplier.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,73 @@
package frc.lib.config.applier;

import com.ctre.phoenix6.configs.CANcoderConfiguration;
import com.ctre.phoenix6.configs.CANcoderConfigurator;
import com.ctre.phoenix6.configs.MagnetSensorConfigs;
import com.ctre.phoenix6.hardware.CANcoder;
import com.ctre.phoenix6.signals.SensorDirectionValue;
import edu.wpi.first.wpilibj.DriverStation;
import frc.lib.config.AbsoluteEncoderConfig;

/** Applies CANcoder configs. */
public class CANcoderConfigApplier extends ConfigApplier {

/**
* Reports to the user that a CANcoder failed configuration.
*
* @param cancoder the CANcoder.
*/
private static void report(CANcoder cancoder) {
DriverStation.reportWarning(
"Failed to apply config to CANcoder with ID: " + cancoder.getDeviceID(), false);
}

/**
* Applies a factory default config to a CANcoder.
*
* @param cancoder the CANcoder.
*/
public static void applyFactoryDefault(CANcoder cancoder) {
CANcoderConfiguration factoryDefaults = new CANcoderConfiguration();

CANcoderConfigurator configurator = cancoder.getConfigurator();

if (attempt(() -> configurator.apply(factoryDefaults)) == false) {
report(cancoder);
}
}

/**
* Creates the magnet sensor configs for the absolute encoder config.
*
* @param absoluteEncoderConfig the absolute encoder config.
* @return the created magnet sensor configs.
*/
private static MagnetSensorConfigs createMagnetSensorConfigs(
AbsoluteEncoderConfig absoluteEncoderConfig) {
final MagnetSensorConfigs magnetSensorConfigs = new MagnetSensorConfigs();

magnetSensorConfigs.MagnetOffset = absoluteEncoderConfig.offset().getRotations();
magnetSensorConfigs.SensorDirection =
absoluteEncoderConfig.ccwPositive()
? SensorDirectionValue.CounterClockwise_Positive
: SensorDirectionValue.Clockwise_Positive;

return magnetSensorConfigs;
}

/**
* Applies an absolute encoder config to a CANcoder.
*
* @param cancoder the CANcoder.
* @param absoluteEncoderConfig the absolute encoder config.
*/
public static void apply(CANcoder cancoder, AbsoluteEncoderConfig absoluteEncoderConfig) {
MagnetSensorConfigs magnetSensorConfigs = createMagnetSensorConfigs(absoluteEncoderConfig);

CANcoderConfigurator configurator = cancoder.getConfigurator();

if (attempt(() -> configurator.apply(magnetSensorConfigs)) == false) {
report(cancoder);
}
}
}
42 changes: 42 additions & 0 deletions src/main/java/frc/lib/config/applier/ConfigApplier.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
package frc.lib.config.applier;

import com.ctre.phoenix6.StatusCode;
import java.util.function.Function;
import java.util.function.Supplier;

/** Applies configs. */
public class ConfigApplier {

/**
* Attempts to apply a config. Returns true if successful.
*
* @param applier a function that attempts to apply a config. Returns the result of the
* application.
* @param isSuccess a function that returns true if the result of an application is a success.
* @param retries the number of unsuccessful attempts before failing.
* @return true if successful.
*/
protected static <Result> boolean attempt(
Supplier<Result> applier, Function<Result, Boolean> isSuccess, int retries) {
for (int i = 0; i < retries; i++) {
Result result = applier.get();

if (isSuccess.apply(result)) {
return true;
}
}

return false;
}

/**
* Attempts to apply a Phoenix 6 config. Returns true if successful.
*
* @param applier a function that attempts to apply a config. Returns the result of the
* application.
* @return true if successful.
*/
protected static boolean attempt(Supplier<StatusCode> applier) {
return attempt(() -> applier.get(), StatusCode::isOK, 10);
}
}
35 changes: 35 additions & 0 deletions src/main/java/frc/lib/config/applier/Pigeon2ConfigApplier.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
package frc.lib.config.applier;

import com.ctre.phoenix6.configs.Pigeon2Configuration;
import com.ctre.phoenix6.configs.Pigeon2Configurator;
import com.ctre.phoenix6.hardware.Pigeon2;
import edu.wpi.first.wpilibj.DriverStation;

/** Applies Pigeon 2 configs. */
public class Pigeon2ConfigApplier extends ConfigApplier {

/**
* Reports to the user that a Pigeon 2 failed configuration.
*
* @param pigeon2 the Pigeon 2.
*/
private static void report(Pigeon2 pigeon2) {
DriverStation.reportWarning(
"Failed to apply config to Pigeon 2 with ID: " + pigeon2.getDeviceID(), false);
}

/**
* Applies a factory default config to a Pigeon 2.
*
* @param pigeon2 the Pigeon 2.
*/
public static void applyFactoryDefault(Pigeon2 pigeon2) {
Pigeon2Configuration factoryDefaults = new Pigeon2Configuration();

Pigeon2Configurator configurator = pigeon2.getConfigurator();

if (attempt(() -> configurator.apply(factoryDefaults)) == false) {
report(pigeon2);
}
}
}
Loading

0 comments on commit 29d6355

Please sign in to comment.