diff --git a/src/main/java/org/jmhsrobotics/frc2024/autoCommands/FireCommand.java b/src/main/java/org/jmhsrobotics/frc2024/autoCommands/FireCommand.java index ebecfcd5..1590e1ea 100644 --- a/src/main/java/org/jmhsrobotics/frc2024/autoCommands/FireCommand.java +++ b/src/main/java/org/jmhsrobotics/frc2024/autoCommands/FireCommand.java @@ -3,7 +3,7 @@ import org.jmhsrobotics.frc2024.subsystems.intake.IntakeSubsystem; import org.jmhsrobotics.frc2024.subsystems.intake.commands.IntakeCommand; import org.jmhsrobotics.frc2024.subsystems.shooter.ShooterSubsystem; -import org.jmhsrobotics.frc2024.subsystems.shooter.commands.ShooterCommand; +import org.jmhsrobotics.frc2024.subsystems.shooter.commands.ShooterAutoCommand; import edu.wpi.first.wpilibj2.command.SequentialCommandGroup; @@ -14,7 +14,7 @@ public class FireCommand extends SequentialCommandGroup { public FireCommand(IntakeSubsystem intakeSubsystem, ShooterSubsystem shooterSubsystem) { this.intakeSubsystem = intakeSubsystem; this.shooterSubsystem = shooterSubsystem; - addCommands(new ShooterCommand(1, this.shooterSubsystem).withTimeout(5), + addCommands(new ShooterAutoCommand(this.shooterSubsystem, 1), new IntakeCommand(1, this.intakeSubsystem, this.shooterSubsystem)); } } diff --git a/src/main/java/org/jmhsrobotics/frc2024/subsystems/shooter/ShooterSubsystem.java b/src/main/java/org/jmhsrobotics/frc2024/subsystems/shooter/ShooterSubsystem.java index 79ff5321..be5c531f 100644 --- a/src/main/java/org/jmhsrobotics/frc2024/subsystems/shooter/ShooterSubsystem.java +++ b/src/main/java/org/jmhsrobotics/frc2024/subsystems/shooter/ShooterSubsystem.java @@ -42,7 +42,7 @@ public void periodic() { volt = SmartDashboard.getNumber("shooter/volt", 0); if (this.getRPM() < goal) { this.setVolt(volt); - }else{ + } else { this.atGoal = true; } } @@ -60,11 +60,11 @@ public void setVolt(double amount) { this.topFlywheel.setVoltage(amount); } - public void setGoal(double goal){ + public void setGoal(double goal) { this.goal = goal; } - public boolean atGoal(){ + public boolean atGoal() { return this.atGoal; } private void initializeMotors() { @@ -84,7 +84,6 @@ private void initializeMotors() { SmartDashboard.putNumber("shooter/volt", 5.5); } - FlywheelSim flywheelSim; RevEncoderSimWrapper encSim; public void initSim() { diff --git a/src/main/java/org/jmhsrobotics/frc2024/subsystems/shooter/commands/ShooterAutoCommand.java b/src/main/java/org/jmhsrobotics/frc2024/subsystems/shooter/commands/ShooterAutoCommand.java index 6fbc39b8..e819fcff 100644 --- a/src/main/java/org/jmhsrobotics/frc2024/subsystems/shooter/commands/ShooterAutoCommand.java +++ b/src/main/java/org/jmhsrobotics/frc2024/subsystems/shooter/commands/ShooterAutoCommand.java @@ -4,26 +4,26 @@ import edu.wpi.first.wpilibj2.command.Command; -public class ShooterAutoCommand extends Command{ - private ShooterSubsystem shooterSubsystem; - private double targetRPM; +public class ShooterAutoCommand extends Command { + private ShooterSubsystem shooterSubsystem; + private double targetRPM; - public ShooterAutoCommand(ShooterAutoCommand shooterAutoCommand, double targetRPM){ - this.shooterSubsystem = shooterSubsystem; - this.targetRPM = targetRPM; - } - @Override - public void execute() { - this.shooterSubsystem.setGoal(this.targetRPM); - } + public ShooterAutoCommand(ShooterSubsystem shooterSubsystem, double targetRPM) { + this.shooterSubsystem = shooterSubsystem; + this.targetRPM = targetRPM; + } + @Override + public void execute() { + this.shooterSubsystem.setGoal(this.targetRPM); + } - @Override - public boolean isFinished() { - return this.shooterSubsystem.atGoal(); - } + @Override + public boolean isFinished() { + return this.shooterSubsystem.atGoal(); + } - @Override - public void end(boolean interrupted) { - this.shooterSubsystem.setVolt(0); - } + @Override + public void end(boolean interrupted) { + this.shooterSubsystem.setVolt(0); + } }