Skip to content

Commit

Permalink
two joysticks, disable vision
Browse files Browse the repository at this point in the history
  • Loading branch information
AvidCoder27 committed Sep 11, 2024
1 parent 984474f commit 7f93381
Showing 1 changed file with 8 additions and 7 deletions.
15 changes: 8 additions & 7 deletions src/main/java/frc/team5115/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@

import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.auto.NamedCommands;

import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.wpilibj2.command.Command;
Expand Down Expand Up @@ -58,6 +57,7 @@ public class RobotContainer {

// Controller
private final CommandXboxController joyDrive = new CommandXboxController(0);
private final CommandXboxController joyManip = new CommandXboxController(1);

// Dashboard inputs
private final LoggedDashboardChooser<Command> autoChooser;
Expand All @@ -80,7 +80,8 @@ public RobotContainer() {
new ModuleIOSparkMax(1),
new ModuleIOSparkMax(2),
new ModuleIOSparkMax(3));
vision = new PhotonVision(drivetrain);
// vision = new PhotonVision(drivetrain);
vision = null;
break;

case SIM:
Expand Down Expand Up @@ -159,28 +160,28 @@ private void configureButtonBindings() {
// joyDrive.x().onTrue(Commands.runOnce(drivetrain::stopWithX, drivetrain));
joyDrive.start().onTrue(resetFieldOrientation());

joyDrive
joyManip
.back()
.onTrue(DriveCommands.vomit(intake, feeder, shooter))
.onFalse(DriveCommands.forceStop(intake, feeder, shooter));

joyDrive.a().onTrue(DriveCommands.intakeUntilNote(arm, intake, feeder));
joyManip.a().onTrue(DriveCommands.intakeUntilNote(arm, intake, feeder));

joyDrive
joyManip
.y()
.onTrue(
Commands.parallel(arm.stow(), shooter.stop(), feeder.stop(), intake.stop())
.withInterruptBehavior(InterruptionBehavior.kCancelSelf));

joyDrive
joyManip
.b()
.onTrue(DriveCommands.prepareShoot(arm, intake, feeder, shooter, 15, 5000))
.onFalse(
DriveCommands.feed(intake, feeder)
.andThen(shooter.stop())
.withInterruptBehavior(InterruptionBehavior.kCancelIncoming));

joyDrive
joyManip
.x()
.onTrue(DriveCommands.prepareAmp(arm, amper, intake, feeder))
.onFalse(DriveCommands.triggerAmp(arm, amper, intake, feeder));
Expand Down

0 comments on commit 7f93381

Please sign in to comment.