Skip to content
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

Change file names to match new conventions #72

Open
wants to merge 8 commits into
base: main
Choose a base branch
from
Open
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
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 @@ -168,13 +168,13 @@
() -> JoystickUtil.modifyAxisCubedPolar(driverLeftStickX, driverLeftStickY)[1]
};

DoubleSupplier operatorLeftStickX = operatorController::getLeftX;

Check warning on line 171 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.8.0/pmd_rules_java_bestpractices.html#unusedlocalvariable
DoubleSupplier operatorRightStickY = operatorController::getRightY;

Check warning on line 172 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.8.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 176 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.8.0/pmd_rules_java_bestpractices.html#unusedlocalvariable
Trigger driverLeftDirectionPad = new Trigger(driverController.pov(270));

Check warning on line 177 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.8.0/pmd_rules_java_bestpractices.html#unusedlocalvariable

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

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

public Elevator(ElevatorIO io) {
public Elevator(ElevatorInterface elevatorInterface) {
super("Elevator");
this.io = io;
this.elevatorInterface = elevatorInterface;
}

/**
Expand All @@ -19,7 +19,7 @@ public Elevator(ElevatorIO io) {
*/
public void setElevatorPosition(double position) {
Logger.recordOutput("Elevator", position);
io.setElevatorPosition(position);
elevatorInterface.setElevatorPosition(position);
}

/**
Expand All @@ -28,12 +28,12 @@ public void setElevatorPosition(double position) {
* @param speed output value from -1.0 to 1.0
*/
public void setElevatorSpeed(double speed) {
io.setElevatorSpeed(speed);
elevatorInterface.setElevatorSpeed(speed);
}

@Override
public void periodic() {
io.updateInputs(inputs);
elevatorInterface.updateInputs(inputs);
Logger.processInputs("Elevator", inputs);
}
}
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 ElevatorInputs {
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(ElevatorInputs 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.ElevatorInputs;

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(ElevatorInputs 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(ElevatorInputs inputs) {
elevatorSim.update(0.02);
junocapra marked this conversation as resolved.
Show resolved Hide resolved

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

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

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

/**
Expand All @@ -17,18 +17,18 @@ public Indexer(IndexerIO io) {
* @param speed The desired speed (-1.0 to 1.0)
*/
public void setIndexerSpeed(double speed) {
io.setSpeed(speed);
indexerInterface.setSpeed(speed);
Logger.recordOutput("Indexer", speed);
}

/** Stops the motor */
public void stop() {
io.stop();
indexerInterface.stop();
}

@Override
public void periodic() {
io.updateInputs(inputs);
indexerInterface.updateInputs(inputs);
Logger.processInputs("Indexer", inputs);
}
}
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 IndexerInputs {
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(IndexerInputs 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(IndexerInputs 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(IndexerInputs inputs) {
indexerSim.update(0.02);

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

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

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

/**
Expand All @@ -19,7 +19,7 @@ public Intake(IntakeIO io) {
*/
public void setPivotAngle(double angle) {
double angleRots = Units.degreesToRotations(angle);
io.setPivotPosition(angleRots);
intakeInterface.setPivotPosition(angleRots);
Logger.recordOutput("OTBIntake/Pivot", angleRots);
}

Expand All @@ -29,21 +29,21 @@ public void setPivotAngle(double angle) {
* @param speed intake roller speed (-1.0 to 1.0)
*/
public void setIntakeSpeed(double speed) {
io.setIntakeSpeed(speed);
intakeInterface.setIntakeSpeed(speed);
Logger.recordOutput("OTBIntake/Intake", speed);
}

public void setPivotSpeed(double speed) {
io.setPivotSpeed(speed);
intakeInterface.setPivotSpeed(speed);
}

public void getPivotPosition() {
io.getPivotPosition();
intakeInterface.getPivotPosition();
}

@Override
public void periodic() {
io.updateInputs(inputs);
intakeInterface.updateInputs(inputs);
Logger.processInputs("OTBIntake", inputs);
}
}
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 IntakeInputs {
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(IntakeInputs 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(IntakeInputs 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(IntakeInputs inputs) {
intakeSim.update(0.02);
pivotSim.update(0.02);

Expand Down
Loading
Loading