From 0881a167e90a2836deecd48c044a4a3185ba57a3 Mon Sep 17 00:00:00 2001 From: Azalea H Date: Fri, 5 Apr 2024 15:54:32 -0700 Subject: [PATCH] Disable speaker vision --- src/main/java/frc/robot/commands/Autos.java | 22 ++++++++++----------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/src/main/java/frc/robot/commands/Autos.java b/src/main/java/frc/robot/commands/Autos.java index e815c6a..34596f1 100644 --- a/src/main/java/frc/robot/commands/Autos.java +++ b/src/main/java/frc/robot/commands/Autos.java @@ -174,15 +174,15 @@ public static Command shootInSpeaker(SwerveDrivetrain drivetrain, Arm arm, Intak new InstantCommand(() -> SmartDashboard.putBoolean("Got to Command", true)), Commands.sequence( new SpinFlywheelShooter(shooter, IntakeShooterConstants.FLYWHEEL_SHOOTER_SPEED_SPEAKER), Commands.parallel( - Commands.sequence( - new AlignAtTagWithX(drivetrain, vision, tagSupplier, - distanceFromTag + spacingFromPoint, - () -> new Rotation2d()), - Commands.race( - new AutoDriveTo(drivetrain, - new Translation2d(-spacingFromPoint, 0)), - new WaitCommand(4))) - .onlyIf(shouldUseVisionSupplier), + // Commands.sequence( + // new AlignAtTagWithX(drivetrain, vision, tagSupplier, + // distanceFromTag + spacingFromPoint, + // () -> new Rotation2d()), + // Commands.race( + // new AutoDriveTo(drivetrain, + // new Translation2d(-spacingFromPoint, 0)), + // new WaitCommand(4))) + // .onlyIf(shouldUseVisionSupplier), new WaitCommand(minSpinUpTimeSeconds), new ArmRotateTo(arm, ArmConstants.ARM_SPEAKER_SHOOTING_DEGREES @@ -202,7 +202,7 @@ public static Command shootInSpeaker(SwerveDrivetrain drivetrain, Arm arm, Intak public static Command intakeFromFloorStart(Arm arm, IntakeShooter shooter) { return Commands.sequence( - new SpinFlywheelShooter(shooter, 0.2), + new SpinFlywheelShooter(shooter, 0.1), new SpinIntakeGrabbers(shooter, IntakeShooterConstants.INTAKE_GRABBER_SPEED_SPEAKER), new ArmRotateTo(arm, Constants.ArmConstants.ARM_INTAKE_DEGREES)); } @@ -211,7 +211,7 @@ public static Command intakeFromFloorEnd(Arm arm, IntakeShooter shooter) { return Commands.sequence( new SpinFlywheelShooter(shooter, 0), new SpinIntakeGrabbers(shooter, -0.75), - new WaitCommand(0.005), + new WaitCommand(0.0025), new SpinIntakeGrabbers(shooter, 0), new ArmRotateTo(arm, ArmConstants.ARM_STOW_2_DEGREES)); }