Skip to content

Commit

Permalink
Removed all code related to the intake sensor
Browse files Browse the repository at this point in the history
  • Loading branch information
rhetorr committed Sep 14, 2024
1 parent 1a59d99 commit 23b2066
Show file tree
Hide file tree
Showing 6 changed files with 13 additions and 46 deletions.
21 changes: 3 additions & 18 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -169,28 +169,13 @@ private void configureBindings() {
.x()
.onTrue(robotCommands.outtakeCommand())
.onFalse(robotCommands.stowCommand());
hardware
.operatorController
.a()
.onTrue(robotCommands.stowCommand());
hardware
.operatorController
.povUp()
.onTrue(robotCommands.climbUpCommand());
hardware
.operatorController
.povDown()
.onTrue(robotCommands.climbDownCommand());
hardware.operatorController.a().onTrue(robotCommands.stowCommand());
hardware.operatorController.povUp().onTrue(robotCommands.climbUpCommand());
hardware.operatorController.povDown().onTrue(robotCommands.climbDownCommand());
hardware
.operatorController
.povLeft()
.onTrue(robotCommands.unjamCommand())
.onFalse(robotCommands.stowCommand());






}
}
4 changes: 1 addition & 3 deletions src/main/java/frc/robot/config/CompConfig.java
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,6 @@ class CompConfig {
999,
CANIVORE_NAME,
999,
999,
new TalonFXConfiguration()
.withClosedLoopRamps(CLOSED_LOOP_RAMP)
.withOpenLoopRamps(OPEN_LOOP_RAMP)
Expand All @@ -77,8 +76,7 @@ class CompConfig {
centeringMotor -> {
centeringMotor.setSmartCurrentLimit(20);
centeringMotor.burnFlash();
},
new Debouncer(3.0 * 0.02)),
}),
new ArmConfig(
CANIVORE_NAME,
999,
Expand Down
4 changes: 1 addition & 3 deletions src/main/java/frc/robot/config/RobotConfig.java
Original file line number Diff line number Diff line change
Expand Up @@ -39,10 +39,8 @@ public record IntakeConfig(
int mainMotorID,
String mainMotorCanBusName,
int centeringMotorID,
int sensorID,
TalonFXConfiguration mainMotorConfig,
Consumer<CANSparkMax> centeringMotorConfig,
Debouncer debouncer) {}
Consumer<CANSparkMax> centeringMotorConfig) {}

public record ArmConfig(
String canBusName,
Expand Down
13 changes: 0 additions & 13 deletions src/main/java/frc/robot/intake/IntakeSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,6 @@
public class IntakeSubsystem extends StateMachine<IntakeState> {
private final TalonFX mainMotor;
private final CANSparkMax centeringMotor;
private boolean sensorHasNote = false;
private boolean debouncedSensorHasNote = false;
private final Debouncer debouncer = RobotConfig.get().intake().debouncer();

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

@Override
protected void collectInputs() {
debouncedSensorHasNote = debouncer.calculate(sensorHasNote);
}

@Override
protected IntakeState getNextState(IntakeState currentState) {
return currentState;
}

public boolean hasNote() {
return debouncedSensorHasNote;
}

@Override
protected void afterTransition(IntakeState newState) {
switch (newState) {
Expand All @@ -65,7 +54,5 @@ public void robotPeriodic() {
DogLog.log("Intake/StatorCurrent", mainMotor.getStatorCurrent().getValueAsDouble());
DogLog.log("Intake/SupplyCurrent", mainMotor.getSupplyCurrent().getValueAsDouble());
DogLog.log("Intake/AppliedVoltage", mainMotor.getMotorVoltage().getValueAsDouble());
DogLog.log("Intake/RawSensor", sensorHasNote);
DogLog.log("Intake/DebouncedSensor", hasNote());
}
}
9 changes: 6 additions & 3 deletions src/main/java/frc/robot/robot_manager/RobotCommands.java
Original file line number Diff line number Diff line change
Expand Up @@ -89,15 +89,18 @@ public Command subwooferCommand() {
return Commands.runOnce(robot::prepareSubwooferRequest, requirements)
.andThen(robot.waitForState(RobotState.IDLE_NO_GP));
}
public Command climbUpCommand(){

public Command climbUpCommand() {
return Commands.runOnce(robot::nextClimbStateRequest, requirements)
.andThen(robot.waitForState(RobotState.CLIMBING_2_HANGING));
}
public Command climbDownCommand(){

public Command climbDownCommand() {
return Commands.runOnce(robot::previousClimbStateRequest, requirements)
.andThen(robot.waitForState(RobotState.CLIMBING_1_LINEUP));
}
public Command unjamCommand(){

public Command unjamCommand() {
return Commands.runOnce(robot::unjamRequest, requirements)
.andThen(robot.waitForState(RobotState.IDLE_NO_GP));
}
Expand Down
8 changes: 2 additions & 6 deletions src/main/java/frc/robot/robot_manager/RobotManager.java
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ protected RobotState getNextState(RobotState currentState) {
shooter.atGoal() && arm.atGoal() ? RobotState.SUBWOOFER_SCORING : currentState;
case UNJAM -> currentState;
case INTAKING -> queuer.hasNote() ? RobotState.IDLE_WITH_GP : currentState;
case OUTTAKING -> queuer.hasNote() || intake.hasNote() ? currentState : RobotState.IDLE_NO_GP;
case OUTTAKING -> queuer.hasNote() ? currentState : RobotState.IDLE_NO_GP;
};
}

Expand Down Expand Up @@ -343,11 +343,7 @@ public void prepareFeedRequest() {
public void stopShootingRequest() {
// If we are actively taking a shot, ignore the request to avoid messing up shooting
switch (getState()) {
case SPEAKER_SCORING,
SUBWOOFER_SCORING,
AMP_SCORING,
FEEDING_SHOOTING,
PASS_SHOOTING -> {}
case SPEAKER_SCORING, SUBWOOFER_SCORING, AMP_SCORING, FEEDING_SHOOTING, PASS_SHOOTING -> {}
default -> setStateFromRequest(RobotState.IDLE_WITH_GP);
}
}
Expand Down

0 comments on commit 23b2066

Please sign in to comment.