Skip to content

Commit

Permalink
rename "SmartShootCommand" to "ShootToSpeakerCommand"
Browse files Browse the repository at this point in the history
This represents what it is about a lot better in my opinion.
  • Loading branch information
kytpbs committed Jun 19, 2024
1 parent 9afffac commit 8f6640c
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 13 deletions.
14 changes: 7 additions & 7 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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()) {
Expand Down Expand Up @@ -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));
}
Expand Down Expand Up @@ -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,
Expand Down Expand Up @@ -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.
Expand All @@ -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(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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),
Expand All @@ -20,18 +20,18 @@ public SmartShootCommand(ShooterSubsystem shooterSubsystem, IntakeSubsystem inta
new LoadToShooterCommand(intakeSubsystem))));
}

public SmartShootCommand(
public ShootToSpeakerCommand(
ShooterSubsystem shooterSubsystem,
IntakeSubsystem intakeSubsystem,
ArmSubsystem armSubsystem,
DriveSubsystem driveSubsystem) {
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,
Expand All @@ -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));
}
}

0 comments on commit 8f6640c

Please sign in to comment.