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

Commit 624f68d

Browse files
committed
refactor(superstructure): Simplify superstructure states.
1 parent 28b5981 commit 624f68d

File tree

7 files changed

+25
-79
lines changed

7 files changed

+25
-79
lines changed

Diff for: src/main/java/frc/robot/RobotContainer.java

+2-7
Original file line numberDiff line numberDiff line change
@@ -89,15 +89,10 @@ private void configureBindings() {
8989
operatorController.leftBumper().onTrue(superstructure.eject());
9090
operatorController.leftTrigger().onTrue(superstructure.intake());
9191

92-
operatorController.rightBumper().onTrue(superstructure.podium());
93-
operatorController.rightTrigger().onTrue(superstructure.subwoofer());
94-
95-
operatorController.povLeft().onTrue(superstructure.spool(SuperstructureState.SUBWOOFER_PRE));
96-
operatorController.povRight().onTrue(superstructure.spool(SuperstructureState.SUBWOOFER));
97-
operatorController.povUp().onTrue(superstructure.feed(SuperstructureState.SUBWOOFER));
92+
operatorController.rightBumper().onTrue(superstructure.shoot(SuperstructureState.SUBWOOFER));
93+
operatorController.rightTrigger().onTrue(superstructure.prepare(SuperstructureState.SUBWOOFER));
9894

9995
operatorController.a().onTrue(superstructure.amp());
100-
operatorController.b().onTrue(superstructure.bloop());
10196
operatorController.x().onTrue(superstructure.stow());
10297
operatorController.y().onTrue(superstructure.skim());
10398

Diff for: src/main/java/frc/robot/arm/Arm.java

+3-3
Original file line numberDiff line numberDiff line change
@@ -43,9 +43,9 @@ private Arm() {
4343

4444
previousTimeSeconds = Timer.getFPGATimestamp();
4545

46-
setPosition(ArmState.INITIAL);
47-
setpoint = ArmState.INITIAL;
48-
goal = ArmState.INITIAL;
46+
setPosition(ArmState.STOW);
47+
setpoint = ArmState.STOW;
48+
goal = ArmState.STOW;
4949
}
5050

5151
/**

Diff for: src/main/java/frc/robot/arm/ArmConstants.java

+6-13
Original file line numberDiff line numberDiff line change
@@ -62,20 +62,13 @@ public static class ShoulderConstants {
6262
/** Motion profile of the shoulder. */
6363
public static final TrapezoidProfile MOTION_PROFILE = new TrapezoidProfile(CONSTRAINTS);
6464

65-
public static final Rotation2d STOW = Rotation2d.fromDegrees(-26);
65+
/** Shoudler angle when stowed. */
66+
public static final Rotation2d STOW_ANGLE = Rotation2d.fromDegrees(-26);
6667

67-
public static final Rotation2d LOB = Rotation2d.fromDegrees(-26);
68+
/** Shoulder angle when shooter is parallel to the ground. */
69+
public static final Rotation2d FLAT_ANGLE = Rotation2d.fromDegrees(30);
6870

69-
public static final Rotation2d SUBWOOFER = Rotation2d.fromDegrees(-26);
70-
71-
public static final Rotation2d PODIUM = Rotation2d.fromDegrees(-10);
72-
73-
public static final Rotation2d EJECT = Rotation2d.fromDegrees(30);
74-
75-
public static final Rotation2d SKIM = Rotation2d.fromDegrees(30);
76-
77-
public static final Rotation2d AMP = Rotation2d.fromDegrees(60);
78-
79-
public static final Rotation2d BLOOP = Rotation2d.fromDegrees(-26);
71+
/** Shoulder angle when amping. */
72+
public static final Rotation2d AMP_ANGLE = Rotation2d.fromDegrees(60);
8073
}
8174
}

Diff for: src/main/java/frc/robot/arm/ArmState.java

+6-12
Original file line numberDiff line numberDiff line change
@@ -9,23 +9,17 @@
99

1010
public record ArmState(State shoulderRotations) {
1111

12-
public static final ArmState INITIAL = new ArmState(ShoulderConstants.STOW);
12+
public static final ArmState STOW = new ArmState(ShoulderConstants.STOW_ANGLE);
1313

14-
public static final ArmState STOW = new ArmState(ShoulderConstants.STOW);
14+
public static final ArmState SUBWOOFER = new ArmState(ShoulderConstants.STOW_ANGLE);
1515

16-
public static final ArmState SUBWOOFER = new ArmState(ShoulderConstants.SUBWOOFER);
16+
public static final ArmState EJECT = new ArmState(ShoulderConstants.FLAT_ANGLE);
1717

18-
public static final ArmState PODIUM = new ArmState(ShoulderConstants.PODIUM);
18+
public static final ArmState SKIM = new ArmState(ShoulderConstants.FLAT_ANGLE);
1919

20-
public static final ArmState EJECT = new ArmState(ShoulderConstants.EJECT);
20+
public static final ArmState LOB = new ArmState(ShoulderConstants.STOW_ANGLE);
2121

22-
public static final ArmState SKIM = new ArmState(ShoulderConstants.SKIM);
23-
24-
public static final ArmState LOB = new ArmState(ShoulderConstants.LOB);
25-
26-
public static final ArmState AMP = new ArmState(ShoulderConstants.AMP);
27-
28-
public static final ArmState BLOOP = new ArmState(ShoulderConstants.BLOOP);
22+
public static final ArmState AMP = new ArmState(ShoulderConstants.AMP_ANGLE);
2923

3024
public ArmState {
3125
Objects.requireNonNull(shoulderRotations);

Diff for: src/main/java/frc/robot/shooter/ShooterState.java

-12
Original file line numberDiff line numberDiff line change
@@ -17,27 +17,15 @@ public record ShooterState(
1717

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

20-
public static final ShooterState SUBWOOFER_PRE =
21-
new ShooterState(FlywheelConstants.SPEAKER_SPEED * 0.5, SerializerConstants.FAST_FEED_SPEED);
22-
2320
public static final ShooterState SUBWOOFER =
2421
new ShooterState(FlywheelConstants.SPEAKER_SPEED, SerializerConstants.FAST_FEED_SPEED);
2522

26-
public static final ShooterState PODIUM =
27-
new ShooterState(FlywheelConstants.PODIUM_SPEED, SerializerConstants.FAST_FEED_SPEED);
28-
29-
public static final ShooterState LOB =
30-
new ShooterState(FlywheelConstants.LOB_SPEED, SerializerConstants.FAST_FEED_SPEED);
31-
3223
public static final ShooterState SKIM =
3324
new ShooterState(FlywheelConstants.SKIM_SPEED, SerializerConstants.FAST_FEED_SPEED);
3425

3526
public static final ShooterState AMP =
3627
new ShooterState(FlywheelConstants.AMP_SPEED, SerializerConstants.SLOW_FEED_SPEED);
3728

38-
public static final ShooterState BLOOP =
39-
new ShooterState(FlywheelConstants.BLOOP_SPEED, SerializerConstants.FAST_FEED_SPEED);
40-
4129
public ShooterState {
4230
Objects.requireNonNull(flywheelVelocityRotationsPerSecond);
4331
Objects.requireNonNull(serializerVelocityRotationsPerSecond);

Diff for: src/main/java/frc/robot/superstructure/Superstructure.java

+8-20
Original file line numberDiff line numberDiff line change
@@ -162,45 +162,33 @@ private Command ready(SuperstructureState shot) {
162162
return to(ready).withTimeout(SuperstructureConstants.READY_DURATION);
163163
}
164164

165-
private Command shoot(SuperstructureState shot) {
165+
private Command autoShoot(SuperstructureState shot) {
166166
return pull(shot)
167167
.andThen(ready(shot))
168168
.andThen(Commands.waitSeconds(SuperstructureConstants.READY_PAUSE_DURATION))
169169
.andThen(hold(shot));
170170
}
171171

172-
private Command shootNoPull(SuperstructureState shot) {
172+
private Command autoShootNoPull(SuperstructureState shot) {
173173
return ready(shot)
174174
.andThen(Commands.waitSeconds(SuperstructureConstants.READY_PAUSE_DURATION))
175175
.andThen(hold(shot));
176176
}
177177

178178
public Command subwooferNoPull() {
179-
return shootNoPull(SuperstructureState.SUBWOOFER).withName("SUBWOOFER_NO_PULL");
179+
return autoShootNoPull(SuperstructureState.SUBWOOFER).withName("SUBWOOFER_NO_PULL");
180180
}
181181

182182
public Command subwoofer() {
183-
return shoot(SuperstructureState.SUBWOOFER).withName("SUBWOOFER");
184-
}
185-
186-
public Command podium() {
187-
return shoot(SuperstructureState.PODIUM).withName("PODIUM");
188-
}
189-
190-
public Command lob() {
191-
return shoot(SuperstructureState.LOB).withName("LOB");
183+
return autoShoot(SuperstructureState.SUBWOOFER).withName("SUBWOOFER");
192184
}
193185

194186
public Command skim() {
195-
return shoot(SuperstructureState.SKIM).withName("SKIM");
187+
return autoShoot(SuperstructureState.SKIM).withName("SKIM");
196188
}
197189

198190
public Command amp() {
199-
return shoot(SuperstructureState.AMP).withName("AMP");
200-
}
201-
202-
public Command bloop() {
203-
return shoot(SuperstructureState.BLOOP).withName("BLOOP");
191+
return autoShoot(SuperstructureState.AMP).withName("AMP");
204192
}
205193

206194
public Command eject() {
@@ -210,11 +198,11 @@ public Command eject() {
210198
.withName("EJECT");
211199
}
212200

213-
public Command spool(SuperstructureState shot) {
201+
public Command prepare(SuperstructureState shot) {
214202
return pull(shot).andThen(ready(shot));
215203
}
216204

217-
public Command feed(SuperstructureState shot) {
205+
public Command shoot(SuperstructureState shot) {
218206
return ready(shot)
219207
.andThen(Commands.waitSeconds(SuperstructureConstants.READY_PAUSE_DURATION))
220208
.andThen(hold(shot));

Diff for: src/main/java/frc/robot/superstructure/SuperstructureState.java

-12
Original file line numberDiff line numberDiff line change
@@ -21,27 +21,15 @@ public record SuperstructureState(
2121
public static final SuperstructureState EJECT =
2222
new SuperstructureState(ArmState.EJECT, IntakeState.EJECT, ShooterState.EJECT);
2323

24-
public static final SuperstructureState SUBWOOFER_PRE =
25-
new SuperstructureState(ArmState.SUBWOOFER, IntakeState.IDLE, ShooterState.SUBWOOFER_PRE);
26-
2724
public static final SuperstructureState SUBWOOFER =
2825
new SuperstructureState(ArmState.SUBWOOFER, IntakeState.IDLE, ShooterState.SUBWOOFER);
2926

30-
public static final SuperstructureState PODIUM =
31-
new SuperstructureState(ArmState.PODIUM, IntakeState.IDLE, ShooterState.PODIUM);
32-
33-
public static final SuperstructureState LOB =
34-
new SuperstructureState(ArmState.LOB, IntakeState.IDLE, ShooterState.LOB);
35-
3627
public static final SuperstructureState SKIM =
3728
new SuperstructureState(ArmState.SKIM, IntakeState.IDLE, ShooterState.SKIM);
3829

3930
public static final SuperstructureState AMP =
4031
new SuperstructureState(ArmState.AMP, IntakeState.IDLE, ShooterState.AMP);
4132

42-
public static final SuperstructureState BLOOP =
43-
new SuperstructureState(ArmState.BLOOP, IntakeState.IDLE, ShooterState.BLOOP);
44-
4533
/**
4634
* Creates a new superstructure state.
4735
*

0 commit comments

Comments
 (0)