diff --git a/src/main/java/org/littletonrobotics/frc2024/subsystems/drive/Module.java b/src/main/java/org/littletonrobotics/frc2024/subsystems/drive/Module.java index 2e3deddd..b41e9d40 100644 --- a/src/main/java/org/littletonrobotics/frc2024/subsystems/drive/Module.java +++ b/src/main/java/org/littletonrobotics/frc2024/subsystems/drive/Module.java @@ -73,7 +73,7 @@ public void updateInputs() { LoggedTunableNumber.ifChanged( hashCode(), () -> io.setTurnPID(turnkP.get(), 0, turnkD.get()), turnkP, turnkD); - // Display warnings + // Display alerts driveMotorDisconnected.set(!inputs.driveMotorConnected); turnMotorDisconnected.set(!inputs.turnMotorConnected); } diff --git a/src/main/java/org/littletonrobotics/frc2024/subsystems/drive/ModuleIOKrakenFOC.java b/src/main/java/org/littletonrobotics/frc2024/subsystems/drive/ModuleIOKrakenFOC.java index c750bc94..32742835 100644 --- a/src/main/java/org/littletonrobotics/frc2024/subsystems/drive/ModuleIOKrakenFOC.java +++ b/src/main/java/org/littletonrobotics/frc2024/subsystems/drive/ModuleIOKrakenFOC.java @@ -63,8 +63,8 @@ public class ModuleIOKrakenFOC implements ModuleIO { new VelocityTorqueCurrentFOC(0).withUpdateFreqHz(0); private final PositionTorqueCurrentFOC turnPositionControl = new PositionTorqueCurrentFOC(0).withUpdateFreqHz(0); - private final NeutralOut driveBrake = new NeutralOut().withUpdateFreqHz(0); - private final NeutralOut turnBrake = new NeutralOut().withUpdateFreqHz(0); + private final NeutralOut driveNeutral = new NeutralOut().withUpdateFreqHz(0); + private final NeutralOut turnNeutral = new NeutralOut().withUpdateFreqHz(0); public ModuleIOKrakenFOC(ModuleConfig config) { // Init controllers and encoders from config constants @@ -156,11 +156,11 @@ public void updateInputs(ModuleIOInputs inputs) { driveAppliedVolts, driveSupplyCurrent, driveTorqueCurrent) - == StatusCode.OK; + .isOK(); inputs.turnMotorConnected = BaseStatusSignal.refreshAll( turnPosition, turnVelocity, turnAppliedVolts, turnSupplyCurrent, turnTorqueCurrent) - == StatusCode.OK; + .isOK(); inputs.drivePositionRad = Units.rotationsToRadians(drivePosition.getValueAsDouble()); inputs.driveVelocityRadPerSec = Units.rotationsToRadians(driveVelocity.getValueAsDouble()); @@ -247,7 +247,7 @@ public void setTurnBrakeMode(boolean enable) { @Override public void stop() { - driveTalon.setControl(driveBrake); - turnTalon.setControl(turnBrake); + driveTalon.setControl(driveNeutral); + turnTalon.setControl(turnNeutral); } }