Skip to content

Change file names to match new conventions #72

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 8 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 3 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
10 changes: 5 additions & 5 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -25,9 +25,9 @@
import frc.robot.subsystems.swerve.moduleIO.ModuleInterface;
import frc.robot.subsystems.swerve.moduleIO.PhysicalModule;
import frc.robot.subsystems.swerve.moduleIO.SimulatedModule;
import frc.robot.subsystems.vision.PhysicalVision;
import frc.robot.subsystems.vision.Vision;
import frc.robot.subsystems.vision.VisionIO;
import frc.robot.subsystems.vision.VisionIOReal;
import frc.robot.subsystems.vision.VisionInterface;
import java.util.function.DoubleSupplier;
import org.littletonrobotics.junction.Logger;

Expand Down Expand Up @@ -67,7 +67,7 @@
new PhysicalModule(SwerveConstants.moduleConfigs[1]),
new PhysicalModule(SwerveConstants.moduleConfigs[2]),
new PhysicalModule(SwerveConstants.moduleConfigs[3]));
visionSubsystem = new Vision(new VisionIOReal());
visionSubsystem = new Vision(new PhysicalVision());
}

case SIM -> {
Expand Down Expand Up @@ -106,15 +106,15 @@
new SimulatedModule(swerveDriveSimulation.getModules()[3]));

// TODO: add sim impl
visionSubsystem = new Vision(new VisionIO() {});
visionSubsystem = new Vision(new VisionInterface() {});

SimulatedField.getInstance().resetFieldForAuto();
resetFieldAndOdometryForAuto(
new Pose2d(1.3980597257614136, 5.493067741394043, Rotation2d.fromRadians(3.1415)));
}

default -> {
visionSubsystem = new Vision(new VisionIO() {});
visionSubsystem = new Vision(new VisionInterface() {});
/* Replayed robot, disable IO implementations */

/* physics simulations are also not needed */
Expand Down Expand Up @@ -209,13 +209,13 @@
() -> modifyAxisCubedPolar(driverLeftStickX, driverLeftStickY)[1]
};

DoubleSupplier operatorLeftStickX = operatorController::getLeftX;

Check warning on line 212 in src/main/java/frc/robot/RobotContainer.java

View workflow job for this annotation

GitHub Actions / Lint

Avoid unused local variables such as 'operatorLeftStickX'.

Detects when a local variable is declared and/or assigned, but not used. Variables whose name starts with `ignored` or `unused` are filtered out. UnusedLocalVariable (Priority: 3, Ruleset: Best Practices) https://docs.pmd-code.org/pmd-doc-7.7.0/pmd_rules_java_bestpractices.html#unusedlocalvariable

Check warning on line 212 in src/main/java/frc/robot/RobotContainer.java

View workflow job for this annotation

GitHub Actions / Lint

Avoid unused local variables such as 'operatorLeftStickX'.

Detects when a local variable is declared and/or assigned, but not used. Variables whose name starts with `ignored` or `unused` are filtered out. UnusedLocalVariable (Priority: 3, Ruleset: Best Practices) https://docs.pmd-code.org/pmd-doc-7.7.0/pmd_rules_java_bestpractices.html#unusedlocalvariable
DoubleSupplier operatorRightStickY = operatorController::getRightY;

Check warning on line 213 in src/main/java/frc/robot/RobotContainer.java

View workflow job for this annotation

GitHub Actions / Lint

Avoid unused local variables such as 'operatorRightStickY'.

Detects when a local variable is declared and/or assigned, but not used. Variables whose name starts with `ignored` or `unused` are filtered out. UnusedLocalVariable (Priority: 3, Ruleset: Best Practices) https://docs.pmd-code.org/pmd-doc-7.7.0/pmd_rules_java_bestpractices.html#unusedlocalvariable

Check warning on line 213 in src/main/java/frc/robot/RobotContainer.java

View workflow job for this annotation

GitHub Actions / Lint

Avoid unused local variables such as 'operatorRightStickY'.

Detects when a local variable is declared and/or assigned, but not used. Variables whose name starts with `ignored` or `unused` are filtered out. UnusedLocalVariable (Priority: 3, Ruleset: Best Practices) https://docs.pmd-code.org/pmd-doc-7.7.0/pmd_rules_java_bestpractices.html#unusedlocalvariable

Trigger driverRightBumper = new Trigger(driverController.rightBumper());
Trigger driverRightDirectionPad = new Trigger(driverController.pov(90));
Trigger driverDownDirectionPad = new Trigger(driverController.pov(180));

Check warning on line 217 in src/main/java/frc/robot/RobotContainer.java

View workflow job for this annotation

GitHub Actions / Lint

Avoid unused local variables such as 'driverDownDirectionPad'.

Detects when a local variable is declared and/or assigned, but not used. Variables whose name starts with `ignored` or `unused` are filtered out. UnusedLocalVariable (Priority: 3, Ruleset: Best Practices) https://docs.pmd-code.org/pmd-doc-7.7.0/pmd_rules_java_bestpractices.html#unusedlocalvariable

Check warning on line 217 in src/main/java/frc/robot/RobotContainer.java

View workflow job for this annotation

GitHub Actions / Lint

Avoid unused local variables such as 'driverDownDirectionPad'.

Detects when a local variable is declared and/or assigned, but not used. Variables whose name starts with `ignored` or `unused` are filtered out. UnusedLocalVariable (Priority: 3, Ruleset: Best Practices) https://docs.pmd-code.org/pmd-doc-7.7.0/pmd_rules_java_bestpractices.html#unusedlocalvariable
Trigger driverLeftDirectionPad = new Trigger(driverController.pov(270));

Check warning on line 218 in src/main/java/frc/robot/RobotContainer.java

View workflow job for this annotation

GitHub Actions / Lint

Avoid unused local variables such as 'driverLeftDirectionPad'.

Detects when a local variable is declared and/or assigned, but not used. Variables whose name starts with `ignored` or `unused` are filtered out. UnusedLocalVariable (Priority: 3, Ruleset: Best Practices) https://docs.pmd-code.org/pmd-doc-7.7.0/pmd_rules_java_bestpractices.html#unusedlocalvariable

Check warning on line 218 in src/main/java/frc/robot/RobotContainer.java

View workflow job for this annotation

GitHub Actions / Lint

Avoid unused local variables such as 'driverLeftDirectionPad'.

Detects when a local variable is declared and/or assigned, but not used. Variables whose name starts with `ignored` or `unused` are filtered out. UnusedLocalVariable (Priority: 3, Ruleset: Best Practices) https://docs.pmd-code.org/pmd-doc-7.7.0/pmd_rules_java_bestpractices.html#unusedlocalvariable

// // autodrive
// Trigger driverAButton = new Trigger(driverController::getAButton);
Expand Down
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/subsystems/elevator/Elevator.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,10 @@
import org.littletonrobotics.junction.Logger;

public class Elevator extends SubsystemBase {
private final ElevatorIO io;
private final ElevatorIOInputsAutoLogged inputs = new ElevatorIOInputsAutoLogged();
private final ElevatorInterface io;
private final ElevatorInterfaceInputsAutoLogged inputs = new ElevatorInterfaceInputsAutoLogged();

public Elevator(ElevatorIO io) {
public Elevator(ElevatorInterface io) {
super("Elevator");
this.io = io;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,9 @@

import org.littletonrobotics.junction.AutoLog;

public interface ElevatorIO {
public interface ElevatorInterface {
@AutoLog
public static class ElevatorIOInputs {
public static class ElevatorInterfaceInputs {
Copy link
Member

Choose a reason for hiding this comment

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

ElevatorInputs

Copy link
Member

Choose a reason for hiding this comment

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

por favor

Copy link
Member

Choose a reason for hiding this comment

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

plz correct this in all da files bc the elevator inputs are autologged from the specific impls. they aren't logged from the interface. @JacksonElia do u think this is good?

Copy link
Member

Choose a reason for hiding this comment

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

yeah I think it is. I really think we should try to avoid using default and not implement any methods in interfaces as that defeats their purpose. If we really want to implement methods in the interface, we can just make them abstract classes.

Copy link
Member

Choose a reason for hiding this comment

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

okay after looking into it more I guess its not awful using default. I looked at their template code and some things have it, but where they use it feels icky to me. I'm gonna ask eldest Matthew about it

Copy link
Member

Choose a reason for hiding this comment

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

The reason I think we do that is bc for log replay u need a blank impl of the io layer to rerun the code. So we just pass in the interface. What we could do instead is create a blank impl with the defaults seen in the interface, which would work. Idk which one is better. So like as opposed to using ElevatorInterface we would use ElevatorReplay or smthn.

Copy link
Member

Choose a reason for hiding this comment

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

Thats a good explanation, thanks. I would say normally I feel like making something like ElevatorReplay would be better practice, but in this case I guess following the convention of using default like akit has already specified makes more sense.

Though, if we start writing a lot of replay specific code for whatever reason, then we should make a specific implementation for it.

public boolean isConnected = false;

public double leaderMotorPosition = 0.0;
Expand All @@ -18,7 +18,7 @@ public static class ElevatorIOInputs {
public double followerMotorCurrentAmps = 0.0;
}

public default void updateInputs(ElevatorIOInputs inputs) {}
public default void updateInputs(ElevatorInterfaceInputs inputs) {}

public default double getElevatorPosition() {
return 0.0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,9 @@
import edu.wpi.first.units.measure.Current;
import edu.wpi.first.units.measure.Voltage;
import frc.robot.Constants.HardwareConstants;
import frc.robot.subsystems.elevator.ElevatorInterface.ElevatorInterfaceInputs;

public class ElevatorIOTalonFX implements ElevatorIO {
public class PhysicalElevator implements ElevatorInterface {
private final TalonFX leaderElevatorMotor;
private final TalonFX followerElevatorMotor;

Expand All @@ -36,7 +37,7 @@ public class ElevatorIOTalonFX implements ElevatorIO {
StatusSignal<Voltage> followerAppliedVolts;
StatusSignal<Current> followerCurrentAmps;

public ElevatorIOTalonFX() {
public PhysicalElevator() {
leaderElevatorMotor = new TalonFX(0);
followerElevatorMotor = new TalonFX(0);

Expand Down Expand Up @@ -106,7 +107,7 @@ public ElevatorIOTalonFX() {
}

@Override
public void updateInputs(ElevatorIOInputs inputs) {
public void updateInputs(ElevatorInterfaceInputs inputs) {
inputs.isConnected =
BaseStatusSignal.isAllGood(
leaderPosition,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,13 +9,13 @@
import edu.wpi.first.math.system.plant.LinearSystemId;
import edu.wpi.first.wpilibj.simulation.ElevatorSim;

public class ElevatorIOSim implements ElevatorIO {
public class SimulatedElevator implements ElevatorInterface {
ElevatorSim elevatorSim;
LinearSystem<N2, N1, N2> elevatorSystem;
private double elevatorAppliedVolts = 0.0;
private final PIDController elevatorPID = new PIDController(0.0, 0.0, 0.0);

public ElevatorIOSim() {
public SimulatedElevator() {
this.elevatorSystem = LinearSystemId.createElevatorSystem(DCMotor.getFalcon500(2), 0, 0, 0);
this.elevatorSim =
new ElevatorSim(
Expand All @@ -28,7 +28,7 @@ public ElevatorIOSim() {
}

@Override
public void updateInputs(ElevatorIOInputs inputs) {
public void updateInputs(ElevatorInterfaceInputs inputs) {
elevatorSim.update(0.02);

inputs.isConnected = true;
Expand Down
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/subsystems/indexer/Indexer.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,10 @@
import org.littletonrobotics.junction.Logger;

public class Indexer extends SubsystemBase {
private IndexerIO io;
private IndexerIOInputsAutoLogged inputs = new IndexerIOInputsAutoLogged();
private IndexerInterface io;
private IndexerInterfaceInputsAutoLogged inputs = new IndexerInterfaceInputsAutoLogged();

public Indexer(IndexerIO io) {
public Indexer(IndexerInterface io) {
this.io = io;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,9 @@

import org.littletonrobotics.junction.AutoLog;

public interface IndexerIO {
public interface IndexerInterface {
@AutoLog
public static class IndexerIOInputs {
public static class IndexerInterfaceInputs {
public boolean isConnected = false;
public double indexerVelocity = 0.0;
public double indexerAppliedVolts = 0.0;
Expand All @@ -13,7 +13,7 @@ public static class IndexerIOInputs {
public double indexerSupplyCurrentAmps = 0.0;
}

default void updateInputs(IndexerIOInputs inputs) {}
default void updateInputs(IndexerInterfaceInputs inputs) {}

default boolean isIndexing() {
return false;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
import edu.wpi.first.units.measure.Voltage;
import frc.robot.Constants.HardwareConstants;

public class IndexerIOTalonFX implements IndexerIO {
public class PhysicalIndexer implements IndexerInterface {
private final TalonFX indexerMotor = new TalonFX(0);

private final StatusSignal<AngularVelocity> indexerVelocity;
Expand All @@ -21,7 +21,7 @@ public class IndexerIOTalonFX implements IndexerIO {
private final StatusSignal<Current> indexerSupplyCurrentAmps;
private final StatusSignal<Temperature> indexerTemp;

public IndexerIOTalonFX() {
public PhysicalIndexer() {
TalonFXConfiguration indexerConfiguration = new TalonFXConfiguration();
indexerConfiguration.MotorOutput.Inverted = InvertedValue.Clockwise_Positive;
indexerConfiguration.MotorOutput.DutyCycleNeutralDeadband =
Expand Down Expand Up @@ -52,7 +52,7 @@ public IndexerIOTalonFX() {
}

@Override
public void updateInputs(IndexerIOInputs inputs) {
public void updateInputs(IndexerInterfaceInputs inputs) {
inputs.indexerAppliedVolts = indexerAppliedVolts.getValueAsDouble();
inputs.indexerStatorCurrentAmps = indexerStatorCurrentAmps.getValueAsDouble();
inputs.indexerSupplyCurrentAmps = indexerSupplyCurrentAmps.getValueAsDouble();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,12 @@
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.wpilibj.simulation.DCMotorSim;

public class IndexerIOSim implements IndexerIO {
public class SimulatedIndexer implements IndexerInterface {
private final DCMotorSim indexerSim = new DCMotorSim(null, DCMotor.getFalcon500(1), 0);

private double indexerAppliedVolts = 0.0;

public IndexerIOSim(IndexerIOInputs inputs) {
public SimulatedIndexer(IndexerInterfaceInputs inputs) {
indexerSim.update(0.02);

inputs.isConnected = true;
Expand Down
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/subsystems/intake/Intake.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,10 @@
import org.littletonrobotics.junction.Logger;

public class Intake extends SubsystemBase {
private IntakeIO io;
private IntakeIOInputsAutoLogged inputs = new IntakeIOInputsAutoLogged();
private IntakeInterface io;
private IntakeInterfaceInputsAutoLogged inputs = new IntakeInterfaceInputsAutoLogged();

public Intake(IntakeIO io) {
public Intake(IntakeInterface io) {
this.io = io;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,9 @@

import org.littletonrobotics.junction.AutoLog;

public interface IntakeIO {
public interface IntakeInterface {
@AutoLog
public static class IntakeIOInputs {
public static class IntakeInterfaceInputs {
public boolean isConnected = true;

// intake motor
Expand All @@ -21,7 +21,7 @@ public static class IntakeIOInputs {
public double pivotCurrentAmps = 0.0;
}

default void updateInputs(IntakeIOInputs inputs) {}
default void updateInputs(IntakeInterfaceInputs inputs) {}

default void setPivotPosition(double position) {}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
import edu.wpi.first.units.measure.AngularVelocity;
import frc.robot.Constants.HardwareConstants;

public class IntakeIOTalonFX implements IntakeIO {
public class PhysicalIntake implements IntakeInterface {
private final TalonFX intakeMotor = new TalonFX(IntakeConstants.INTAKE_MOTOR_ID);
private final TalonFX leaderPivotMotor = new TalonFX(IntakeConstants.LEFT_INTAKE_PIVOT_MOTOR_ID);
private final TalonFX followerPivotMotor =
Expand All @@ -24,7 +24,7 @@ public class IntakeIOTalonFX implements IntakeIO {
private final StatusSignal<Angle> pivotPosition;
private final StatusSignal<AngularVelocity> pivotVelocity;

public IntakeIOTalonFX() {
public PhysicalIntake() {
TalonFXConfiguration intakeConfig = new TalonFXConfiguration();

intakeConfig.MotorOutput.Inverted = InvertedValue.CounterClockwise_Positive;
Expand Down Expand Up @@ -82,7 +82,7 @@ public IntakeIOTalonFX() {
}

@Override
public void updateInputs(IntakeIOInputs inputs) {
public void updateInputs(IntakeInterfaceInputs inputs) {
inputs.intakeVelocity = intakeVelocity.getValueAsDouble();
inputs.pivotPosition = pivotPosition.getValueAsDouble();
inputs.pivotVelocity = pivotVelocity.getValueAsDouble();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,8 @@
import edu.wpi.first.math.trajectory.TrapezoidProfile.Constraints;
import edu.wpi.first.wpilibj.simulation.DCMotorSim;
import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim;
import frc.robot.subsystems.intake.IntakeIO.IntakeIOInputs;

public class IntakeIOSim implements IntakeIO {
public class SimulatedIntake implements IntakeInterface {
DCMotorSim intakeSim = new DCMotorSim(null, DCMotor.getFalcon500(1), 0);
SingleJointedArmSim pivotSim =
new SingleJointedArmSim(
Expand All @@ -22,7 +21,7 @@ public class IntakeIOSim implements IntakeIO {
private double intakeAppliedVolts = 0.0;
private double pivotAppliedVolts = 0.0;

public IntakeIOSim(IntakeIOInputs inputs) {
public SimulatedIntake(IntakeInterfaceInputs inputs) {
intakeSim.update(0.02);
pivotSim.update(0.02);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
import frc.robot.Constants.HardwareConstants;

/** Add your docs here. */
public class PivotIOTalonFX implements PivotIO {
public class PhysicalPivot implements PivotInterface {

private final TalonFX leaderPivotMotor;
private final TalonFX followerPivotMotor;
Expand All @@ -45,7 +45,7 @@ public class PivotIOTalonFX implements PivotIO {

private final VoltageOut voltageControl = new VoltageOut(0);

public PivotIOTalonFX() {
public PhysicalPivot() {
leaderPivotMotor = new TalonFX(PivotConstants.LEADER_PIVOT_MOTOR_ID);
followerPivotMotor = new TalonFX(PivotConstants.FOLLOWER_PIVOT_MOTOR_ID);
pivotEncoder = new CANcoder(PivotConstants.PIVOT_ENCODER_ID);
Expand Down Expand Up @@ -120,7 +120,7 @@ public PivotIOTalonFX() {
* @param inputs inputs for logging
*/
@Override
public void updateInputs(PivotIOInputs inputs) {
public void updateInputs(PivotInterfaceInputs inputs) {
inputs.leaderPosition = leaderPivotMotor.getPosition().getValueAsDouble();
inputs.leaderVelocity = leaderPivotMotor.getVelocity().getValueAsDouble();
inputs.leaderAppliedVolts = leaderPivotMotor.getMotorVoltage().getValueAsDouble();
Expand Down
8 changes: 3 additions & 5 deletions src/main/java/frc/robot/subsystems/pivot/Pivot.java
Original file line number Diff line number Diff line change
@@ -1,21 +1,19 @@
package frc.robot.subsystems.pivot;

import static edu.wpi.first.units.Units.*;

import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.extras.interpolators.SingleLinearInterpolator;
import org.littletonrobotics.junction.Logger;

public class Pivot extends SubsystemBase {
private final PivotIO io;
private final PivotIOInputsAutoLogged inputs = new PivotIOInputsAutoLogged();
private final PivotInterface io;
private final PivotInterfaceInputsAutoLogged inputs = new PivotInterfaceInputsAutoLogged();

private final SingleLinearInterpolator speakerAngleLookupValues;
private final SingleLinearInterpolator speakerOverDefenseAngleLookupValues;
private final SingleLinearInterpolator passAngleLookupValues;

/** Creates a new Pivot. */
public Pivot(PivotIO io) {
public Pivot(PivotInterface io) {
this.io = io;
speakerAngleLookupValues = new SingleLinearInterpolator(PivotConstants.SPEAKER_PIVOT_POSITION);
speakerOverDefenseAngleLookupValues =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,9 @@

import org.littletonrobotics.junction.AutoLog;

public interface PivotIO {
public interface PivotInterface {
@AutoLog
public static class PivotIOInputs {
public static class PivotInterfaceInputs {
public boolean leaderMotorConnected = true;
public boolean followerMotorConnected = true;
public double leaderPosition = 0.0;
Expand All @@ -22,7 +22,7 @@ public static class PivotIOInputs {
public double followerTempCelsius = 0.0;
}

public default void updateInputs(PivotIOInputs inputs) {}
public default void updateInputs(PivotInterfaceInputs inputs) {}

public default double getAngle() {
return 0.0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim;
import frc.robot.Constants.HardwareConstants;

public class PivotIOSim implements PivotIO {
public class SimulatedPivot implements PivotInterface {
private final double pivotGearing = PivotConstants.PIVOT_GEAR_RATIO;
private final double pivotMass = PivotConstants.PIVOT_MASS;
private final double pivotLength = PivotConstants.PIVOT_LENGTH;
Expand All @@ -37,7 +37,7 @@ public class PivotIOSim implements PivotIO {
* @param inputs inputs for logging
*/
@Override
public void updateInputs(PivotIOInputs inputs) {
public void updateInputs(PivotInterfaceInputs inputs) {
pivotSim.update(HardwareConstants.TIMEOUT_S);

inputs.leaderPosition = Units.radiansToRotations(pivotSim.getAngleRads());
Expand Down
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/subsystems/shooter/Flywheel.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,12 +4,12 @@
import org.littletonrobotics.junction.Logger;

public class Flywheel extends SubsystemBase {
private final FlywheelIO io;
private final FlywheelIOInputsAutoLogged inputs = new FlywheelIOInputsAutoLogged();
private final FlywheelInterface io;
private final FlywheelInputsAutoLogged inputs = new FlywheelInputsAutoLogged();

// private final SimpleMotorFeedforward ffModel;

public Flywheel(FlywheelIO io) {
public Flywheel(FlywheelInterface io) {
this.io = io;
}

Expand Down
Loading
Loading