Skip to content
This repository was archived by the owner on Jan 10, 2025. It is now read-only.

Commit d41545e

Browse files
committed
2 parents 426060e + e5b4de2 commit d41545e

File tree

8 files changed

+25
-60
lines changed

8 files changed

+25
-60
lines changed

src/main/java/frc/robot/Robot.java

Lines changed: 3 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -169,28 +169,13 @@ private void configureBindings() {
169169
.x()
170170
.onTrue(robotCommands.outtakeCommand())
171171
.onFalse(robotCommands.stowCommand());
172-
hardware
173-
.operatorController
174-
.a()
175-
.onTrue(robotCommands.stowCommand());
176-
hardware
177-
.operatorController
178-
.povUp()
179-
.onTrue(robotCommands.climbUpCommand());
180-
hardware
181-
.operatorController
182-
.povDown()
183-
.onTrue(robotCommands.climbDownCommand());
172+
hardware.operatorController.a().onTrue(robotCommands.stowCommand());
173+
hardware.operatorController.povUp().onTrue(robotCommands.climbUpCommand());
174+
hardware.operatorController.povDown().onTrue(robotCommands.climbDownCommand());
184175
hardware
185176
.operatorController
186177
.povLeft()
187178
.onTrue(robotCommands.unjamCommand())
188179
.onFalse(robotCommands.stowCommand());
189-
190-
191-
192-
193-
194-
195180
}
196181
}

src/main/java/frc/robot/config/CompConfig.java

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -66,7 +66,6 @@ class CompConfig {
6666
999,
6767
CANIVORE_NAME,
6868
999,
69-
999,
7069
new TalonFXConfiguration()
7170
.withClosedLoopRamps(CLOSED_LOOP_RAMP)
7271
.withOpenLoopRamps(OPEN_LOOP_RAMP)
@@ -77,8 +76,7 @@ class CompConfig {
7776
centeringMotor -> {
7877
centeringMotor.setSmartCurrentLimit(20);
7978
centeringMotor.burnFlash();
80-
},
81-
new Debouncer(3.0 * 0.02)),
79+
}),
8280
new ArmConfig(
8381
CANIVORE_NAME,
8482
999,

src/main/java/frc/robot/config/RobotConfig.java

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -39,10 +39,8 @@ public record IntakeConfig(
3939
int mainMotorID,
4040
String mainMotorCanBusName,
4141
int centeringMotorID,
42-
int sensorID,
4342
TalonFXConfiguration mainMotorConfig,
44-
Consumer<CANSparkMax> centeringMotorConfig,
45-
Debouncer debouncer) {}
43+
Consumer<CANSparkMax> centeringMotorConfig) {}
4644

4745
public record ArmConfig(
4846
String canBusName,

src/main/java/frc/robot/intake/IntakeSubsystem.java

Lines changed: 0 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -11,8 +11,6 @@
1111
public class IntakeSubsystem extends StateMachine<IntakeState> {
1212
private final TalonFX mainMotor;
1313
private final CANSparkMax centeringMotor;
14-
private boolean sensorHasNote = false;
15-
private boolean debouncedSensorHasNote = false;
1614
private final Debouncer debouncer = RobotConfig.get().intake().debouncer();
1715

1816
public IntakeSubsystem(TalonFX mainMotor, CANSparkMax centeringMotor) {
@@ -29,20 +27,11 @@ public void setState(IntakeState newState) {
2927
setStateFromRequest(newState);
3028
}
3129

32-
@Override
33-
protected void collectInputs() {
34-
debouncedSensorHasNote = debouncer.calculate(sensorHasNote);
35-
}
36-
3730
@Override
3831
protected IntakeState getNextState(IntakeState currentState) {
3932
return currentState;
4033
}
4134

42-
public boolean hasNote() {
43-
return debouncedSensorHasNote;
44-
}
45-
4635
@Override
4736
protected void afterTransition(IntakeState newState) {
4837
switch (newState) {
@@ -65,7 +54,5 @@ public void robotPeriodic() {
6554
DogLog.log("Intake/StatorCurrent", mainMotor.getStatorCurrent().getValueAsDouble());
6655
DogLog.log("Intake/SupplyCurrent", mainMotor.getSupplyCurrent().getValueAsDouble());
6756
DogLog.log("Intake/AppliedVoltage", mainMotor.getMotorVoltage().getValueAsDouble());
68-
DogLog.log("Intake/RawSensor", sensorHasNote);
69-
DogLog.log("Intake/DebouncedSensor", hasNote());
7057
}
7158
}

src/main/java/frc/robot/queuer/QueuerState.java

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,7 @@
11
package frc.robot.queuer;
22

33
public enum QueuerState {
4-
IDLE_WITH_GP,
5-
IDLE_NO_GP,
4+
IDLE,
65
SHOOTING,
76
INTAKING,
87
OUTTAKING;

src/main/java/frc/robot/queuer/QueuerSubsystem.java

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@ public class QueuerSubsystem extends StateMachine<QueuerState> {
1616
private final Debouncer debouncer = RobotConfig.get().queuer().debouncer();
1717

1818
public QueuerSubsystem(TalonFX motor, DigitalInput sensor) {
19-
super(SubsystemPriority.QUEUER, QueuerState.IDLE_NO_GP);
19+
super(SubsystemPriority.QUEUER, queuer.setState(QueuerState.IDLE));
2020

2121
this.sensor = sensor;
2222
this.motor = motor;
@@ -47,8 +47,7 @@ public boolean hasNote() {
4747
@Override
4848
protected void afterTransition(QueuerState newState) {
4949
switch (newState) {
50-
case IDLE_NO_GP -> motor.disable();
51-
case IDLE_WITH_GP -> motor.disable();
50+
case IDLE -> motor.disable();
5251
case SHOOTING -> motor.setVoltage(0); // probably like 12
5352
case INTAKING -> motor.setVoltage(0); // probably like 4
5453
case OUTTAKING -> motor.setVoltage(0); // proabably like -4

src/main/java/frc/robot/robot_manager/RobotCommands.java

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -89,15 +89,18 @@ public Command subwooferCommand() {
8989
return Commands.runOnce(robot::prepareSubwooferRequest, requirements)
9090
.andThen(robot.waitForState(RobotState.IDLE_NO_GP));
9191
}
92-
public Command climbUpCommand(){
92+
93+
public Command climbUpCommand() {
9394
return Commands.runOnce(robot::nextClimbStateRequest, requirements)
9495
.andThen(robot.waitForState(RobotState.CLIMBING_2_HANGING));
9596
}
96-
public Command climbDownCommand(){
97+
98+
public Command climbDownCommand() {
9799
return Commands.runOnce(robot::previousClimbStateRequest, requirements)
98100
.andThen(robot.waitForState(RobotState.CLIMBING_1_LINEUP));
99101
}
100-
public Command unjamCommand(){
102+
103+
public Command unjamCommand() {
101104
return Commands.runOnce(robot::unjamRequest, requirements)
102105
.andThen(robot.waitForState(RobotState.IDLE_NO_GP));
103106
}

src/main/java/frc/robot/robot_manager/RobotManager.java

Lines changed: 11 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -76,7 +76,7 @@ protected RobotState getNextState(RobotState currentState) {
7676
shooter.atGoal() && arm.atGoal() ? RobotState.SUBWOOFER_SCORING : currentState;
7777
case UNJAM -> currentState;
7878
case INTAKING -> queuer.hasNote() ? RobotState.IDLE_WITH_GP : currentState;
79-
case OUTTAKING -> queuer.hasNote() || intake.hasNote() ? currentState : RobotState.IDLE_NO_GP;
79+
case OUTTAKING -> queuer.hasNote() ? currentState : RobotState.IDLE_NO_GP;
8080
};
8181
}
8282

@@ -87,7 +87,7 @@ protected void afterTransition(RobotState newState) {
8787
arm.setState(ArmState.SUBWOOFER_SHOT);
8888
shooter.setState(ShooterState.SUBWOOFER_SHOT);
8989
intake.setState(IntakeState.IDLE);
90-
queuer.setState(QueuerState.IDLE_WITH_GP);
90+
queuer.setState(QueuerState.IDLE);
9191
}
9292
case SUBWOOFER_SCORING -> {
9393
arm.setState(ArmState.SUBWOOFER_SHOT);
@@ -99,7 +99,7 @@ protected void afterTransition(RobotState newState) {
9999
arm.setState(ArmState.SPEAKER_SHOT);
100100
shooter.setState(ShooterState.SPEAKER_SHOT);
101101
intake.setState(IntakeState.IDLE);
102-
queuer.setState(QueuerState.IDLE_WITH_GP);
102+
queuer.setState(QueuerState.IDLE);
103103
}
104104
case SPEAKER_SCORING -> {
105105
arm.setState(ArmState.SPEAKER_SHOT);
@@ -111,7 +111,7 @@ protected void afterTransition(RobotState newState) {
111111
arm.setState(ArmState.AMP);
112112
shooter.setState(ShooterState.AMP);
113113
intake.setState(IntakeState.IDLE);
114-
queuer.setState(QueuerState.IDLE_WITH_GP);
114+
queuer.setState(QueuerState.IDLE);
115115
}
116116
case AMP_SCORING -> {
117117
arm.setState(ArmState.AMP);
@@ -123,7 +123,7 @@ protected void afterTransition(RobotState newState) {
123123
arm.setState(ArmState.FEEDING);
124124
shooter.setState(ShooterState.FEEDING);
125125
intake.setState(IntakeState.IDLE);
126-
queuer.setState(QueuerState.IDLE_WITH_GP);
126+
queuer.setState(QueuerState.IDLE);
127127
}
128128
case FEEDING_SHOOTING -> {
129129
arm.setState(ArmState.FEEDING);
@@ -135,7 +135,7 @@ protected void afterTransition(RobotState newState) {
135135
arm.setState(ArmState.PASS);
136136
shooter.setState(ShooterState.PASS);
137137
intake.setState(IntakeState.IDLE);
138-
queuer.setState(QueuerState.IDLE_WITH_GP);
138+
queuer.setState(QueuerState.IDLE);
139139
}
140140
case PASS_SHOOTING -> {
141141
arm.setState(ArmState.PASS);
@@ -165,25 +165,25 @@ protected void afterTransition(RobotState newState) {
165165
arm.setState(ArmState.CLIMBING_1_LINEUP);
166166
shooter.setState(ShooterState.IDLE_STOPPED);
167167
intake.setState(IntakeState.IDLE);
168-
queuer.setState(QueuerState.IDLE_NO_GP);
168+
queuer.setState(queuer.setState(QueuerState.IDLE));
169169
}
170170
case CLIMBING_2_HANGING -> {
171171
arm.setState(ArmState.CLIMBING_2_HANGING);
172172
shooter.setState(ShooterState.IDLE_STOPPED);
173173
intake.setState(IntakeState.IDLE);
174-
queuer.setState(QueuerState.IDLE_NO_GP);
174+
queuer.setState(queuer.setState(QueuerState.IDLE));
175175
}
176176
case IDLE_NO_GP -> {
177177
arm.setState(ArmState.IDLE);
178178
shooter.setState(ShooterState.IDLE_STOPPED);
179179
intake.setState(IntakeState.IDLE);
180-
queuer.setState(QueuerState.IDLE_NO_GP);
180+
queuer.setState(queuer.setState(QueuerState.IDLE));
181181
}
182182
case IDLE_WITH_GP -> {
183183
arm.setState(ArmState.IDLE);
184184
shooter.setState(ShooterState.IDLE_WARMUP);
185185
intake.setState(IntakeState.IDLE);
186-
queuer.setState(QueuerState.IDLE_WITH_GP);
186+
queuer.setState(QueuerState.IDLE);
187187
}
188188
}
189189
}
@@ -343,11 +343,7 @@ public void prepareFeedRequest() {
343343
public void stopShootingRequest() {
344344
// If we are actively taking a shot, ignore the request to avoid messing up shooting
345345
switch (getState()) {
346-
case SPEAKER_SCORING,
347-
SUBWOOFER_SCORING,
348-
AMP_SCORING,
349-
FEEDING_SHOOTING,
350-
PASS_SHOOTING -> {}
346+
case SPEAKER_SCORING, SUBWOOFER_SCORING, AMP_SCORING, FEEDING_SHOOTING, PASS_SHOOTING -> {}
351347
default -> setStateFromRequest(RobotState.IDLE_WITH_GP);
352348
}
353349
}

0 commit comments

Comments
 (0)