Limit Switch

This commit is contained in:
Michael Mikovsky
2026-02-14 10:55:51 -08:00
parent 0425cdd0a1
commit 8381ac4607
8 changed files with 89 additions and 66 deletions
@@ -7,19 +7,24 @@ import java.util.function.Supplier;
import org.littletonrobotics.junction.Logger;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc4388.robot.subsystems.intake.Intake.IntakeMode;
public class Intake extends SubsystemBase {
public IntakeIO io;
IntakeStateAutoLogged state = new IntakeStateAutoLogged();
Supplier<Pose2d> m_swervePoseSupplier;
public DigitalInput m_armLimitSwitch;
public Intake(
IntakeIO io
IntakeIO io,
DigitalInput m_armLimitSwitch
// Supplier<Pose2d> swervePoseSupplier
) {
this.io = io;
this.m_armLimitSwitch= m_armLimitSwitch;
// this.m_swervePoseSupplier = swervePoseSupplier;
}
@@ -56,6 +61,7 @@ public class Intake extends SubsystemBase {
@Override
public void periodic() {
// FaultReporter.register(this); // TODO Implement fault reporter
// System.out.println(m_armLimitSwitch.get());
Logger.processInputs("Intake", state);
@@ -68,7 +74,12 @@ public class Intake extends SubsystemBase {
io.setRollerVelocity(state, RotationsPerSecond.of(IntakeConstants.ROLLER_ACTIVE.get()));
break;
case Retracted:
io.setArmAngle(state, Rotations.of(IntakeConstants.ARM_LIMIT_RETRACTED.get()));
if (!m_armLimitSwitch.get()){
System.out.println("Triggered!");
io.stopArm();
} else {
io.setArmAngle(state, Rotations.of(IntakeConstants.ARM_LIMIT_RETRACTED.get()));
}
io.setRollerVelocity(state, RotationsPerSecond.of(0));
break;
}
@@ -12,7 +12,7 @@ import frc4388.utility.status.CanDevice;
public class IntakeConstants {
// Motor conversions
public static final double ARM_MOTOR_GEAR_RATIO = 100;
public static final double ARM_MOTOR_GEAR_RATIO = 125;
public static final double ROLLER_MOTOR_GEAR_RATIO = 3;
@@ -68,7 +68,7 @@ public class IntakeConstants {
public static final TalonFXConfiguration ARM_MOTOR_CONFIG = new TalonFXConfiguration()
.withCurrentLimits(
new CurrentLimitsConfigs()
.withStatorCurrentLimit(40) // TODO: tune???
.withStatorCurrentLimit(15) // TODO: tune???
.withStatorCurrentLimitEnable(true)
).withMotorOutput(
new MotorOutputConfigs()
@@ -33,6 +33,7 @@ public interface IntakeIO {
// 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 updateInputs(IntakeState state) {}
@@ -78,6 +78,10 @@ public class IntakeReal implements IntakeIO {
// PositionDutyCycle posRequest = new PositionDutyCycle(motorTargetAngle);
m_armMotor.setControl(armPosition.withPosition(motorAngle));
}
@Override
public void stopArm(){
m_armMotor.set(0);
}
@Override
public void updateInputs(IntakeState state) {
@@ -97,54 +97,54 @@ public class Shooter extends SubsystemBase {
// TODO: get if the robot is within the angle of the hub
boolean driverError =
XYSpeed <= ShooterConstants.ROBOT_SPEED_TOLERANCE.get() |
AngSpeed <= ShooterConstants.ROBOT_ANG_SPEED_TOLERANCE.get() |
distanceToHub <= ShooterConstants.ROBOT_MIN_HUB.get() |
distanceToHub >= ShooterConstants.ROBOT_MAX_HUB.get();
// boolean driverError =
// XYSpeed <= ShooterConstants.ROBOT_SPEED_TOLERANCE.get() |
// AngSpeed <= ShooterConstants.ROBOT_ANG_SPEED_TOLERANCE.get() |
// distanceToHub <= ShooterConstants.ROBOT_MIN_HUB.get() |
// distanceToHub >= ShooterConstants.ROBOT_MAX_HUB.get();
double shooterSpeed = Math.abs(state.motor1Velocity.in(RotationsPerSecond) + state.motor2Velocity.in(RotationsPerSecond)) / 2;
// double shooterSpeed = Math.abs(state.motor1Velocity.in(RotationsPerSecond) + state.motor2Velocity.in(RotationsPerSecond)) / 2;
boolean badShooterVelocity = shooterSpeed < ShooterConstants.SHOOTER_SPEED_TOLERANCE.get();
boolean intakeBad = m_Intake.getMode() == IntakeMode.Extended;
// boolean badShooterVelocity = shooterSpeed < ShooterConstants.SHOOTER_SPEED_TOLERANCE.get();
// boolean intakeBad = m_Intake.getMode() == IntakeMode.Extended;
int bitmask = (driverError ? 1 : 0) + (badShooterVelocity ? 2 : 0) + (intakeBad ? 4 : 0);
switch (bitmask) {
case 0b000: // No Errors
m_robotLED.setMode(Constants.LEDConstants.OPREADY);
break;
case 0b001: // No op err, yes driver err
m_robotLED.setMode(Constants.LEDConstants.OPREADY_BADPHYS);
break;
case 0b010: // Bad flywheel, no driver err
m_robotLED.setMode(Constants.LEDConstants.BAD_FLYWEEL);
break;
case 0b011: // Bad flywheel, yes driver err
m_robotLED.setMode(Constants.LEDConstants.BAD_FLYWEEL_BADPHYS);
break;
case 0b100: // Bad intake, no driver err
m_robotLED.setMode(Constants.LEDConstants.INTAKE_OUT);
break;
case 0b101: // Bad intake, yes driver err
m_robotLED.setMode(Constants.LEDConstants.INTAKE_OUT_BADPHYS);
break;
case 0b110: // Bad intake and shooter (intake is more important), no driver err
m_robotLED.setMode(Constants.LEDConstants.INTAKE_OUT);
break;
case 0b111: // Bad intake and shooter (intake is more important), yes driver err
m_robotLED.setMode(Constants.LEDConstants.INTAKE_OUT_BADPHYS);
break;
}
// int bitmask = (driverError ? 1 : 0) + (badShooterVelocity ? 2 : 0) + (intakeBad ? 4 : 0);
// switch (bitmask) {
// case 0b000: // No Errors
// m_robotLED.setMode(Constants.LEDConstants.OPREADY);
// break;
// case 0b001: // No op err, yes driver err
// m_robotLED.setMode(Constants.LEDConstants.OPREADY_BADPHYS);
// break;
// case 0b010: // Bad flywheel, no driver err
// m_robotLED.setMode(Constants.LEDConstants.BAD_FLYWEEL);
// break;
// case 0b011: // Bad flywheel, yes driver err
// m_robotLED.setMode(Constants.LEDConstants.BAD_FLYWEEL_BADPHYS);
// break;
// case 0b100: // Bad intake, no driver err
// m_robotLED.setMode(Constants.LEDConstants.INTAKE_OUT);
// break;
// case 0b101: // Bad intake, yes driver err
// m_robotLED.setMode(Constants.LEDConstants.INTAKE_OUT_BADPHYS);
// break;
// case 0b110: // Bad intake and shooter (intake is more important), no driver err
// m_robotLED.setMode(Constants.LEDConstants.INTAKE_OUT);
// break;
// case 0b111: // Bad intake and shooter (intake is more important), yes driver err
// m_robotLED.setMode(Constants.LEDConstants.INTAKE_OUT_BADPHYS);
// break;
// }
// We set the shooter mode to ready if there are no errors
mode = (
bitmask == 0 ?
ShooterMode.Ready :
ShooterMode.NotReady
);
// // We set the shooter mode to ready if there are no errors
// mode = (
// bitmask == 0 ?
// ShooterMode.Ready :
// ShooterMode.NotReady
// );
}
// }
switch (mode) {
case Shooting:
@@ -162,4 +162,4 @@ public class Shooter extends SubsystemBase {
}
}
}
}}
@@ -24,8 +24,8 @@ public class ShooterConstants {
// public static final AngularVelocity INDEXER_ACTIVE_VELOCITY = RotationsPerSecond.of(10);
// public static final AngularVelocity INDEXER_INACTIVE_VELOCITY = RotationsPerSecond.of(0.0);
public static final ConfigurableDouble SHOOTER_ACTIVE_VELOCITY = new ConfigurableDouble("Shooter Active Velocity", 30);
public static final ConfigurableDouble SHOOTER_RESTING_VELOCITY = new ConfigurableDouble("Shooter Resting Velocity", 15);
public static final ConfigurableDouble SHOOTER_ACTIVE_VELOCITY = new ConfigurableDouble("Shooter Active Velocity", 0);
public static final ConfigurableDouble SHOOTER_RESTING_VELOCITY = new ConfigurableDouble("Shooter Resting Velocity", 0);
public static final ConfigurableDouble INDEXER_FORWARD_VELOCITY = new ConfigurableDouble("Indexer FWD Velocity", 10);
public static final ConfigurableDouble INDEXER_REVERSE_VELOCITY = new ConfigurableDouble("Indexer reverse Velocity", 10);