Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Switched Talon FX to SRX #182

Merged
merged 3 commits into from
Feb 8, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 6 additions & 0 deletions src/main/java/frc/robot/constants/IntakeConstants.java
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
package frc.robot.constants;

import com.ctre.phoenix.motorcontrol.SupplyCurrentLimitConfiguration;
import com.ctre.phoenix6.configs.CurrentLimitsConfigs;

public class IntakeConstants {
Expand All @@ -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;
}
Original file line number Diff line number Diff line change
@@ -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);
}
}
Loading