Skip to content
This repository was archived by the owner on Jan 17, 2026. It is now read-only.
Open
Show file tree
Hide file tree
Changes from 1 commit
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
7 changes: 6 additions & 1 deletion src/main/java/org/curtinfrc/frc2025/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -520,7 +520,6 @@ public Robot() {
controller
.leftStick()
.whileTrue(ejector.eject(15).withInterruptBehavior(InterruptionBehavior.kCancelIncoming));
controller.povUp().whileTrue(intake.intake(-4));

intake
.backSensor
Expand Down Expand Up @@ -552,6 +551,12 @@ public Robot() {
.andThen(ejector.stop())
.withInterruptBehavior(InterruptionBehavior.kCancelSelf));

intake.motorStalled.whileTrue(
Commands.runOnce(
() -> {
intake
.intake(-4);
}));
ejector.backSensor.whileTrue(intake.stop());

// Reset gyro to 0° when B button is pressed
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import org.littletonrobotics.junction.AutoLogOutput;
import org.littletonrobotics.junction.Logger;

public class Intake extends SubsystemBase {
Expand All @@ -16,6 +17,14 @@ public Intake(IntakeIO io) {
public final Trigger frontSensor = new Trigger(() -> inputs.frontSensor);
public final Trigger backSensor = new Trigger(() -> inputs.backSensor);

@AutoLogOutput(key = "Intake/motorStalled")
public final Trigger motorStalled =
new Trigger(
() ->
inputs.angularVelocityRotationsPerMinute < 6
&& inputs.appliedVolts > 0
&& inputs.currentAmps > 30);

@Override
public void periodic() {
io.updateInputs(inputs);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,20 +10,20 @@
public class IntakeIOSim implements IntakeIO {
private final DCMotor intakeMotor = DCMotor.getNEO(1);
private final DCMotorSim intakeMotorSim;
private final SimDevice frontImpl;
private final SimDevice frontSensorImpl;
private final SimBoolean frontSensor;
private final SimDevice backImpl;
private final SimDevice backSensorImpl;
private final SimBoolean backSensor;
private double volts = 0;

public IntakeIOSim() {
intakeMotorSim =
new DCMotorSim(LinearSystemId.createDCMotorSystem(intakeMotor, 3, 1), intakeMotor);

frontImpl = SimDevice.create("IntakeSensorFront", 3);
frontSensor = frontImpl.createBoolean("IsTriggered", Direction.kInput, false);
backImpl = SimDevice.create("IntakeSensorBack", 4);
backSensor = backImpl.createBoolean("IsTriggered", Direction.kInput, false);
frontSensorImpl = SimDevice.create("IntakeSensorFront", 3);
frontSensor = frontSensorImpl.createBoolean("IsTriggered", Direction.kInput, false);
backSensorImpl = SimDevice.create("IntakeSensorBack", 4);
backSensor = backSensorImpl.createBoolean("IsTriggered", Direction.kInput, false);
}

@Override
Expand Down
Loading