Skip to content

Commit

Permalink
deferring command construction harder than my college decisions
Browse files Browse the repository at this point in the history
  • Loading branch information
MysticalApple committed Apr 8, 2024
1 parent 82dfd60 commit 4938501
Showing 1 changed file with 14 additions and 14 deletions.
28 changes: 14 additions & 14 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,6 @@
import static frc.robot.Constants.VisionConstants.BACK_RIGHT_CAMERA;
import static frc.robot.Constants.VisionConstants.NOTE_CAMERA;

import java.util.function.BooleanSupplier;

import com.choreo.lib.ChoreoTrajectory;
import edu.wpi.first.cscore.MjpegServer;
import edu.wpi.first.cscore.UsbCamera;
Expand Down Expand Up @@ -273,14 +271,14 @@ private void configureBindings() {
/* Automatic Amping -- Pressing and holding the button will cause the robot to automatically path find to the
* amp and deposit its note. Releasing the button will stop the robot (and the path finding). */
// TODO: Bring back LED integration.
driveController.getAutoAmp().onTrue(
new AutoAmpSequence(fmsSubsystem,
swerveSubsystem,
elevatorSubsystem,
intakePivotSubsystem,
intakeRollerSubsystem)

.onlyWhile(driveController.getAutoAmp())
driveController.getAutoAmp().whileTrue(
Commands.deferredProxy(() -> new AutoAmpSequence(
fmsSubsystem,
swerveSubsystem,
elevatorSubsystem,
intakePivotSubsystem,
intakeRollerSubsystem
))
);

// DEPRECATED AMP ALIGN
Expand All @@ -297,10 +295,12 @@ private void configureBindings() {

/* Stage Align -- Pressing and holding the button will cause the robot to automatically pathfind such that its
* climb hooks will end up directly above the center of the nearest chain. */
driveController.getStageAlignButton().onTrue(
AlignCommand.getStageAlignCommand(swerveSubsystem,
swerveSubsystem::getRobotPosition, fmsSubsystem::isRedAlliance)
.onlyWhile(driveController.getStageAlignButton())
driveController.getStageAlignButton().whileTrue(
Commands.deferredProxy(() -> AlignCommand.getStageAlignCommand(
swerveSubsystem,
swerveSubsystem::getRobotPosition,
fmsSubsystem::isRedAlliance
))
);

/* Note align -- deprecated, new version in the works*/
Expand Down

0 comments on commit 4938501

Please sign in to comment.