Skip to content
This repository was archived by the owner on May 19, 2024. It is now read-only.

Commit ac2f03b

Browse files
committed
refactor(superstructure): Automatically generate shoot commands.
1 parent b723a6f commit ac2f03b

File tree

3 files changed

+38
-85
lines changed

3 files changed

+38
-85
lines changed

src/main/java/frc/robot/shooter/ShooterState.java

Lines changed: 5 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -17,29 +17,19 @@ public record ShooterState(
1717

1818
public static final ShooterState EJECT = new ShooterState(0, SerializerConstants.EJECT_SPEED);
1919

20-
public static final ShooterState SPEAKER_READY =
21-
new ShooterState(FlywheelConstants.SPEAKER_SPEED, 0);
22-
23-
public static final ShooterState SPEAKER_SHOOT =
20+
public static final ShooterState SUBWOOFER =
2421
new ShooterState(FlywheelConstants.SPEAKER_SPEED, SerializerConstants.FAST_FEED_SPEED);
2522

26-
public static final ShooterState PODIUM_READY =
27-
new ShooterState(FlywheelConstants.PODIUM_SPEED, 0);
28-
29-
public static final ShooterState PODIUM_SHOOT =
23+
public static final ShooterState PODIUM =
3024
new ShooterState(FlywheelConstants.PODIUM_SPEED, SerializerConstants.FAST_FEED_SPEED);
3125

32-
public static final ShooterState LOB_READY = new ShooterState(FlywheelConstants.LOB_SPEED, 0);
33-
34-
public static final ShooterState LOB_SHOOT =
26+
public static final ShooterState LOB =
3527
new ShooterState(FlywheelConstants.LOB_SPEED, SerializerConstants.FAST_FEED_SPEED);
3628

37-
public static final ShooterState SKIM_READY = new ShooterState(FlywheelConstants.SKIM_SPEED, 0);
38-
39-
public static final ShooterState SKIM_SHOOT =
29+
public static final ShooterState SKIM =
4030
new ShooterState(FlywheelConstants.SKIM_SPEED, SerializerConstants.FAST_FEED_SPEED);
4131

42-
public static final ShooterState AMP_SHOOT =
32+
public static final ShooterState AMP =
4333
new ShooterState(FlywheelConstants.AMP_SPEED, SerializerConstants.SLOW_FEED_SPEED);
4434

4535
public ShooterState {

src/main/java/frc/robot/superstructure/Superstructure.java

Lines changed: 23 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,10 @@
99
import frc.lib.Telemetry;
1010
import frc.robot.arm.Arm;
1111
import frc.robot.intake.Intake;
12+
import frc.robot.intake.IntakeState;
1213
import frc.robot.shooter.Shooter;
14+
import frc.robot.shooter.ShooterState;
15+
1316
import java.util.function.Supplier;
1417

1518
/** Subsystem class for the superstructure subsystem. */
@@ -35,9 +38,9 @@ private Superstructure() {
3538
intake = Intake.getInstance();
3639
shooter = Shooter.getInstance();
3740

38-
setPosition(SuperstructureState.INITIAL);
41+
setPosition(SuperstructureState.STOW);
3942

40-
goal = SuperstructureState.INITIAL;
43+
goal = SuperstructureState.STOW;
4144
}
4245

4346
/**
@@ -148,44 +151,37 @@ public Command intake() {
148151
.withName("INTAKE");
149152
}
150153

154+
private Command shoot(SuperstructureState shot) {
155+
final SuperstructureState pull = new SuperstructureState(shot.armState(), IntakeState.IDLE, ShooterState.PULL);
156+
157+
final ShooterState spin = new ShooterState(shot.shooterState().flywheelVelocityRotationsPerSecond(), 0);
158+
159+
final SuperstructureState ready = new SuperstructureState(shot.armState(), IntakeState.IDLE, spin);
160+
161+
return hold(pull)
162+
.withTimeout(SuperstructureConstants.PULL_DURATION)
163+
.andThen(to(ready))
164+
.andThen(hold(shot));
165+
}
166+
151167
public Command subwoofer() {
152-
return hold(SuperstructureState.SUBWOOFER_PULL)
153-
.withTimeout(SuperstructureConstants.PULL_DURATION)
154-
.andThen(to(SuperstructureState.SUBWOOFER_READY))
155-
.andThen(hold(SuperstructureState.SUBWOOFER_SHOOT))
156-
.withName("SPEAKER");
168+
return shoot(SuperstructureState.SUBWOOFER).withName("SUBWOOFER");
157169
}
158170

159171
public Command podium() {
160-
return hold(SuperstructureState.PODIUM_PULL)
161-
.withTimeout(SuperstructureConstants.PULL_DURATION)
162-
.andThen(to(SuperstructureState.PODIUM_READY))
163-
.andThen(hold(SuperstructureState.PODIUM_SHOOT))
164-
.withName("PODIUM");
172+
return shoot(SuperstructureState.PODIUM).withName("PODIUM");
165173
}
166174

167175
public Command lob() {
168-
return hold(SuperstructureState.LOB_PULL)
169-
.withTimeout(SuperstructureConstants.PULL_DURATION)
170-
.andThen(to(SuperstructureState.LOB_READY))
171-
.andThen(hold(SuperstructureState.LOB_SHOOT))
172-
.withName("LOB");
176+
return shoot(SuperstructureState.LOB).withName("LOB");
173177
}
174178

175179
public Command skim() {
176-
return hold(SuperstructureState.SKIM_PULL)
177-
.withTimeout(SuperstructureConstants.PULL_DURATION)
178-
.andThen(to(SuperstructureState.SKIM_READY))
179-
.andThen(hold(SuperstructureState.SKIM_SHOOT))
180-
.withName("SKIM");
180+
return shoot(SuperstructureState.SKIM).withName("SKIM");
181181
}
182182

183183
public Command amp() {
184-
return hold(SuperstructureState.AMP_PULL)
185-
.withTimeout(SuperstructureConstants.PULL_DURATION)
186-
.andThen(to(SuperstructureState.AMP_POSITION))
187-
.andThen(hold(SuperstructureState.AMP_SHOOT))
188-
.withName("AMP");
184+
return shoot(SuperstructureState.AMP).withName("AMP");
189185
}
190186

191187
public Command eject() {

src/main/java/frc/robot/superstructure/SuperstructureState.java

Lines changed: 10 additions & 43 deletions
Original file line numberDiff line numberDiff line change
@@ -12,9 +12,6 @@
1212
public record SuperstructureState(
1313
ArmState armState, IntakeState intakeState, ShooterState shooterState) {
1414

15-
public static final SuperstructureState INITIAL =
16-
new SuperstructureState(ArmState.INITIAL, IntakeState.IDLE, ShooterState.IDLE);
17-
1815
public static final SuperstructureState STOW =
1916
new SuperstructureState(ArmState.STOW, IntakeState.IDLE, ShooterState.IDLE);
2017

@@ -27,50 +24,20 @@ public record SuperstructureState(
2724
public static final SuperstructureState EJECT =
2825
new SuperstructureState(ArmState.EJECT, IntakeState.EJECT, ShooterState.EJECT);
2926

30-
public static final SuperstructureState SUBWOOFER_PULL =
31-
new SuperstructureState(ArmState.SUBWOOFER, IntakeState.IDLE, ShooterState.PULL);
32-
33-
public static final SuperstructureState SUBWOOFER_READY =
34-
new SuperstructureState(ArmState.SUBWOOFER, IntakeState.IDLE, ShooterState.SPEAKER_READY);
35-
36-
public static final SuperstructureState SUBWOOFER_SHOOT =
37-
new SuperstructureState(ArmState.SUBWOOFER, IntakeState.IDLE, ShooterState.SPEAKER_SHOOT);
38-
39-
public static final SuperstructureState PODIUM_PULL =
40-
new SuperstructureState(ArmState.PODIUM, IntakeState.IDLE, ShooterState.PULL);
41-
42-
public static final SuperstructureState PODIUM_READY =
43-
new SuperstructureState(ArmState.PODIUM, IntakeState.IDLE, ShooterState.PODIUM_READY);
44-
45-
public static final SuperstructureState PODIUM_SHOOT =
46-
new SuperstructureState(ArmState.PODIUM, IntakeState.IDLE, ShooterState.PODIUM_SHOOT);
47-
48-
public static final SuperstructureState LOB_PULL =
49-
new SuperstructureState(ArmState.LOB, IntakeState.IDLE, ShooterState.PULL);
50-
51-
public static final SuperstructureState LOB_READY =
52-
new SuperstructureState(ArmState.LOB, IntakeState.IDLE, ShooterState.LOB_READY);
53-
54-
public static final SuperstructureState LOB_SHOOT =
55-
new SuperstructureState(ArmState.LOB, IntakeState.IDLE, ShooterState.LOB_SHOOT);
56-
57-
public static final SuperstructureState SKIM_PULL =
58-
new SuperstructureState(ArmState.SKIM, IntakeState.IDLE, ShooterState.PULL);
59-
60-
public static final SuperstructureState SKIM_READY =
61-
new SuperstructureState(ArmState.SKIM, IntakeState.IDLE, ShooterState.SKIM_READY);
27+
public static final SuperstructureState SUBWOOFER =
28+
new SuperstructureState(ArmState.SUBWOOFER, IntakeState.IDLE, ShooterState.SUBWOOFER);
6229

63-
public static final SuperstructureState SKIM_SHOOT =
64-
new SuperstructureState(ArmState.SKIM, IntakeState.IDLE, ShooterState.SKIM_SHOOT);
30+
public static final SuperstructureState PODIUM =
31+
new SuperstructureState(ArmState.PODIUM, IntakeState.IDLE, ShooterState.PODIUM);
6532

66-
public static final SuperstructureState AMP_PULL =
67-
new SuperstructureState(ArmState.AMP, IntakeState.IDLE, ShooterState.PULL);
33+
public static final SuperstructureState LOB =
34+
new SuperstructureState(ArmState.LOB, IntakeState.IDLE, ShooterState.LOB);
6835

69-
public static final SuperstructureState AMP_POSITION =
70-
new SuperstructureState(ArmState.AMP, IntakeState.IDLE, ShooterState.IDLE);
36+
public static final SuperstructureState SKIM =
37+
new SuperstructureState(ArmState.SKIM, IntakeState.IDLE, ShooterState.SKIM);
7138

72-
public static final SuperstructureState AMP_SHOOT =
73-
new SuperstructureState(ArmState.AMP, IntakeState.IDLE, ShooterState.AMP_SHOOT);
39+
public static final SuperstructureState AMP =
40+
new SuperstructureState(ArmState.AMP, IntakeState.IDLE, ShooterState.AMP);
7441

7542
/**
7643
* Creates a new superstructure state.

0 commit comments

Comments
 (0)