Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions src/main/java/frc/robot/subsystems/hopper/HopperIO.java
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
package frc.robot.subsystems.hopper;
import static edu.wpi.first.units.Units.Amps;
import static edu.wpi.first.units.Units.Celsius;
import static edu.wpi.first.units.Units.DegreesPerSecond;
import static edu.wpi.first.units.Units.DegreesPerSecondPerSecond;
import static edu.wpi.first.units.Units.Volts;
Expand All @@ -9,6 +10,7 @@
import edu.wpi.first.units.measure.AngularAcceleration;
import edu.wpi.first.units.measure.AngularVelocity;
import edu.wpi.first.units.measure.Current;
import edu.wpi.first.units.measure.Temperature;
import edu.wpi.first.units.measure.Voltage;

public interface HopperIO {
Expand All @@ -19,12 +21,14 @@ public static class HopperIOInputs {
public AngularAcceleration feederAcceleration = DegreesPerSecondPerSecond.of(0) ;
public Voltage feederVoltage = Volts.of(0.0);
public Current feederCurrent = Amps.of(0.0);
public Temperature feederTemp = Celsius.zero();

public boolean scramblerConnected = false;
public AngularVelocity scramblerVelocity = DegreesPerSecond.of(0);
public AngularAcceleration scramblerAcceleration = DegreesPerSecondPerSecond.of(0) ;
public Voltage scramblerVoltage = Volts.of(0.0);
public Current scramblerCurrent = Amps.of(0.0);
public Temperature scramblerTemp = Celsius.zero();
}
public default void updateInputs(HopperIOInputs inputs) {}

Expand Down
29 changes: 23 additions & 6 deletions src/main/java/frc/robot/subsystems/hopper/HopperIOTalonFX.java
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
import edu.wpi.first.units.measure.AngularAcceleration;
import edu.wpi.first.units.measure.AngularVelocity;
import edu.wpi.first.units.measure.Current;
import edu.wpi.first.units.measure.Temperature;
import edu.wpi.first.units.measure.Voltage;

public class HopperIOTalonFX implements HopperIO {
Expand All @@ -40,13 +41,15 @@ public class HopperIOTalonFX implements HopperIO {
private final StatusSignal<AngularVelocity> feederAngularVelocitySignal;
private final StatusSignal<AngularAcceleration> feederAngularAccelerationSignal ;
private final StatusSignal<Voltage> feederVoltageSignal;
private final StatusSignal<Current> feederCurrentSignal;
private final StatusSignal<Current> feederCurrentSignal;
private final StatusSignal<Temperature> feederTemp;

//Scrambler Status Signals
private final StatusSignal<AngularVelocity> scramblerAngularVelocitySignal;
private final StatusSignal<AngularAcceleration> scramblerAngularAccelerationSignal ;
private final StatusSignal<Voltage> scramblerVoltageSignal;
private final StatusSignal<Current> scramblerCurrentSignal;
private final StatusSignal<Temperature> scramblerTemp;

private final Debouncer feederConnectedDebounce = new Debouncer(0.5, DebounceType.kFalling);
private final Debouncer scramblerConnectedDebounce = new Debouncer(0.5, DebounceType.kFalling);
Expand Down Expand Up @@ -75,7 +78,8 @@ public HopperIOTalonFX(CANBus canBus) {
feederAngularVelocitySignal = feederMotor.getVelocity();
feederAngularAccelerationSignal = feederMotor.getAcceleration() ;
feederVoltageSignal = feederMotor.getMotorVoltage();
feederCurrentSignal = feederMotor.getSupplyCurrent();
feederCurrentSignal = feederMotor.getSupplyCurrent();
feederTemp = feederMotor.getDeviceTemp();

// Scrambler Motor Configuration
scramblerMotor = new TalonFX(HopperConstants.scramblerMotorCANID);
Expand All @@ -96,37 +100,50 @@ public HopperIOTalonFX(CANBus canBus) {
scramblerAngularAccelerationSignal = scramblerMotor.getAcceleration() ;
scramblerVoltageSignal = scramblerMotor.getMotorVoltage();
scramblerCurrentSignal = scramblerMotor.getSupplyCurrent();
scramblerTemp = scramblerMotor.getDeviceTemp();

BaseStatusSignal.setUpdateFrequencyForAll(50.0,
feederAngularVelocitySignal, feederVoltageSignal, feederCurrentSignal, feederAngularAccelerationSignal);
feederAngularVelocitySignal, feederVoltageSignal, feederCurrentSignal, feederAngularAccelerationSignal, feederTemp);

feederMotor.optimizeBusUtilization();

BaseStatusSignal.setUpdateFrequencyForAll(50.0,
scramblerAngularVelocitySignal, scramblerVoltageSignal, scramblerCurrentSignal, scramblerAngularAccelerationSignal);
scramblerAngularVelocitySignal, scramblerVoltageSignal, scramblerCurrentSignal, scramblerAngularAccelerationSignal, scramblerTemp);

scramblerMotor.optimizeBusUtilization();
}

@Override
public void updateInputs(HopperIOInputs inputs) {
StatusCode feederStatus = BaseStatusSignal.refreshAll(
feederAngularVelocitySignal, feederVoltageSignal, feederCurrentSignal);
feederAngularVelocitySignal,
feederAngularAccelerationSignal,
feederVoltageSignal,
feederCurrentSignal,
feederTemp
);

StatusCode scramblerStatus = BaseStatusSignal.refreshAll(
scramblerAngularVelocitySignal, scramblerVoltageSignal, scramblerCurrentSignal);
scramblerAngularVelocitySignal,
scramblerAngularAccelerationSignal,
scramblerVoltageSignal,
scramblerCurrentSignal,
scramblerTemp
);

inputs.feederConnected = feederConnectedDebounce.calculate(feederStatus.isOK());
inputs.feederVelocity = feederAngularVelocitySignal.getValue();
inputs.feederAcceleration = feederAngularAccelerationSignal.getValue() ;
inputs.feederVoltage = feederVoltageSignal.getValue();
inputs.feederCurrent = feederCurrentSignal.getValue();
inputs.feederTemp = feederTemp.getValue();

inputs.scramblerConnected = scramblerConnectedDebounce.calculate(scramblerStatus.isOK());
inputs.scramblerVelocity = scramblerAngularVelocitySignal.getValue();
inputs.scramblerAcceleration = scramblerAngularAccelerationSignal.getValue() ;
inputs.scramblerVoltage = scramblerVoltageSignal.getValue();
inputs.scramblerCurrent = scramblerCurrentSignal.getValue();
inputs.scramblerTemp = scramblerTemp.getValue();
}

@Override
Expand Down
5 changes: 5 additions & 0 deletions src/main/java/frc/robot/subsystems/intake/IntakeIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,13 @@
import edu.wpi.first.units.measure.Angle;
import edu.wpi.first.units.measure.AngularVelocity;
import edu.wpi.first.units.measure.Current;
import edu.wpi.first.units.measure.Temperature;

import static edu.wpi.first.units.Units.Volts;
import static edu.wpi.first.units.Units.Degrees;
import static edu.wpi.first.units.Units.DegreesPerSecond;
import static edu.wpi.first.units.Units.Amps;
import static edu.wpi.first.units.Units.Celsius;

import org.littletonrobotics.junction.AutoLog;

Expand All @@ -22,11 +25,13 @@ public class IntakeIOInputs{
public AngularVelocity pivotCancoderVelocity = DegreesPerSecond.of(0);
public Voltage pivotAppliedVolts = Volts.of(0);
public Current pivotCurrentAmps = Amps.of(0);
public Temperature pivotTemp = Celsius.zero();

public boolean rollerConnected = false;
public AngularVelocity rollerAngularVelocity = DegreesPerSecond.of(0);
public Voltage rollerAppliedVolts = Volts.of(0);
public Current rollerCurrentAmps = Amps.of(0);
public Temperature rollerTemp = Celsius.zero();
}

public default void updateInputs(IntakeIOInputsAutoLogged inputs) {}
Expand Down
13 changes: 11 additions & 2 deletions src/main/java/frc/robot/subsystems/intake/IntakeIOTalonFX.java
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
import edu.wpi.first.units.measure.Angle;
import edu.wpi.first.units.measure.AngularVelocity;
import edu.wpi.first.units.measure.Current;
import edu.wpi.first.units.measure.Temperature;
import edu.wpi.first.units.measure.Voltage;


Expand Down Expand Up @@ -59,13 +60,15 @@ public class IntakeIOTalonFX implements IntakeIO {
private StatusSignal<AngularVelocity> pivotAngularVelocitySignal;
private StatusSignal<Current> pivotCurrentAmpsSignal;
private StatusSignal<Voltage> pivotAppliedVoltsSignal;
private StatusSignal<Temperature> pivotTemp;
private StatusSignal<Angle> pivotCancoderPositionSignal;
private StatusSignal<AngularVelocity> pivotCancoderVelocitySignal;

//Roller status signals
private StatusSignal<AngularVelocity> rollerAngularVelocitySignal;
private StatusSignal<Voltage> rollerAppliedVoltsSignal;
private StatusSignal<Current> rollerCurrentAmpsSignal;
private StatusSignal<Temperature> rollerTemp;

public IntakeIOTalonFX(CANBus canbus) {
// Initialize motor objects
Expand Down Expand Up @@ -157,6 +160,8 @@ public IntakeIOTalonFX(CANBus canbus) {
pivotAppliedVoltsSignal = pivotMotor.getMotorVoltage();
rollerCurrentAmpsSignal = rollerMotor.getSupplyCurrent();
pivotCurrentAmpsSignal = pivotMotor.getSupplyCurrent();
pivotTemp = pivotMotor.getDeviceTemp();
rollerTemp = rollerMotor.getDeviceTemp();
pivotCancoderPositionSignal = pivotCancoder.getPosition();
pivotCancoderVelocitySignal = pivotCancoder.getVelocity();

Expand All @@ -177,27 +182,31 @@ public void updateInputs(IntakeIOInputsAutoLogged inputs) {
pivotAppliedVoltsSignal,
pivotCurrentAmpsSignal,
pivotCancoderPositionSignal,
pivotCancoderVelocitySignal
pivotCancoderVelocitySignal,
pivotTemp
);

var rollerStatus = BaseStatusSignal.refreshAll(
rollerAngularVelocitySignal,
rollerAppliedVoltsSignal,
rollerCurrentAmpsSignal
rollerCurrentAmpsSignal,
rollerTemp
);

inputs.pivotConnected = pivotConnectedDebounce.calculate(pivotStatus.isOK());
inputs.pivotAngle = pivotAngleSignal.getValue() ;
inputs.pivotAngularVelocity = pivotAngularVelocitySignal.getValue();
inputs.pivotAppliedVolts = pivotAppliedVoltsSignal.getValue();
inputs.pivotCurrentAmps = pivotCurrentAmpsSignal.getValue();
inputs.pivotTemp = pivotTemp.getValue();
inputs.pivotCancoderPosition = pivotCancoderPositionSignal.getValue();
inputs.pivotCancoderVelocity = pivotCancoderVelocitySignal.getValue();

inputs.rollerConnected = rollerConnectedDebounce.calculate(rollerStatus.isOK());
inputs.rollerAngularVelocity = rollerAngularVelocitySignal.getValue();
inputs.rollerAppliedVolts = rollerAppliedVoltsSignal.getValue();
inputs.rollerCurrentAmps = rollerCurrentAmpsSignal.getValue();
inputs.rollerTemp = rollerTemp.getValue();
}

@Override
Expand Down
3 changes: 3 additions & 0 deletions src/main/java/frc/robot/subsystems/shooter/ShooterIO.java
Original file line number Diff line number Diff line change
@@ -1,13 +1,15 @@
package frc.robot.subsystems.shooter;

import static edu.wpi.first.units.Units.Amps;
import static edu.wpi.first.units.Units.Celsius;
import static edu.wpi.first.units.Units.RadiansPerSecond;
import static edu.wpi.first.units.Units.Volts;

import org.littletonrobotics.junction.AutoLog;

import edu.wpi.first.units.measure.AngularVelocity;
import edu.wpi.first.units.measure.Current;
import edu.wpi.first.units.measure.Temperature;
import edu.wpi.first.units.measure.Voltage;

public interface ShooterIO {
Expand All @@ -18,6 +20,7 @@ public static class ShooterIOInputs {
public Voltage shooter1Voltage = Volts.zero();
public Current shooter1Current = Amps.zero();
public AngularVelocity shooter1Velocity = RadiansPerSecond.zero();
public Temperature shooter1Temp = Celsius.zero();
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Shooter2Temp and Shooter3Temp are never set in here, causing the build to fail.


public Voltage shooter2Voltage = Volts.zero();
public Current shooter2Current = Amps.zero();
Expand Down
16 changes: 15 additions & 1 deletion src/main/java/frc/robot/subsystems/shooter/ShooterIOTalonFX.java
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@

import edu.wpi.first.units.measure.AngularVelocity;
import edu.wpi.first.units.measure.Current;
import edu.wpi.first.units.measure.Temperature;
import edu.wpi.first.units.measure.Voltage;

public class ShooterIOTalonFX implements ShooterIO {
Expand All @@ -31,14 +32,17 @@ public class ShooterIOTalonFX implements ShooterIO {
private StatusSignal<AngularVelocity> shooter1AngularVelocity;
private StatusSignal<Voltage> shooter1AppliedVolts;
private StatusSignal<Current> shooter1CurrentAmps;
private StatusSignal<Temperature> shooter1Temp;

private StatusSignal<AngularVelocity> shooter2AngularVelocity;
private StatusSignal<Voltage> shooter2AppliedVolts;
private StatusSignal<Current> shooter2CurrentAmps;
private StatusSignal<Temperature> shooter2Temp;

private StatusSignal<AngularVelocity> shooter3AngularVelocity;
private StatusSignal<Voltage> shooter3AppliedVolts;
private StatusSignal<Current> shooter3CurrentAmps;
private StatusSignal<Temperature> shooter3Temp;

public ShooterIOTalonFX(CANBus shooterCANBus) {

Expand Down Expand Up @@ -80,24 +84,30 @@ public ShooterIOTalonFX(CANBus shooterCANBus) {
shooter1AngularVelocity = shooter1Motor.getVelocity();
shooter1AppliedVolts = shooter1Motor.getMotorVoltage();
shooter1CurrentAmps = shooter1Motor.getSupplyCurrent();
shooter1Temp = shooter1Motor.getDeviceTemp();
shooter2AngularVelocity = shooter2Motor.getVelocity();
shooter2AppliedVolts = shooter2Motor.getMotorVoltage();
shooter2CurrentAmps = shooter2Motor.getSupplyCurrent();
shooter2Temp = shooter2Motor.getDeviceTemp();
shooter3AngularVelocity = shooter3Motor.getVelocity();
shooter3AppliedVolts = shooter3Motor.getMotorVoltage();
shooter3CurrentAmps = shooter3Motor.getSupplyCurrent();
shooter3Temp = shooter3Motor.getDeviceTemp();

// Status Signal Collection, less repetitive code
signals = new StatusSignalCollection(
shooter1AngularVelocity,
shooter1AppliedVolts,
shooter1CurrentAmps,
shooter1Temp,
shooter2AngularVelocity,
shooter2AppliedVolts,
shooter2CurrentAmps,
shooter2Temp,
shooter3AngularVelocity,
shooter3AppliedVolts,
shooter3CurrentAmps
shooter3CurrentAmps,
shooter3Temp
);

tryUntilOk(5, () -> signals.setUpdateFrequencyForAll(50.0));
Expand All @@ -123,6 +133,10 @@ public void updateInputs(ShooterIOInputs inputs) {
inputs.shooter2Current = shooter2CurrentAmps.getValue();
inputs.shooter3Current = shooter3CurrentAmps.getValue();

inputs.shooter1Temp = shooter1Temp.getValue();
inputs.shooter2Temp = shooter2Temp.getValue();
inputs.shooter3Temp = shooter3Temp.getValue();

inputs.wheelVelocity = inputs.shooter1Velocity.times(ShooterConstants.gearRatio);
}

Expand Down
Loading