Skip to content

Commit 0d86593

Browse files
committed
Merge branch 'Staging' of https://github.com/FRC-7525/7525-Rebuilt into Staging
2 parents 59b7f45 + 0269a35 commit 0d86593

File tree

3 files changed

+11
-2
lines changed

3 files changed

+11
-2
lines changed

src/main/java/frc/robot/Subsystems/Shooter/ShooterConstants.java

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@ public final class ShooterConstants {
2424
public static final Angle FIXED_SHOT_ANGLE = Degrees.of(20);
2525
public static final AngularVelocity FIXED_SHOT_SPEED = RotationsPerSecond.of(-26);
2626

27-
public static final Angle STANDBY_ANGLE = Degrees.of(45);
27+
public static final Angle STANDBY_ANGLE = Degrees.of(45);
2828
public static final AngularVelocity STANDBY_SPEED = RotationsPerSecond.of(-30);
2929

3030
// Numerical constants (moved from magic literals)
@@ -49,6 +49,8 @@ public final class ShooterConstants {
4949
public static final int RIGHT_SHOOTER_MOTOR_ID = 38;
5050
public static final int HOOD_MOTOR_ID = 39;
5151

52+
public static final int LIMIT_SWITCH_PORT = 9;
53+
5254
public static final Supplier<PIDController> HOOD_PID = () ->
5355
switch (GlobalConstants.ROBOT_MODE) {
5456
case REAL -> new PIDController(0.04, 0.0002, 0.0); //.0384 good alr

src/main/java/frc/robot/Subsystems/Shooter/ShooterIOReal.java

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,7 @@
1111
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
1212
import edu.wpi.first.units.measure.Angle;
1313
import edu.wpi.first.units.measure.AngularVelocity;
14+
import edu.wpi.first.wpilibj.DigitalInput;
1415
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
1516
import org.littletonrobotics.junction.Logger;
1617

@@ -24,6 +25,7 @@ public class ShooterIOReal implements ShooterIO {
2425
protected PIDController hoodPID;
2526
protected PIDController wheelPID;
2627
protected SimpleMotorFeedforward wheelFeedforward;
28+
protected DigitalInput limitSwitch = new DigitalInput(LIMIT_SWITCH_PORT);
2729

2830
public ShooterIOReal() {
2931
wheelSetpoint = RotationsPerSecond.zero();
@@ -70,6 +72,11 @@ public void setWheelVelocity(AngularVelocity velocity) {
7072
public void setHoodAngle(Angle angle) {
7173
hoodSetpoint = angle;
7274
hoodMotor.set(hoodPID.calculate(hoodMotor.getPosition().getValue().div(HOOD_GEARING).in(Degrees), -hoodSetpoint.in(Degrees)));
75+
76+
if (limitSwitch.get()) {
77+
hoodMotor.setPosition(0);
78+
hoodMotor.set(0);
79+
}
7380
}
7481

7582
@Override

src/main/java/frc/robot/Subsystems/Shooter/ShooterStates.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@
1313
import org.team7525.subsystem.SubsystemStates;
1414

1515
public enum ShooterStates implements SubsystemStates {
16-
IDLE("IDLE", () -> Degrees.of(0), () -> RotationsPerSecond.of(-65)),
16+
IDLE("IDLE", () -> Degrees.of(0), () -> RotationsPerSecond.of(0)),
1717
REVERSE("REVERSE", () -> Degrees.of(0), () -> REVERSE_WHEEL_SPEED), // TODO: get good value
1818
// Use placeholder Pose2d and zero velocity for now; replace with real robot pose/velocity when available.
1919
SHOOT_HUB(

0 commit comments

Comments
 (0)