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

Commit 99fc777

Browse files
committed
2 parents c929a0a + a200e00 commit 99fc777

File tree

6 files changed

+80
-9
lines changed

6 files changed

+80
-9
lines changed
Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
package frc.robot.intake;
2+
3+
public enum IntakeState {
4+
IDLE,
5+
INTAKING,
6+
OUTTAKING;
7+
}
Lines changed: 58 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,58 @@
1+
package frc.robot.intake;
2+
3+
import com.ctre.phoenix6.hardware.TalonFX;
4+
5+
import dev.doglog.DogLog;
6+
import edu.wpi.first.math.filter.Debouncer;
7+
import edu.wpi.first.wpilibj.DigitalInput;
8+
import frc.robot.util.scheduling.SubsystemPriority;
9+
import frc.robot.util.state_machines.StateMachine;
10+
11+
public class IntakeSubsystem extends StateMachine<IntakeState> {
12+
private final TalonFX motor;
13+
private final DigitalInput sensor;
14+
private boolean sensorHasNote = false;
15+
private boolean debouncedSensorHasNote = false;
16+
private final Debouncer debouncer = new Debouncer(3.0*0.02);
17+
18+
public IntakeSubsystem (TalonFX motor,DigitalInput sensor){
19+
super(SubsystemPriority.INTAKE, IntakeState.IDLE);
20+
21+
this.sensor = sensor;
22+
this.motor = motor;
23+
}
24+
public void setState (IntakeState newState){
25+
setStateFromRequest(newState);
26+
}
27+
28+
@Override
29+
protected void collectInputs(){
30+
sensorHasNote=sensor.get();
31+
debouncedSensorHasNote=debouncer.calculate(sensorHasNote);
32+
}
33+
@Override
34+
protected IntakeState getNextState(IntakeState currentState){
35+
return currentState;
36+
}
37+
public boolean hasNote(){
38+
return debouncedSensorHasNote;
39+
}
40+
@Override
41+
protected void afterTransition(IntakeState newState){
42+
switch (newState){
43+
case IDLE->motor.disable();
44+
case INTAKING->motor.setVoltage(0);//around 10
45+
case OUTTAKING->motor.setVoltage(0);//around -6
46+
}
47+
}
48+
@Override
49+
public void robotPeriodic(){
50+
super.robotPeriodic();
51+
DogLog.log("Intake/StatorCurrent", motor.getStatorCurrent().getValueAsDouble());
52+
DogLog.log("Intake/SupplyCurrent", motor.getSupplyCurrent().getValueAsDouble());
53+
DogLog.log("Intake/AppliedVoltage", motor.getMotorVoltage().getValueAsDouble());
54+
DogLog.log("Intake/RawSensor",sensorHasNote);
55+
DogLog.log("Intake/DebouncedSensor",hasNote());
56+
57+
}
58+
}

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

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@ public class QueuerSubsystem extends StateMachine<QueuerState> {
1414
private final DigitalInput sensor;
1515
private boolean sensorHasNote = false;
1616
private boolean debouncedSensorHasNote = false;
17-
private final Debouncer debouncer= new Debouncer(3 * 0.02);
17+
private final Debouncer debouncer= new Debouncer(3.0 * 0.02);
1818

1919
public QueuerSubsystem(TalonFX motor, DigitalInput sensor) {
2020
super(SubsystemPriority.QUEUER, QueuerState.IDLE_NO_GP);
@@ -54,8 +54,12 @@ protected void afterTransition(QueuerState newState){
5454
}
5555
@Override
5656
public void robotPeriodic(){
57+
super.robotPeriodic();
58+
5759
DogLog.log("Queuer/StatorCurrent", motor.getStatorCurrent().getValueAsDouble());
5860
DogLog.log("Queuer/SupplyCurrent", motor.getSupplyCurrent().getValueAsDouble());
5961
DogLog.log("Queuer/AppliedVoltage", motor.getMotorVoltage().getValueAsDouble());
62+
DogLog.log("Queuer/RawSensor",sensorHasNote);
63+
DogLog.log("Queuer/DebouncedSensor",hasNote());
6064
}
6165
}

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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,5 +4,5 @@ public class ShooterRpms {
44
public static final double SUBWOOFER = 3000.0;
55
public static final double DROP = 500.0;
66
public static final double PODIUM = 4000.0;
7-
public static final double IDLE_WITH_GP = 1000.0;
7+
public static final double IDLE_WARMUP = 1000.0;
88
}

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

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

33
public enum ShooterState {
4-
IDLE_WITH_GP,
5-
IDLE_NO_GP,
4+
IDLE_WARMUP,
5+
IDLE_STOPPED,
66
SPEAKER_SHOT,
77
DROP,
88
SUBWOOFER_SHOT,

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

Lines changed: 7 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,7 @@ public void setDistanceToFeedSpot(double distance) {
2828
}
2929

3030
public ShooterSubsystem(TalonFX motor) {
31-
super(SubsystemPriority.SHOOTER, ShooterState.IDLE_NO_GP);
31+
super(SubsystemPriority.SHOOTER, ShooterState.IDLE_STOPPED);
3232
this.motor = motor;
3333

3434
// TODO: Tune lookup table
@@ -40,7 +40,7 @@ public ShooterSubsystem(TalonFX motor) {
4040
public boolean atGoal() {
4141
return switch (getState()) {
4242
case SUBWOOFER_SHOT -> MathUtil.isNear(ShooterRpms.SUBWOOFER, shooterRPM, 50);
43-
case IDLE_WITH_GP, IDLE_NO_GP->true;
43+
case IDLE_WARMUP, IDLE_STOPPED->true;
4444
case PODIUM_SHOT-> MathUtil.isNear(ShooterRpms.PODIUM,shooterRPM,50);
4545
case DROP->MathUtil.isNear(ShooterRpms.DROP,shooterRPM,50);
4646
case FEEDING->MathUtil.isNear(feedSpotDistanceToRpm.get(distanceToFeedSpot),shooterRPM,50);
@@ -66,8 +66,8 @@ protected ShooterState getNextState(ShooterState currentState) {
6666
@Override
6767
protected void afterTransition(ShooterState newState) {
6868
switch (newState) {
69-
case IDLE_NO_GP -> motor.disable();
70-
case IDLE_WITH_GP -> motor.setControl(velocityRequest.withVelocity(ShooterRpms.IDLE_WITH_GP / 60.0));
69+
case IDLE_STOPPED -> motor.disable();
70+
case IDLE_WARMUP -> motor.setControl(velocityRequest.withVelocity(ShooterRpms.IDLE_WARMUP / 60.0));
7171
case SPEAKER_SHOT ->
7272
motor.setControl(
7373
velocityRequest.withVelocity(speakerDistanceToRpm.get(distanceToSpeaker) / 60.0));
@@ -82,7 +82,9 @@ protected void afterTransition(ShooterState newState) {
8282

8383
@Override
8484
public void robotPeriodic() {
85-
// Log stator current, supply current, current velocity in RPM, applied voltage
85+
86+
super.robotPeriodic();
87+
8688
DogLog.log("Shooter/StatorCurrent",motor.getStatorCurrent().getValueAsDouble());
8789
DogLog.log("Shooter/SupplyCurrent", motor.getSupplyCurrent().getValueAsDouble());
8890
DogLog.log("Shooter/RPM",motor.getVelocity().getValueAsDouble()*60.0);

0 commit comments

Comments
 (0)