Skip to content

Commit

Permalink
Simplify rumble command
Browse files Browse the repository at this point in the history
Fix endgame rumble 2
  • Loading branch information
suryatho committed Mar 9, 2024
1 parent 20785d9 commit 3de475a
Showing 1 changed file with 15 additions and 24 deletions.
39 changes: 15 additions & 24 deletions src/main/java/org/littletonrobotics/frc2024/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import edu.wpi.first.wpilibj2.command.button.RobotModeTriggers;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import java.util.function.Function;
import java.util.function.Supplier;
import lombok.experimental.ExtensionMethod;
import org.littletonrobotics.frc2024.FieldConstants.AprilTagLayoutType;
Expand Down Expand Up @@ -333,7 +332,7 @@ public RobotContainer() {
&& DriverStation.getMatchTime() > 0
&& DriverStation.getMatchTime() <= Math.round(endgameAlert1.get()))
.onTrue(
controllerRumbleCommand(true, true, true)
controllerRumbleCommand(true, true)
.withTimeout(0.5)
.beforeStarting(() -> Leds.getInstance().endgameAlert = true)
.finallyDo(() -> Leds.getInstance().endgameAlert = false));
Expand All @@ -343,14 +342,13 @@ public RobotContainer() {
&& DriverStation.getMatchTime() > 0
&& DriverStation.getMatchTime() <= Math.round(endgameAlert2.get()))
.onTrue(
controllerRumbleCommand(true, true, true)
controllerRumbleCommand(true, true)
.withTimeout(0.2)
.andThen(
Commands.waitSeconds(0.1)
.repeatedly()
.withTimeout(0.9) // Rumble three times
.beforeStarting(() -> Leds.getInstance().endgameAlert = true)
.finallyDo(() -> Leds.getInstance().endgameAlert = false)));
.andThen(Commands.waitSeconds(0.1))
.repeatedly()
.withTimeout(0.9) // Rumble three times
.beforeStarting(() -> Leds.getInstance().endgameAlert = true)
.finallyDo(() -> Leds.getInstance().endgameAlert = false));
}

private void configureAutos() {
Expand Down Expand Up @@ -477,7 +475,7 @@ private void configureButtonBindings() {
rollers.setGoalCommand(Rollers.Goal.FEED_TO_SHOOTER),
superstructureAimCommand.get(),
flywheels.shootCommand()));
driver.a().and(readyToShoot).whileTrue(controllerRumbleCommand(true, true, false));
driver.a().and(readyToShoot).whileTrue(controllerRumbleCommand(true, false));

// Poop.
driver
Expand Down Expand Up @@ -701,23 +699,16 @@ private void configureButtonBindings() {
}

/** Creates a controller rumble command with specified rumble and controllers */
private Command controllerRumbleCommand(
boolean useRight, boolean rumbleDriver, boolean rumbleOperator) {
private Command controllerRumbleCommand(boolean useRightRumble, boolean rumbleOperator) {
return Commands.startEnd(
() -> {
if (rumbleDriver) {
if (useRight) {
driver.getHID().setRumble(RumbleType.kBothRumble, 1.0);
} else {
driver.getHID().setRumble(RumbleType.kLeftRumble, 1.0);
}
}
driver
.getHID()
.setRumble(useRightRumble ? RumbleType.kBothRumble : RumbleType.kLeftRumble, 1.0);
if (rumbleOperator) {
if (useRight) {
operator.getHID().setRumble(RumbleType.kBothRumble, 1.0);
} else {
operator.getHID().setRumble(RumbleType.kLeftRumble, 1.0);
}
operator
.getHID()
.setRumble(useRightRumble ? RumbleType.kBothRumble : RumbleType.kLeftRumble, 1.0);
}
},
() -> {
Expand Down

0 comments on commit 3de475a

Please sign in to comment.