From 8f6640c1ce870428cdcdb1bfd8fb28ef15422f89 Mon Sep 17 00:00:00 2001 From: Kaya <95276965+kytpbs@users.noreply.github.com> Date: Wed, 19 Jun 2024 12:34:37 +0300 Subject: [PATCH] rename "SmartShootCommand" to "ShootToSpeakerCommand" This represents what it is about a lot better in my opinion. --- src/main/java/frc/robot/RobotContainer.java | 14 +++++++------- ...hootCommand.java => ShootToSpeakerCommand.java} | 12 ++++++------ 2 files changed, 13 insertions(+), 13 deletions(-) rename src/main/java/frc/robot/commands/{SmartShootCommand.java => ShootToSpeakerCommand.java} (80%) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 9feee06..103b296 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -23,8 +23,8 @@ import frc.robot.commands.BasicIntakeCommand; import frc.robot.commands.DefaultDriveCommand; import frc.robot.commands.ShootToAmpCommand; +import frc.robot.commands.ShootToSpeakerCommand; import frc.robot.commands.SmartIntakeCommand; -import frc.robot.commands.SmartShootCommand; import frc.robot.commands.led_commands.LEDIdleCommand; import frc.robot.simulationSystems.PhotonSim; import frc.robot.subsystems.ArmSubsystem; @@ -58,7 +58,7 @@ public RobotContainer() { autoChooser = AutoBuilder.buildAutoChooser(); autoChooser.addOption( "Shoot To Shooter", - new SmartShootCommand(shooterSubsystem, intakeSubsystem, armSubsystem, driveSubsystem)); + new ShootToSpeakerCommand(shooterSubsystem, intakeSubsystem, armSubsystem, driveSubsystem)); PhotonCameraSystem.getAprilTagWithID(0); // Load the class before enable. SmartDashboard.putData("Auto Chooser", autoChooser); if (RobotBase.isSimulation()) { @@ -108,7 +108,7 @@ private void setupNamedCommands() { NamedCommands.registerCommand("Intake", new BasicIntakeCommand(intakeSubsystem)); NamedCommands.registerCommand( "Shoot To Speaker", - new SmartShootCommand(shooterSubsystem, intakeSubsystem, armSubsystem, driveSubsystem)); + new ShootToSpeakerCommand(shooterSubsystem, intakeSubsystem, armSubsystem, driveSubsystem)); NamedCommands.registerCommand( "Shoot To Amp", new ShootToAmpCommand(shooterSubsystem, intakeSubsystem, armSubsystem)); } @@ -142,7 +142,7 @@ private void configureJoystickBindings() { new JoystickButton(controller, Button.kY.value) // Shoot, smart (Fully Shoot) .whileTrue( - new SmartShootCommand( + new ShootToSpeakerCommand( shooterSubsystem, intakeSubsystem, armSubsystem, @@ -171,7 +171,7 @@ private void configureJoystickBindings() { .whileTrue(new RunCommand(() -> shooterSubsystem.setShooterSpeed(-1), shooterSubsystem)); new JoystickButton(controller, Button.kLeftBumper.value) - .whileTrue(new SmartShootCommand(shooterSubsystem, intakeSubsystem)); + .whileTrue(new ShootToSpeakerCommand(shooterSubsystem, intakeSubsystem)); new Trigger(() -> controller.getPOV() == 0) // Move arm to 0.5, and set it there until the button is released. @@ -189,10 +189,10 @@ private void configureMidiBindings() { .onTrue(armSubsystem.runOnce(armSubsystem::resetEncoder).ignoringDisable(true)); new JoystickButton(midiController, 3) - .whileTrue(new SmartShootCommand(shooterSubsystem, intakeSubsystem)); + .whileTrue(new ShootToSpeakerCommand(shooterSubsystem, intakeSubsystem)); new JoystickButton(midiController, 4) - .whileTrue(new SmartShootCommand(shooterSubsystem, intakeSubsystem)); + .whileTrue(new ShootToSpeakerCommand(shooterSubsystem, intakeSubsystem)); new JoystickButton(midiController, 16) .onTrue( diff --git a/src/main/java/frc/robot/commands/SmartShootCommand.java b/src/main/java/frc/robot/commands/ShootToSpeakerCommand.java similarity index 80% rename from src/main/java/frc/robot/commands/SmartShootCommand.java rename to src/main/java/frc/robot/commands/ShootToSpeakerCommand.java index c0e1acc..a8ae0ee 100644 --- a/src/main/java/frc/robot/commands/SmartShootCommand.java +++ b/src/main/java/frc/robot/commands/ShootToSpeakerCommand.java @@ -8,10 +8,10 @@ import frc.robot.subsystems.ShooterSubsystem; import java.util.function.DoubleSupplier; -public class SmartShootCommand extends ParallelRaceGroup { +public class ShootToSpeakerCommand extends ParallelRaceGroup { private static final double waitTime = 2.5; - public SmartShootCommand(ShooterSubsystem shooterSubsystem, IntakeSubsystem intakeSubsystem) { + public ShootToSpeakerCommand(ShooterSubsystem shooterSubsystem, IntakeSubsystem intakeSubsystem) { super( new SequentialCommandGroup( new BasicRunShooterCommand(shooterSubsystem, waitTime), @@ -20,7 +20,7 @@ public SmartShootCommand(ShooterSubsystem shooterSubsystem, IntakeSubsystem inta new LoadToShooterCommand(intakeSubsystem)))); } - public SmartShootCommand( + public ShootToSpeakerCommand( ShooterSubsystem shooterSubsystem, IntakeSubsystem intakeSubsystem, ArmSubsystem armSubsystem, @@ -28,10 +28,10 @@ public SmartShootCommand( super( // Constantly move the arm until all the other commands finish. new MoveArmToShooterCommand(armSubsystem, driveSubsystem), - new SmartShootCommand(shooterSubsystem, intakeSubsystem)); + new ShootToSpeakerCommand(shooterSubsystem, intakeSubsystem)); } - public SmartShootCommand( + public ShootToSpeakerCommand( ShooterSubsystem shooterSubsystem, IntakeSubsystem intakeSubsystem, ArmSubsystem armSubsystem, @@ -43,6 +43,6 @@ public SmartShootCommand( new MoveArmToShooterCommand(armSubsystem, driveSubsystem), new DriveFacingShooter(driveSubsystem, xSpeed, ySpeed), // The finishing command will be this one: - new SmartShootCommand(shooterSubsystem, intakeSubsystem)); + new ShootToSpeakerCommand(shooterSubsystem, intakeSubsystem)); } }