From ac1f386e63ccb94224b0fa68be34b26a272b2a0d Mon Sep 17 00:00:00 2001 From: Ghost <145223182+GhostR406@users.noreply.github.com> Date: Thu, 29 Jan 2026 18:23:28 -0500 Subject: [PATCH] 1/29/26 added intake.stop(), intake.getPosition(), & intake.getVelocity()! --- .../java/frc/robot/subsystems/intake/Intake.java | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/src/main/java/frc/robot/subsystems/intake/Intake.java b/src/main/java/frc/robot/subsystems/intake/Intake.java index dc054da..f5bb45e 100644 --- a/src/main/java/frc/robot/subsystems/intake/Intake.java +++ b/src/main/java/frc/robot/subsystems/intake/Intake.java @@ -2,6 +2,7 @@ import static edu.wpi.first.units.Units.RotationsPerSecond; +import edu.wpi.first.units.measure.Angle; import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc.lib.W8.io.motor.MotorIO.PIDSlot; @@ -21,6 +22,18 @@ public void setVelocity(double velocity) { _io.runVelocity(angVelo, Constants.IntakeConstants.ACCELERATION, PIDSlot.SLOT_0); } + public AngularVelocity getVelocity() { + return _io.getVelocity(); + } + + public Angle getPosition() { + return _io.getPosition(); + } + + public void stop() { + setVelocity(0); + } + @Override public void periodic() {} }