Skip to content

Commit

Permalink
Merge remote-tracking branch 'origin/main' into offseason-base
Browse files Browse the repository at this point in the history
  • Loading branch information
krypto-bot-2539[bot] committed Feb 8, 2025
2 parents 799312c + dd09bac commit bb12e00
Show file tree
Hide file tree
Showing 2 changed files with 22 additions and 15 deletions.
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;
}
31 changes: 16 additions & 15 deletions src/main/java/frc/robot/subsystems/intake/IntakeRollerTalonFX.java
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);
}
}

0 comments on commit bb12e00

Please sign in to comment.