From d4c7b9fb3458884c46e1b886866250f6f95a43d2 Mon Sep 17 00:00:00 2001 From: Thomas Jin <83102001+Bob127227311@users.noreply.github.com> Date: Tue, 8 Oct 2024 16:59:43 -0400 Subject: [PATCH] shooter fix eeelsa --- .../robot/subsystems/shooter/ShooterIO.java | 7 +++++- .../subsystems/shooter/ShooterIOReal.java | 23 ++++++++++++------- 2 files changed, 21 insertions(+), 9 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterIO.java b/src/main/java/frc/robot/subsystems/shooter/ShooterIO.java index fe15e61..c2b3476 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterIO.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterIO.java @@ -1,6 +1,5 @@ package frc.robot.subsystems.shooter; -import frc.robot.subsystems.shooter.ShooterIO.ShooterIOInputs; import org.littletonrobotics.junction.AutoLog; public interface ShooterIO { @@ -8,11 +7,17 @@ public interface ShooterIO { public static class ShooterIOInputs { public double leftMotorVelocity = 0.0; public double rightMotorVelocity = 0.0; + public double leftAppliedVolts = 0.0; + public double rightAppliedVolts = 0.0; + public double leftOutputCurrent = 0.0; + public double rightOutputCurrent = 0.0; } public default void spinForwards() {} public default void spinBackwards() {} + public default void stopMotor() {} + public default void updateInputs(ShooterIOInputs inputs) {} } diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterIOReal.java b/src/main/java/frc/robot/subsystems/shooter/ShooterIOReal.java index 5f70d9b..5bcf7d2 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterIOReal.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterIOReal.java @@ -1,5 +1,6 @@ package frc.robot.subsystems.shooter; +import com.revrobotics.CANSparkBase.IdleMode; import com.revrobotics.CANSparkFlex; import com.revrobotics.CANSparkLowLevel.MotorType; import com.revrobotics.RelativeEncoder; @@ -9,15 +10,22 @@ public class ShooterIOReal implements ShooterIO { new CANSparkFlex(0, MotorType.kBrushless); // Can IDs not accurate private CANSparkFlex rightShooterMotor = new CANSparkFlex(1, MotorType.kBrushless); // Can IDsp not accurate + private RelativeEncoder leftShooterEncoder = leftShooterMotor.getEncoder(); private RelativeEncoder rightShooterEncoder = rightShooterMotor.getEncoder(); public ShooterIOReal() { + rightShooterMotor.restoreFactoryDefaults(); + leftShooterMotor.restoreFactoryDefaults(); + rightShooterMotor.follow(leftShooterMotor, true); - + leftShooterMotor.setSmartCurrentLimit(40); rightShooterMotor.setSmartCurrentLimit(40); + rightShooterMotor.setIdleMode(IdleMode.kCoast); + leftShooterMotor.setIdleMode(IdleMode.kCoast); + rightShooterMotor.burnFlash(); leftShooterMotor.burnFlash(); } @@ -50,25 +58,24 @@ public double getLeftVoltage() { } public double getRightVoltage() { - return rightShooterMotor.getBusVoltage(); + return rightShooterMotor.getBusVoltage(); } public double getLeftCurrent() { - return leftShooterMotor.getOutputCurrent(); + return leftShooterMotor.getOutputCurrent(); } public double getRightCurrent() { - return rightShooterMotor.getOutputCurrent(); + return rightShooterMotor.getOutputCurrent(); } @Override public void updateInputs(ShooterIOInputs inputs) { inputs.leftMotorVelocity = getLeftvelocity(); inputs.rightMotorVelocity = getRightvelocity(); - inputs.leftAppliedVolts = getLeftVoltage(); + inputs.leftAppliedVolts = getLeftVoltage(); inputs.rightAppliedVolts = getRightVoltage(); - inputs.leftOutputCurrent = getLeftCurrent(); + inputs.leftOutputCurrent = getLeftCurrent(); inputs.rightOutputCurrent = getRightCurrent(); } -} - +} \ No newline at end of file