Skip to content

Commit

Permalink
feat: finished shooter IO autologged inputs
Browse files Browse the repository at this point in the history
  • Loading branch information
georgel735 committed Feb 2, 2024
1 parent 2a28eac commit 377d9f2
Show file tree
Hide file tree
Showing 3 changed files with 53 additions and 7 deletions.
25 changes: 24 additions & 1 deletion src/main/java/frc/robot/subsystems/shooter/ShooterIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,12 +4,35 @@

public interface ShooterIO {
@AutoLog
class ShooterIOInputs {}
class ShooterIOInputs {
public double tlVelocity = 0.0;
public double trVelocity = 0.0;
public double blVelocity = 0.0;
public double brVelocity = 0.0;
public double tlAppliedOutput = 0.0;
public double trAppliedOutput = 0.0;
public double blAppliedOutput = 0.0;
public double brAppliedOutput = 0.0;
public double kickerAppliedOutput = 0.0;
public double tlCurrentDraw = 0.0;
public double trCurrentDraw = 0.0;
public double blCurrentDraw = 0.0;
public double brCurrentDraw = 0.0;
public double kickerCurrentDraw = 0.0;
public double tlTemperature = 0.0;
public double trTemperature = 0.0;
public double blTemperature = 0.0;
public double brTemperature = 0.0;



}
default void setMotorVoltageTL(double voltage) {}
default void setMotorVoltageTR(double voltage) {}
default void setMotorVoltageBL(double voltage) {}
default void setMotorVoltageBR(double voltage) {}
default void setKickerVoltage(double voltage) {}
default void setIntakeVoltage(double voltage) {}
default void updateInputs(ShooterIOInputs inputs) {}

}
33 changes: 27 additions & 6 deletions src/main/java/frc/robot/subsystems/shooter/ShooterIOPrototype.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,30 +9,30 @@ public class ShooterIOPrototype implements ShooterIO {
private final CANSparkMax m_topRightMotor;
private final CANSparkFlex m_bottomLeftMotor;
private final CANSparkMax m_bottomRightMotor;
private final CANSparkMax m_kickekMotor;
private final CANSparkMax m_kickerkMotor;
public ShooterIOPrototype() {
m_topLeftMotor = new CANSparkFlex(13, CANSparkLowLevel.MotorType.kBrushless);
m_topRightMotor = new CANSparkMax(14, CANSparkLowLevel.MotorType.kBrushless);
m_bottomLeftMotor = new CANSparkFlex(15, CANSparkLowLevel.MotorType.kBrushless);
m_bottomRightMotor = new CANSparkMax(16, CANSparkLowLevel.MotorType.kBrushless);
m_kickekMotor = new CANSparkMax(17, CANSparkLowLevel.MotorType.kBrushless);
m_kickerkMotor = new CANSparkMax(17, CANSparkLowLevel.MotorType.kBrushless);

m_topLeftMotor.setInverted(false);
m_topRightMotor.setInverted(true);
m_bottomLeftMotor.setInverted(true);
m_bottomRightMotor.setInverted(true);
m_kickekMotor.setInverted(true);
m_kickerkMotor.setInverted(true);

m_topLeftMotor.burnFlash();
m_topRightMotor.burnFlash();
m_topRightMotor.burnFlash();
m_bottomRightMotor.burnFlash();
m_kickekMotor.burnFlash();
m_kickerkMotor.burnFlash();
}

// @Override
// public void updateInputs(ShooterIOInputs inputs) {
// inputs.tLAngularVelocity = m_topLeftMotor.getEncoder().getVelocity() * Math.PI;
// inputs.tLAngularVelocity = m_topLeftMotor.getEncoder().getVelocity() * Math.PI * 2;
// inputs.tRAngularVelocity = m_topRightMotor.getEncoder().getVelocity() * Math.PI;
// inputs.bLAngularVelocity = m_bottomLeftMotor.getEncoder().getVelocity() * Math.PI;
// inputs.bRAngularVelocity = m_bottomRightMotor.getEncoder().getVelocity() * Math.PI;
Expand Down Expand Up @@ -67,7 +67,28 @@ public void setMotorVoltageBR(double voltage) {

@Override
public void setKickerVoltage(double voltage) {
m_kickekMotor.setVoltage(voltage);
m_kickerkMotor.setVoltage(voltage);
}

@Override
public void updateInputs(ShooterIOInputs inputs) {
inputs.tlVelocity = m_topLeftMotor.getEncoder().getVelocity() * Math.PI * 2.0;
inputs.trVelocity = m_topRightMotor.getEncoder().getVelocity() * Math.PI * 2.0;
inputs.blVelocity = m_bottomLeftMotor.getEncoder().getVelocity() * Math.PI * 2.0;
inputs.brVelocity = m_bottomRightMotor.getEncoder().getVelocity() * Math.PI * 2.0;
inputs.tlAppliedOutput = m_topLeftMotor.getAppliedOutput();
inputs.trAppliedOutput = m_topRightMotor.getAppliedOutput();
inputs.blAppliedOutput = m_bottomLeftMotor.getAppliedOutput();
inputs.brAppliedOutput = m_bottomRightMotor.getAppliedOutput();
inputs.kickerAppliedOutput = m_kickerkMotor.getAppliedOutput();
inputs.tlCurrentDraw = m_topLeftMotor.getOutputCurrent();
inputs.trCurrentDraw = m_topRightMotor.getOutputCurrent();
inputs.blCurrentDraw = m_bottomLeftMotor.getOutputCurrent();
inputs.brCurrentDraw = m_bottomRightMotor.getOutputCurrent();
inputs.kickerCurrentDraw = m_kickerkMotor.getOutputCurrent();
inputs.tlTemperature = m_topLeftMotor.getMotorTemperature();
inputs.trTemperature = m_topRightMotor.getMotorTemperature();
inputs.blTemperature = m_bottomLeftMotor.getMotorTemperature();
inputs.brTemperature = m_bottomRightMotor.getMotorTemperature();
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -7,10 +7,12 @@

public class ShooterSubsystem extends SubsystemBase {
private final ShooterIO m_io;
private final ShooterIOInputsAutoLogged m_inputs;

private static final String TOP_WHEEL_RATIO = "Top wheel ratio";
public ShooterSubsystem(ShooterIO io) {
m_io = io;
m_inputs = new ShooterIOInputsAutoLogged();
SmartDashboard.putNumber(TOP_WHEEL_RATIO, 0.8);
SmartDashboard.putNumber("Left wheel", 0.6);
SmartDashboard.putNumber("Right wheel", 0.6);
Expand Down

0 comments on commit 377d9f2

Please sign in to comment.