Files
2026KPopRobotHunters/src/main/java/frc4388/robot/subsystems/intake/IntakeIO.java
T
2026-02-14 15:57:33 -07:00

43 lines
1.7 KiB
Java

package frc4388.robot.subsystems.intake;
import static edu.wpi.first.units.Units.Amps;
import static edu.wpi.first.units.Units.Rotations;
import static edu.wpi.first.units.Units.RotationsPerSecond;
import org.littletonrobotics.junction.AutoLog;
import edu.wpi.first.units.measure.Angle;
import edu.wpi.first.units.measure.AngularVelocity;
import edu.wpi.first.units.measure.Current;
public interface IntakeIO {
@AutoLog
public class IntakeState {
boolean retractedLimit = false;
Angle armAngle = Rotations.of(0);
Angle armTargetAngle = Rotations.of(0);
Current armMotorCurrent = Amps.of(0);
// Angle shooterPitch = Rotations.of(0);
// Angle shooterTargetPitch = Rotations.of(0);
// Current pitchMotorCurrent = Amps.of(0);
AngularVelocity rollerVelocity = RotationsPerSecond.of(0);
AngularVelocity rollerTargetVelocity = RotationsPerSecond.of(0);
Current rollerMotorCurrent = Amps.of(0);
// LinearVelocity feederVelocity = InchesPerSecond.of(0);
// LinearVelocity feederTargetVelocity = InchesPerSecond.of(0);
// Current feederMotorCurrent = Amps.of(0);
}
// public default void setShooterAngle(ShooterState state, Angle angle) {}
// public default void setShooterPitch(ShooterState state, Angle angle) {}
public default void setArmAngle(IntakeState state, Angle angle) {}
public default void stopArm() {}
public default void setRollerVelocity(IntakeState state, AngularVelocity angularVelocity) {}
public default void armExtend(double percentOutput) {}
public default void armRetract(double percentOutput) {}
public default void updateInputs(IntakeState state) {}
public default void updateGains() {}
}