Skip to content

Commit

Permalink
decent changes
Browse files Browse the repository at this point in the history
  • Loading branch information
Ishan1522 committed Aug 9, 2024
1 parent d969077 commit 51f121e
Show file tree
Hide file tree
Showing 2 changed files with 137 additions and 10 deletions.
113 changes: 113 additions & 0 deletions src/main/java/frc/robot/extras/TalonUtil.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,113 @@
// somewhat inspired by 254
package frc.robot.extras;

import java.util.function.Supplier;

import com.ctre.phoenix.ErrorCode;
import com.ctre.phoenix6.StatusCode;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.hardware.TalonFX;
import edu.wpi.first.wpilibj.DriverStation;

public class TalonUtil {

public static boolean applyAndCheckConfiguration(
TalonFX talon, TalonFXConfiguration config, double timeoutSeconds, int numTries) {
for (int i = 0; i < numTries; i++) {
if (checkErrorAndRetry(() -> talon.getConfigurator().apply(config, timeoutSeconds))) {
return true;
}
}
DriverStation.reportError(
"Failed to apply config for talon after " + numTries + " attempts", false);
return false;
}


public static boolean applyAndCheckConfiguration(TalonFX talon, TalonFXConfiguration config, double timeoutMs) {
boolean result = applyAndCheckConfiguration(talon, config, timeoutMs, 5);
return result;
}

public enum StickyFault {
BootDuringEnable,
DeviceTemp,
ForwardHardLimit,
ForwardSoftLimit,
Hardware,
OverSupplyV,
ProcTemp,
ReverseHardLimit,
ReverseSoftLimit,
Undervoltage,
UnstableSupplyV
}

public static void checkStickyFaults(String subsystemName, TalonFX talon) {
boolean[] faults = new boolean[StickyFault.values().length];
faults[0] = talon.getStickyFault_BootDuringEnable().getValue();
faults[1] = talon.getStickyFault_DeviceTemp().getValue();
faults[2] = talon.getStickyFault_ForwardHardLimit().getValue();
faults[3] = talon.getStickyFault_ForwardSoftLimit().getValue();
faults[4] = talon.getStickyFault_Hardware().getValue();
faults[5] = talon.getStickyFault_OverSupplyV().getValue();
faults[6] = talon.getStickyFault_ProcTemp().getValue();
faults[7] = talon.getStickyFault_ReverseHardLimit().getValue();
faults[8] = talon.getStickyFault_ReverseSoftLimit().getValue();
faults[9] = talon.getStickyFault_Undervoltage().getValue();
faults[10] = talon.getStickyFault_UnstableSupplyV().getValue();

for (int i = 0; i < faults.length; i++) {
if (faults[i]) {
DriverStation.reportError(
subsystemName + ": Talon Fault! " + StickyFault.values()[i].toString(), false);
}
}

talon.clearStickyFaults();
}

/**
* checks the specified error code for issues
*
* @param errorCode error code
* @param message message to print if error happens
*/
public static void checkError(ErrorCode errorCode, String message) {
if (errorCode != ErrorCode.OK) {
DriverStation.reportError(message + " " + errorCode, false);
}
}

public static boolean checkErrorAndRetry(Supplier<StatusCode> function, int numTries) {
StatusCode code = function.get();
int tries = 0;
while (code != StatusCode.OK && tries < numTries) {
DriverStation.reportWarning("Retrying CTRE Device Config " + code.getName(), false);
code = function.get();
tries++;
}
if (code != StatusCode.OK) {
DriverStation.reportError(
"Failed to execute phoenix pro api call after " + numTries + " attempts", false);
return false;
}
return true;
}

/**
* checks the specified error code and throws an exception if there are any issues
*
* @param errorCode error code
* @param message message to print if error happens
*/
public static void checkErrorWithThrow(ErrorCode errorCode, String message) {
if (errorCode != ErrorCode.OK) {
throw new RuntimeException(message + " " + errorCode);
}
}

public static boolean checkErrorAndRetry(Supplier<StatusCode> function) {
return checkErrorAndRetry(function, 5);
}
}
34 changes: 24 additions & 10 deletions src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
import frc.robot.Constants.HardwareConstants;
import frc.robot.Constants.ShooterConstants;
import frc.robot.extras.SmarterDashboardRegistry;
import frc.robot.extras.TalonUtil;

public class ShooterSubsystem extends SubsystemBase {
private final TalonFX leaderFlywheel;
Expand All @@ -42,7 +43,25 @@ public ShooterSubsystem() {
velocityRequest = new VelocityVoltage(0);
voltageRequest = new VoltageOut(0);

try {
configureTalons();
} catch (RuntimeException e) {
System.out.println("Failed to configure talons :(");
}

leaderVelocity = leaderFlywheel.getVelocity();
followerVelocity = followerFlywheel.getVelocity();

BaseStatusSignal.setUpdateFrequencyForAll(
HardwareConstants.SIGNAL_FREQUENCY, leaderVelocity, followerVelocity);
ParentDevice.optimizeBusUtilizationForAll(leaderFlywheel, rollerMotor, followerFlywheel);
}

private void configureTalons() throws RuntimeException {
TalonFXConfiguration shooterConfig = new TalonFXConfiguration();
TalonUtil.checkErrorAndRetry(() -> leaderFlywheel.getConfigurator().refresh(shooterConfig, HardwareConstants.TIMEOUT_S));
TalonUtil.checkErrorAndRetry(() -> followerFlywheel.getConfigurator().refresh(shooterConfig, HardwareConstants.TIMEOUT_S));

shooterConfig.Slot0.kP = ShooterConstants.SHOOT_P;
shooterConfig.Slot0.kI = ShooterConstants.SHOOT_I;
shooterConfig.Slot0.kD = ShooterConstants.SHOOT_D;
Expand All @@ -58,21 +77,16 @@ public ShooterSubsystem() {
shooterConfig.CurrentLimits.SupplyCurrentLimit = ShooterConstants.SHOOTER_SUPPLY_LIMIT;
shooterConfig.CurrentLimits.SupplyCurrentLimitEnable = ShooterConstants.SHOOTER_SUPPLY_ENABLE;

leaderFlywheel.getConfigurator().apply(shooterConfig, HardwareConstants.TIMEOUT_S);
TalonUtil.applyAndCheckConfiguration(leaderFlywheel, shooterConfig, HardwareConstants.TIMEOUT_S);
shooterConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive;
followerFlywheel.getConfigurator().apply(shooterConfig, HardwareConstants.TIMEOUT_S);
TalonUtil.applyAndCheckConfiguration(followerFlywheel, shooterConfig, HardwareConstants.TIMEOUT_S);

TalonFXConfiguration rollerConfig = new TalonFXConfiguration();
TalonUtil.checkErrorAndRetry(() -> leaderFlywheel.getConfigurator().refresh(rollerConfig, HardwareConstants.TIMEOUT_S));

rollerConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake;
rollerConfig.MotorOutput.DutyCycleNeutralDeadband = HardwareConstants.MIN_FALCON_DEADBAND;
rollerMotor.getConfigurator().apply(rollerConfig, HardwareConstants.TIMEOUT_S);

leaderVelocity = leaderFlywheel.getVelocity();
followerVelocity = followerFlywheel.getVelocity();

BaseStatusSignal.setUpdateFrequencyForAll(
HardwareConstants.SIGNAL_FREQUENCY, leaderVelocity, followerVelocity);
ParentDevice.optimizeBusUtilizationForAll(leaderFlywheel, rollerMotor, followerFlywheel);
TalonUtil.applyAndCheckConfiguration(rollerMotor, rollerConfig, HardwareConstants.TIMEOUT_S);
}

/**
Expand Down

0 comments on commit 51f121e

Please sign in to comment.