From c8d46520df1f0ccf681f75f4d7a530b723c4e20d Mon Sep 17 00:00:00 2001 From: Owen <117956892+Owen756@users.noreply.github.com> Date: Fri, 23 Feb 2024 13:53:28 -0800 Subject: [PATCH] shooter tuning --- .../frc/robot/shooter/ShooterSubsystem.java | 21 ++++++------------- 1 file changed, 6 insertions(+), 15 deletions(-) diff --git a/src/main/java/frc/robot/shooter/ShooterSubsystem.java b/src/main/java/frc/robot/shooter/ShooterSubsystem.java index 1b1fce58..183903c4 100644 --- a/src/main/java/frc/robot/shooter/ShooterSubsystem.java +++ b/src/main/java/frc/robot/shooter/ShooterSubsystem.java @@ -11,7 +11,6 @@ import frc.robot.util.scheduling.LifecycleSubsystem; import frc.robot.util.scheduling.SubsystemPriority; import org.littletonrobotics.junction.Logger; -import org.littletonrobotics.junction.networktables.LoggedDashboardNumber; public class ShooterSubsystem extends LifecycleSubsystem { private static final double SPIN_RATIO = 3.0 / 5.0; @@ -21,7 +20,6 @@ public class ShooterSubsystem extends LifecycleSubsystem { private static final double TOLERANCE_RPM = 100; private final TalonFX leftMotor; private final TalonFX rightMotor; - private final LoggedDashboardNumber ntRPM = new LoggedDashboardNumber("Shooter/RPMOverride", -1); private final VelocityTorqueCurrentFOC velocityRequest = new VelocityTorqueCurrentFOC(0).withSlot(0).withLimitReverseMotion(true); private double speakerDistance = 0; @@ -77,7 +75,7 @@ public void robotPeriodic() { Logger.recordOutput( "Shooter/LeftMotor/POutput", leftMotor.getClosedLoopProportionalOutput().getValue()); Logger.recordOutput( - "Shooter/LeftMotor/SupplierCurrent", leftMotor.getSupplyCurrent().getValueAsDouble()); + "Shooter/LeftMotor/SupplyCurrent", leftMotor.getSupplyCurrent().getValueAsDouble()); Logger.recordOutput("Shooter/LeftMotor/StatorCurrent", leftMotor.getStatorCurrent().getValue()); Logger.recordOutput("Shooter/LeftMotor/Voltage", leftMotor.getMotorVoltage().getValue()); Logger.recordOutput( @@ -88,18 +86,11 @@ public void robotPeriodic() { Logger.recordOutput( "Shooter/RightMotor/POutput", rightMotor.getClosedLoopProportionalOutput().getValue()); Logger.recordOutput( - "Shooter/RightMotor/SupplierCurrent", rightMotor.getSupplyCurrent().getValueAsDouble()); + "Shooter/RightMotor/SupplyCurrent", rightMotor.getSupplyCurrent().getValueAsDouble()); Logger.recordOutput("Shooter/AtGoal", atGoal(goalMode)); - double overrideRPM = ntRPM.get(); - - double usedGoalRPM = overrideRPM == -1 ? goalRPM : overrideRPM; - - Logger.recordOutput("Shooter/OverrideRPM", overrideRPM); - Logger.recordOutput("Shooter/UsedRPM", usedGoalRPM); - - rightMotor.setControl(velocityRequest.withVelocity((usedGoalRPM) / 60)); - leftMotor.setControl(velocityRequest.withVelocity((usedGoalRPM * SPIN_RATIO) / 60)); + leftMotor.setControl(velocityRequest.withVelocity((goalRPM) / 60)); + rightMotor.setControl(velocityRequest.withVelocity((goalRPM * SPIN_RATIO) / 60)); } public boolean atGoal(ShooterMode mode) { @@ -111,8 +102,8 @@ public boolean atGoal(ShooterMode mode) { return true; } - if (Math.abs(goalRPM - getRPM(rightMotor)) < TOLERANCE_RPM - && Math.abs((goalRPM * SPIN_RATIO) - getRPM(leftMotor)) < TOLERANCE_RPM) { + if (Math.abs((goalRPM * SPIN_RATIO) - getRPM(rightMotor)) < TOLERANCE_RPM + && Math.abs(goalRPM - getRPM(leftMotor)) < TOLERANCE_RPM) { return true; }