From 5ae85343da8de272ac26a0914e8c51d943533971 Mon Sep 17 00:00:00 2001 From: Ethan Porter Date: Thu, 18 Jan 2024 12:42:00 -0500 Subject: [PATCH] Run SpotlessApply --- src/main/java/frc/robot/RobotContainer.java | 1 - .../robot/commands/ShooterBaseCommand.java | 101 +++++++++--------- .../frc/robot/subsystems/shooter/Shooter.java | 8 +- .../robot/subsystems/shooter/ShooterBase.java | 82 +++++++------- .../robot/subsystems/shooter/ShooterIO.java | 2 +- .../subsystems/shooter/ShooterIOSim.java | 5 +- 6 files changed, 95 insertions(+), 104 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 1a512b9a..95483310 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -4,7 +4,6 @@ package frc.robot; - import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.InstantCommand; diff --git a/src/main/java/frc/robot/commands/ShooterBaseCommand.java b/src/main/java/frc/robot/commands/ShooterBaseCommand.java index 277c0e5d..00d4b894 100644 --- a/src/main/java/frc/robot/commands/ShooterBaseCommand.java +++ b/src/main/java/frc/robot/commands/ShooterBaseCommand.java @@ -1,64 +1,63 @@ package frc.robot.commands; - - -import java.util.Map; -import java.util.function.BooleanSupplier; - import edu.wpi.first.networktables.GenericEntry; import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets; import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab; - import edu.wpi.first.wpilibj2.command.Command; import frc.robot.subsystems.shooter.ShooterBase; +import java.util.Map; +import java.util.function.BooleanSupplier; public class ShooterBaseCommand extends Command { - ShooterBase shooter; - BooleanSupplier enable; - ShuffleboardTab tab; - GenericEntry voltsEntry; - - public ShooterBaseCommand(ShooterBase shooter, BooleanSupplier enable) { - this.shooter = shooter; - this.enable = enable; - - //create shooter tab on ShuffleBoard - tab = Shuffleboard.getTab("Shooter"); - // Create volt entry under Shooter tab as a number sider with min = -1 and max = 1 - voltsEntry = tab.add("Volts", 0).withWidget(BuiltInWidgets.kNumberSlider) - .withProperties(Map.of("min", -12, "max", 12)).getEntry(); - - // Sets default value to 0.0 - voltsEntry.setValue(0.0); - - addRequirements(shooter); + ShooterBase shooter; + BooleanSupplier enable; + ShuffleboardTab tab; + GenericEntry voltsEntry; + + public ShooterBaseCommand(ShooterBase shooter, BooleanSupplier enable) { + this.shooter = shooter; + this.enable = enable; + + // create shooter tab on ShuffleBoard + tab = Shuffleboard.getTab("Shooter"); + // Create volt entry under Shooter tab as a number sider with min = -1 and max = 1 + voltsEntry = + tab.add("Volts", 0) + .withWidget(BuiltInWidgets.kNumberSlider) + .withProperties(Map.of("min", -12, "max", 12)) + .getEntry(); + + // Sets default value to 0.0 + voltsEntry.setValue(0.0); + + addRequirements(shooter); + } + + @Override + public void initialize() { + // disable shooter when initialize + shooter.disable(); + } + + @Override + public void execute() { + // Turns on motors if right trigger is fully pressed. else the motors turn off. + if (enable.getAsBoolean() == true) { + // Checks the volt Entry for the volt and sets the voltage of motors + shooter.setVoltage(voltsEntry.getDouble(0.0)); + + // Enable motors, It has to be called regularly for voltage compensation to work properly + shooter.enable(); + } else { + // Disable the shooters + shooter.disable(); } - @Override - public void initialize() { - // disable shooter when initialize - shooter.disable(); - } - + } - @Override - public void execute() { - // Turns on motors if right trigger is fully pressed. else the motors turn off. - if (enable.getAsBoolean() == true) { - // Checks the volt Entry for the volt and sets the voltage of motors - shooter.setVoltage(voltsEntry.getDouble(0.0)); - - // Enable motors, It has to be called regularly for voltage compensation to work properly - shooter.enable(); - } else { - // Disable the shooters - shooter.disable(); - } - } - - @Override - //disable shooter when it ends. - public void end(boolean interrupted) { - shooter.disable(); - } + @Override + // disable shooter when it ends. + public void end(boolean interrupted) { + shooter.disable(); + } } diff --git a/src/main/java/frc/robot/subsystems/shooter/Shooter.java b/src/main/java/frc/robot/subsystems/shooter/Shooter.java index b59af5f5..25480d3e 100644 --- a/src/main/java/frc/robot/subsystems/shooter/Shooter.java +++ b/src/main/java/frc/robot/subsystems/shooter/Shooter.java @@ -1,14 +1,10 @@ package frc.robot.subsystems.shooter; public interface Shooter { - /** - * Disable the speed of a motors for the shooter. - */ + /** Disable the speed of a motors for the shooter. */ public default void disable() {} - /** - * Enable the speed of a motors for the shooter. - */ + /** Enable the speed of a motors for the shooter. */ public default void enable() {} /** diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterBase.java b/src/main/java/frc/robot/subsystems/shooter/ShooterBase.java index 4714b4d4..a742256f 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterBase.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterBase.java @@ -1,48 +1,46 @@ package frc.robot.subsystems.shooter; - -import org.littletonrobotics.junction.Logger; - import edu.wpi.first.wpilibj2.command.SubsystemBase; +import org.littletonrobotics.junction.Logger; public class ShooterBase extends SubsystemBase implements Shooter { - ShooterIO io; - private final ShooterIOInputsAutoLogged inputs = new ShooterIOInputsAutoLogged(); - private double voltage; - - public ShooterBase(ShooterIO io) { - this.io = io; - voltage = 0; - } - - @Override - //Disable the shooter - public void disable() { - voltage = 0; - io.setVoltage(voltage); - } - - @Override - //Enable the shooter - public void enable() { - io.setVoltage(voltage); - } - - @Override - //Sets the voltage to volts. the volts value is -12 to 12 - public void setVoltage(double volts) { - voltage = volts; - } - - @Override - public double getCurrentSpeed() { - return inputs.velocityRadPerSec; - } - - @Override - public void periodic() { - //Updates the inputs - io.updateInputs(inputs); - Logger.processInputs("Shooter", inputs); - } + ShooterIO io; + private final ShooterIOInputsAutoLogged inputs = new ShooterIOInputsAutoLogged(); + private double voltage; + + public ShooterBase(ShooterIO io) { + this.io = io; + voltage = 0; + } + + @Override + // Disable the shooter + public void disable() { + voltage = 0; + io.setVoltage(voltage); + } + + @Override + // Enable the shooter + public void enable() { + io.setVoltage(voltage); + } + + @Override + // Sets the voltage to volts. the volts value is -12 to 12 + public void setVoltage(double volts) { + voltage = volts; + } + + @Override + public double getCurrentSpeed() { + return inputs.velocityRadPerSec; + } + + @Override + public void periodic() { + // Updates the inputs + io.updateInputs(inputs); + Logger.processInputs("Shooter", inputs); + } } diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterIO.java b/src/main/java/frc/robot/subsystems/shooter/ShooterIO.java index f31cb8b6..541aa72d 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterIO.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterIO.java @@ -14,4 +14,4 @@ public default void updateInputs(ShooterIOInputs inputs) {} /** Run open loop at the specified voltage. */ public default void setVoltage(double volts) {} -} \ No newline at end of file +} diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterIOSim.java b/src/main/java/frc/robot/subsystems/shooter/ShooterIOSim.java index ba392284..e5088d81 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterIOSim.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterIOSim.java @@ -11,10 +11,10 @@ public class ShooterIOSim implements ShooterIO { @Override public void updateInputs(ShooterIOInputs inputs) { - //Update sim + // Update sim sim.update(0.02); - //Update inputs + // Update inputs inputs.velocityRadPerSec = sim.getAngularVelocityRadPerSec(); inputs.appliedVolts = appliedVolts; } @@ -24,5 +24,4 @@ public void setVoltage(double volts) { appliedVolts = volts; sim.setInputVoltage(volts); } - }