Skip to content

Commit

Permalink
Disable speaker vision
Browse files Browse the repository at this point in the history
  • Loading branch information
MeowAzalea committed Apr 5, 2024
1 parent e313c6d commit 0881a16
Showing 1 changed file with 11 additions and 11 deletions.
22 changes: 11 additions & 11 deletions src/main/java/frc/robot/commands/Autos.java
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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));
}
Expand All @@ -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));
}
Expand Down

0 comments on commit 0881a16

Please sign in to comment.