From 289bc9ecadb64f9e22c86f6fa199f46d31ee9a4f Mon Sep 17 00:00:00 2001 From: Gael Date: Sat, 28 Sep 2024 13:52:20 -0500 Subject: [PATCH] more trigger stuff --- src/main/java/frc/robot/RobotContainer.java | 12 ++++-------- 1 file changed, 4 insertions(+), 8 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 1d573ba6..ae4b39aa 100755 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -257,8 +257,8 @@ private void configureButtonBindings() { .onTrue(elevatorWrist.homePosition()); // run action based on current state as incremented through operator states list operator.a().and(OperatorState.isSpeakerMode).whileTrue(elevatorWrist.speakerPreset()); - operator.a().and(OperatorState.isAmpMode).whileTrue(Commands - .either(elevatorWrist.ampPosition(), Commands.none(), this.intake.noteInIndexer)); + operator.a().and(OperatorState.isAmpMode).and(this.intake.noteInIndexer) + .whileTrue(elevatorWrist.ampPosition()); operator.a().and(OperatorState.isShootWhileMoveMode).and(s_Swerve.seeAprilTag) .whileTrue(new ShootWhileMoving(s_Swerve, driver, () -> s_Swerve.getPose(), () -> FieldConstants.allianceFlip(FieldConstants.Speaker.centerSpeakerOpening) @@ -271,12 +271,8 @@ private void configureButtonBindings() { .whileTrue(new TurnToAngle(s_Swerve, Rotation2d.fromDegrees(25)).alongWith(elevatorWrist .followPosition(() -> Constants.ElevatorWristConstants.SetPoints.HOME_HEIGHT, () -> Constants.ElevatorWristConstants.SetPoints.PODIUM_ANGLE))); - operator.a().and(OperatorState.isClimbMode) - .whileTrue(Commands - .sequence(elevatorWrist.ampPosition(), - Commands.runOnce(() -> OperatorState.enableManualMode())) - .alongWith(new TeleopSwerve(s_Swerve, driver, Constants.Swerve.isFieldRelative, - Constants.Swerve.isOpenLoop))); + operator.a().and(OperatorState.isClimbMode).whileTrue(Commands.sequence( + elevatorWrist.ampPosition(), Commands.runOnce(() -> OperatorState.enableManualMode()))); // Toggle manual mode operator.start().onTrue(Commands.runOnce(() -> {