@@ -314,18 +314,18 @@ private void configureBindings() {
314314 // .onFalse(new InstantCommand(()->joystick.setRumble(RumbleType.kBothRumble, 0))
315315 // .andThen(Commands.parallel(s_Shooter.stop(), new RunCommand(() -> stopDrive(), drivetrain))));
316316
317- // joystick.b().whileTrue(Commands.parallel(new ReefBranchAlign(drivetrain,
318- // new Transform2d(Units.inchesToMeters(-4.5), Units.inchesToMeters(0.5+2.25), new Rotation2d()),
319- // () -> -joystick.getLeftY()), s_Shooter.slowShoot())).onFalse(s_Shooter.stop());
317+ joystick .b ().whileTrue (Commands .parallel (new ReefBranchAlign (drivetrain ,
318+ new Transform2d (Units .inchesToMeters (-4.5 ), Units .inchesToMeters (0.5 +2.25 ), new Rotation2d ()),
319+ () -> -joystick .getLeftY ()), s_Shooter .slowShoot ())).onFalse (s_Shooter .stop ());
320320
321321
322- joystick .b ().whileTrue (Commands .sequence (
323- s_Shooter .setDefaultDoNotRun (),
324- Commands .parallel (
325- new ReefBranchAlign (drivetrain , new Transform2d (Units .inchesToMeters (-4.5 ), Units .inchesToMeters (0.5 +2.25 ), new Rotation2d ()),() -> -joystick .getLeftY ()),
326- s_Shooter .slowShoot ()
327- )
328- )).onFalse (s_Shooter .stop ());
322+ // joystick.b().whileTrue(Commands.sequence(
323+ // s_Shooter.setDefaultDoNotRun(),
324+ // Commands.parallel(
325+ // new ReefBranchAlign(drivetrain, new Transform2d(Units.inchesToMeters(-4.5), Units.inchesToMeters(0.5+2.25), new Rotation2d()),() -> -joystick.getLeftY()),
326+ // s_Shooter.slowShoot()
327+ // )
328+ // )).onFalse(s_Shooter.stop());
329329 // stop the robot override
330330 joystick .button (7 ).whileTrue (new RunCommand (()-> {System .out .println ("STOP" );stopDrive (); }, drivetrain ));
331331
0 commit comments