From dd09bac6965a1f99148eabdd49f6bffe54ddf39e Mon Sep 17 00:00:00 2001 From: Raymond Dokholyan <58710772+urayed@users.noreply.github.com> Date: Sat, 8 Feb 2025 17:05:02 -0500 Subject: [PATCH] Switched Talon FX to SRX (#182) * Switched Talon FX to SRX * Fixed voltage setting. --------- Co-authored-by: mmilunicmobile Co-authored-by: Matthew Milunic <62996888+mmilunicmobile@users.noreply.github.com> --- .../frc/robot/constants/IntakeConstants.java | 6 ++++ .../intake/IntakeRollerTalonFX.java | 31 ++++++++++--------- 2 files changed, 22 insertions(+), 15 deletions(-) diff --git a/src/main/java/frc/robot/constants/IntakeConstants.java b/src/main/java/frc/robot/constants/IntakeConstants.java index 587aed0e..2ead1810 100644 --- a/src/main/java/frc/robot/constants/IntakeConstants.java +++ b/src/main/java/frc/robot/constants/IntakeConstants.java @@ -1,5 +1,6 @@ package frc.robot.constants; +import com.ctre.phoenix.motorcontrol.SupplyCurrentLimitConfiguration; import com.ctre.phoenix6.configs.CurrentLimitsConfigs; public class IntakeConstants { @@ -17,5 +18,10 @@ public class IntakeConstants { public static final CurrentLimitsConfigs currentLimit = new CurrentLimitsConfigs(); + public static final SupplyCurrentLimitConfiguration rollerSupplyCurrentLimit = + new SupplyCurrentLimitConfiguration(); + + public static final int rollerContinuousCurrentLimit = 90; + public static final int intakeGPSensor = 99; } diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeRollerTalonFX.java b/src/main/java/frc/robot/subsystems/intake/IntakeRollerTalonFX.java index 1ca618cc..fe450c80 100644 --- a/src/main/java/frc/robot/subsystems/intake/IntakeRollerTalonFX.java +++ b/src/main/java/frc/robot/subsystems/intake/IntakeRollerTalonFX.java @@ -1,36 +1,37 @@ package frc.robot.subsystems.intake; -import com.ctre.phoenix6.configs.TalonFXConfiguration; -import com.ctre.phoenix6.hardware.TalonFX; -import com.ctre.phoenix6.signals.NeutralModeValue; +import com.ctre.phoenix.motorcontrol.ControlMode; +import com.ctre.phoenix.motorcontrol.NeutralMode; +import com.ctre.phoenix.motorcontrol.can.TalonSRX; import edu.wpi.first.wpilibj.DigitalInput; import frc.robot.constants.IntakeConstants; public class IntakeRollerTalonFX implements IntakeRollerIO { - private final TalonFX intakeroller = - new TalonFX(IntakeConstants.idRoller, IntakeConstants.canbusRoller); + private final TalonSRX intakeroller = new TalonSRX(IntakeConstants.idRoller); private DigitalInput intakeGPSensor = new DigitalInput(IntakeConstants.intakeGPSensor); public IntakeRollerTalonFX() { - intakeroller.setVoltage(0); + intakeroller.set(ControlMode.PercentOutput, 0); - intakeroller - .getConfigurator() - .apply(new TalonFXConfiguration().withCurrentLimits(IntakeConstants.currentLimit)); + intakeroller.enableVoltageCompensation(true); - intakeroller.setNeutralMode(NeutralModeValue.Brake); + // intakeroller.configSupplyCurrentLimit(IntakeConstants.rollerSupplyCurrentLimit); + + // intakeroller.configContinuousCurrentLimit(IntakeConstants.rollerContinuousCurrentLimit); + + intakeroller.setNeutralMode(NeutralMode.Brake); } public void updateInputs(IntakeRollerIOInputs inputs) { - inputs.speed = intakeroller.getVelocity().getValueAsDouble(); - inputs.voltage = intakeroller.getMotorVoltage().getValueAsDouble(); - inputs.temperature = intakeroller.getDeviceTemp().getValueAsDouble(); - inputs.current = intakeroller.getStatorCurrent().getValueAsDouble(); + inputs.speed = intakeroller.getSelectedSensorVelocity(); + inputs.voltage = intakeroller.getMotorOutputVoltage(); + inputs.temperature = intakeroller.getTemperature(); + inputs.current = intakeroller.getStatorCurrent(); inputs.sensor = intakeGPSensor.get(); } public void setVoltage(double voltage) { - intakeroller.set(voltage); + intakeroller.set(ControlMode.PercentOutput, voltage / 12.0); } }