Skip to content

Commit

Permalink
button binding
Browse files Browse the repository at this point in the history
  • Loading branch information
ryanknj5 committed Sep 14, 2024
1 parent 9df4054 commit 1a59d99
Show file tree
Hide file tree
Showing 3 changed files with 51 additions and 14 deletions.
45 changes: 37 additions & 8 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -131,37 +131,66 @@ public void testPeriodic() {}
public void testExit() {}

private void configureBindings() {
// TODO: Swerve button bindings

hardware
.driverController
.rightTrigger()
.onTrue(robotCommands.confirmShotCommand())
.onFalse(robotCommands.stowCommand());
.onFalse(robotCommands.stopShootingCommand());
hardware
.driverController
.leftTrigger()
.onTrue(robotCommands.intakeCommand())
.onFalse(robotCommands.stowCommand());
// TODO: Two of these bindings use right bumper
hardware
.driverController
.rightBumper()
.onTrue(robotCommands.feedingCommand())
.onFalse(robotCommands.stowCommand());
.onTrue(robotCommands.passCommand())
.onFalse(robotCommands.stopShootingCommand());
hardware
.driverController
.rightBumper()
.onTrue(robotCommands.passCommand())
.onFalse(robotCommands.stowCommand());
.leftBumper()
.onTrue(robotCommands.feedingCommand())
.onFalse(robotCommands.stopShootingCommand());

hardware
.operatorController
.rightTrigger()
.onTrue(robotCommands.ampCommand())
.onFalse(robotCommands.stowCommand());
.onFalse(robotCommands.stopShootingCommand());
hardware
.operatorController
.leftTrigger()
.onTrue(robotCommands.subwooferCommand())
.onFalse(robotCommands.stowCommand());
hardware
.operatorController
.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
.povLeft()
.onTrue(robotCommands.unjamCommand())
.onFalse(robotCommands.stowCommand());






}
}
12 changes: 12 additions & 0 deletions src/main/java/frc/robot/robot_manager/RobotCommands.java
Original file line number Diff line number Diff line change
Expand Up @@ -89,4 +89,16 @@ public Command subwooferCommand() {
return Commands.runOnce(robot::prepareSubwooferRequest, requirements)
.andThen(robot.waitForState(RobotState.IDLE_NO_GP));
}
public Command climbUpCommand(){
return Commands.runOnce(robot::nextClimbStateRequest, requirements)
.andThen(robot.waitForState(RobotState.CLIMBING_2_HANGING));
}
public Command climbDownCommand(){
return Commands.runOnce(robot::previousClimbStateRequest, requirements)
.andThen(robot.waitForState(RobotState.CLIMBING_1_LINEUP));
}
public Command unjamCommand(){
return Commands.runOnce(robot::unjamRequest, requirements)
.andThen(robot.waitForState(RobotState.IDLE_NO_GP));
}
}
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 @@ -341,17 +341,13 @@ 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,
SPEAKER_PREPARE_TO_SCORE,
SUBWOOFER_PREPARE_TO_SCORE,
AMP_PREPARE_TO_SCORE,
FEEDING_PREPARE_TO_SHOOT,
PASS_PREPARE_TO_SHOOT -> {}
PASS_SHOOTING -> {}
default -> setStateFromRequest(RobotState.IDLE_WITH_GP);
}
}
Expand Down

0 comments on commit 1a59d99

Please sign in to comment.