-
-
Notifications
You must be signed in to change notification settings - Fork 1
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge remote-tracking branch 'origin/main' into offseason-base
- Loading branch information
Showing
2 changed files
with
22 additions
and
15 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
31 changes: 16 additions & 15 deletions
31
src/main/java/frc/robot/subsystems/intake/IntakeRollerTalonFX.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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); | ||
} | ||
} |