From b4eedf4e0ca5c062bfd4f9036a7fb63b98ce2e5e Mon Sep 17 00:00:00 2001 From: Programming Date: Sat, 9 Mar 2024 10:57:03 -0800 Subject: [PATCH] Reduced Auton Time --- src/main/java/frc/robot/RobotContainer.java | 8 ++++---- .../java/frc/robot/commands/ShooterSetSpeedCommand.java | 8 ++++++-- 2 files changed, 10 insertions(+), 6 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index c6bd158..9ad7240 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -68,9 +68,9 @@ public class RobotContainer { public RobotContainer() { NamedCommands.registerCommand("Shoot", new SequentialCommandGroup( - new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Shooting), + new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Shooting, 1.5), new ParallelDeadlineGroup(new WaitCommand(1), new NoteOuttakeCommand(m_intakeSubsystem)), - new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Off))); + new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Off, 0.01))); NamedCommands.registerCommand("Intake", new SequentialCommandGroup( @@ -164,9 +164,9 @@ private void configureBindings() { // DriveConstants.kMaxAngularSpeedRadiansPerSecond - 1, 5))); new JoystickButton(m_driverController, Button.kX.value) - .onTrue(new SequentialCommandGroup(new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Shooting), + .onTrue(new SequentialCommandGroup(new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Shooting, 1.5), new NoteOuttakeCommand(m_intakeSubsystem))) - .onFalse(new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Off)); + .onFalse(new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Off, 0.3)); new JoystickButton(m_operatorController, Button.kA.value) .onTrue(new InstantCommand(() -> m_climberSubsystem.forward(), diff --git a/src/main/java/frc/robot/commands/ShooterSetSpeedCommand.java b/src/main/java/frc/robot/commands/ShooterSetSpeedCommand.java index 46d32c9..ecb4581 100644 --- a/src/main/java/frc/robot/commands/ShooterSetSpeedCommand.java +++ b/src/main/java/frc/robot/commands/ShooterSetSpeedCommand.java @@ -13,15 +13,19 @@ public class ShooterSetSpeedCommand extends Command { ShooterSubsystem m_ShooterSubsystem; double m_shooterSpeed = 0; + + double set_time = 1.5; Timer m_timer = new Timer(); ShootSpeed m_shootSpeed; /** Creates a new ShootCommand. */ - public ShooterSetSpeedCommand(ShooterSubsystem shooterSubsystem, ShootSpeed shootSpeed) { + public ShooterSetSpeedCommand(ShooterSubsystem shooterSubsystem, ShootSpeed shootSpeed, double time) { m_ShooterSubsystem = shooterSubsystem; addRequirements(m_ShooterSubsystem); + set_time = time; + m_shootSpeed = shootSpeed; } @@ -47,6 +51,6 @@ public void end(boolean interrupted) { // Returns true when the command should end. @Override public boolean isFinished() { - return m_timer.get() > 1.5; + return m_timer.get() > set_time; } }