Skip to content

Commit

Permalink
Split rightBumper to 4 separate triggers
Browse files Browse the repository at this point in the history
  • Loading branch information
BrownGenius committed Apr 2, 2024
1 parent d46ee4a commit a12bd05
Showing 1 changed file with 35 additions and 29 deletions.
64 changes: 35 additions & 29 deletions src/main/java/frc/robot/controls/DriverControls.java
Original file line number Diff line number Diff line change
Expand Up @@ -293,38 +293,44 @@ public static void setupMainControls(CommandXboxController mainController) {
.onTrue(
new EjectPiece(RobotConfig.intake, RobotConfig.arm, RobotConfig.shooter)); // Eject Note

mainController.rightBumper().onTrue(RobotConfig.intake.getTurnOffCommand());

mainController
.rightBumper()
.onTrue(
new ParallelCommandGroup(
RobotConfig.intake.getTurnOffCommand(),
new SelectCommand<>(
Map.ofEntries(
Map.entry(
true,
AutoBuilder.pathfindToPoseFlipped(
new Pose2d(1.8, 7.75, Rotation2d.fromDegrees(-90)),
new PathConstraints(4.0, 3.0, 2 * Math.PI, 3 * Math.PI))),
Map.entry(
false,
new DriveToYaw(
RobotConfig.drive,
() -> DevilBotState.getVisionRobotYawToTarget())
.withTimeout(DriveConstants.pidTimeoutInSeconds))),
() -> DevilBotState.isAmpMode()),
new SetShooterVelocity(
RobotConfig.shooter, () -> DevilBotState.getShooterVelocity())
.withTimeout(ShooterConstants.pidTimeoutInSeconds), // turn on shooter
/* TODO: Use ArmToPositionTP instead of setting arm angle directly */
new InstantCommand(
() -> {
Optional<Double> armAngle = DevilBotState.getArmAngleToTarget();
if (armAngle.isPresent()) {
RobotConfig.arm.setAngle((armAngle.get()));
}
},
RobotConfig.arm)
.onlyIf(() -> !DevilBotState.isAmpMode()))); // Aim
new SelectCommand<>(
Map.ofEntries(
Map.entry(
true,
AutoBuilder.pathfindToPoseFlipped(
new Pose2d(1.8, 7.75, Rotation2d.fromDegrees(-90)),
new PathConstraints(4.0, 3.0, 2 * Math.PI, 3 * Math.PI))),
Map.entry(
false,
new DriveToYaw(
RobotConfig.drive, () -> DevilBotState.getVisionRobotYawToTarget())
.withTimeout(DriveConstants.pidTimeoutInSeconds))),
() -> DevilBotState.isAmpMode()));

mainController
.rightBumper()
.onTrue(
new SetShooterVelocity(RobotConfig.shooter, () -> DevilBotState.getShooterVelocity())
.withTimeout(ShooterConstants.pidTimeoutInSeconds) // turn on shooter
);

mainController
.rightBumper()
.onTrue(
new InstantCommand(
() -> {
Optional<Double> armAngle = DevilBotState.getArmAngleToTarget();
if (armAngle.isPresent()) {
RobotConfig.arm.setAngle((armAngle.get()));
}
},
RobotConfig.arm)
.onlyIf(() -> !DevilBotState.isAmpMode()));

mainController
.rightTrigger()
Expand Down

0 comments on commit a12bd05

Please sign in to comment.