From 9a8a1ba87162f984a95977d61fcb1eb8619dfc0d Mon Sep 17 00:00:00 2001 From: Logan Hollowood <98189655+GearBoxFox@users.noreply.github.com> Date: Fri, 2 Feb 2024 19:30:36 -0500 Subject: [PATCH] removed unused smartdashboard controls --- .../robot/subsystems/shooter/ShooterSubsystem.java | 11 ++++------- 1 file changed, 4 insertions(+), 7 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java b/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java index 1c4c3302..a56465f3 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java @@ -1,7 +1,5 @@ package frc.robot.subsystems.shooter; - -import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.SubsystemBase; import org.littletonrobotics.junction.Logger; @@ -14,7 +12,6 @@ public class ShooterSubsystem extends SubsystemBase { private final LoggedDashboardNumber m_leftSetpoint; private final LoggedDashboardNumber m_rightSetpoint; - private static final String TOP_WHEEL_RATIO = "Top wheel ratio"; public ShooterSubsystem(ShooterIO io) { m_io = io; m_inputs = new ShooterIOInputsAutoLogged(); @@ -30,12 +27,12 @@ public void periodic() { } public void setShooterPowerLeft(double power) { - m_io.setMotorVoltageTL((power * 12.0) * SmartDashboard.getNumber(TOP_WHEEL_RATIO, 0.85)); + m_io.setMotorVoltageTL(power * 12.0); m_io.setMotorVoltageBL(power * 12.0); } public void setShooterPowerRight(double power) { - m_io.setMotorVoltageTR((power * 12.0) * SmartDashboard.getNumber(TOP_WHEEL_RATIO, 0.85)); + m_io.setMotorVoltageTR(power * 12.0); m_io.setMotorVoltageBR(power * 12.0); } @@ -54,8 +51,8 @@ public void runShooterVelocity() { public Command setShooterPowerFactory(double left, double right) { return run(() -> { - setShooterPowerLeft(left == 0.0 ? 0.0 : SmartDashboard.getNumber("Left wheel", 0.6)); - setShooterPowerRight(right == 0.0 ? 0.0 : SmartDashboard.getNumber("Right wheel", 0.6)); + setShooterPowerLeft(left); + setShooterPowerRight(right); setKickerPower(left == 0.0 ? 0.0 : 1.0); setIntakePower(left == 0.0 ? 0.0 : 0.35); });