From f47b22086c68f2c4d949b982b1e8357c55633a13 Mon Sep 17 00:00:00 2001 From: Hayden Heroux Date: Mon, 8 Apr 2024 23:53:44 -0400 Subject: [PATCH] refactor: Remove motors. --- simgui.json | 7 +++++-- src/main/java/frc/robot/intake/Intake.java | 4 ++-- src/main/java/frc/robot/shooter/Shooter.java | 4 ++-- src/main/java/frc/robot/shooter/ShooterFactory.java | 12 ++++++------ 4 files changed, 15 insertions(+), 12 deletions(-) diff --git a/simgui.json b/simgui.json index f2add02..49c93c2 100644 --- a/simgui.json +++ b/simgui.json @@ -58,9 +58,13 @@ "Position": { "open": true }, + "Shoulder": { + "open": true + }, "Velocities": { "open": true - } + }, + "open": true }, "Climber": { "East": { @@ -99,7 +103,6 @@ "Measurement": { "open": true }, - "open": true, "setpoint": { "open": true } diff --git a/src/main/java/frc/robot/intake/Intake.java b/src/main/java/frc/robot/intake/Intake.java index e46d187..5012d5e 100644 --- a/src/main/java/frc/robot/intake/Intake.java +++ b/src/main/java/frc/robot/intake/Intake.java @@ -13,10 +13,10 @@ public class Intake extends Subsystem { /** Instance variable for the intake subsystem singleton. */ private static Intake instance = null; - /** Roller motors. */ + /** Rollers. */ private final VelocityControllerIO frontRoller, backRoller; - /** Roller motor values. */ + /** Roller values. */ private final VelocityControllerIOValues frontRollerValues, backRollerValues; /** Creates a new instance of the intake subsystem. */ diff --git a/src/main/java/frc/robot/shooter/Shooter.java b/src/main/java/frc/robot/shooter/Shooter.java index f526ae9..ffd5b5b 100644 --- a/src/main/java/frc/robot/shooter/Shooter.java +++ b/src/main/java/frc/robot/shooter/Shooter.java @@ -27,11 +27,11 @@ public class Shooter extends Subsystem { /** Creates a new instance of the shooter subsystem. */ private Shooter() { - serializer = ShooterFactory.createSerializerMotor(); + serializer = ShooterFactory.createSerializer(); serializerValues = new VelocityControllerIOValues(); serializer.configure(SerializerConstants.CONTROLLER_CONSTANTS); - flywheel = ShooterFactory.createFlywheelMotor(); + flywheel = ShooterFactory.createFlywheel(); flywheelValues = new VelocityControllerIOValues(); flywheel.configure(FlywheelConstants.CONTROLLER_CONSTANTS); } diff --git a/src/main/java/frc/robot/shooter/ShooterFactory.java b/src/main/java/frc/robot/shooter/ShooterFactory.java index a0fdea7..27eb8ba 100644 --- a/src/main/java/frc/robot/shooter/ShooterFactory.java +++ b/src/main/java/frc/robot/shooter/ShooterFactory.java @@ -13,11 +13,11 @@ public class ShooterFactory { /** - * Creates a serializer motor. + * Creates a serializer. * - * @return a serializer motor. + * @return a serializer. */ - public static VelocityControllerIO createSerializerMotor() { + public static VelocityControllerIO createSerializer() { if (Robot.isReal() && RobotConstants.REAL_SUBSYSTEMS.contains(Subsystem.SHOOTER)) { return new VelocityControllerIOTalonFXPIDF(SerializerConstants.CAN, SerializerConstants.PIDF); } @@ -26,11 +26,11 @@ public static VelocityControllerIO createSerializerMotor() { } /** - * Creates a flywheel motor. + * Creates a flywheel. * - * @return a flywheel motor. + * @return a flywheel. */ - public static VelocityControllerIO createFlywheelMotor() { + public static VelocityControllerIO createFlywheel() { if (Robot.isReal() && RobotConstants.REAL_SUBSYSTEMS.contains(Subsystem.SHOOTER)) { return new VelocityControllerIOTalonFXPIDF(FlywheelConstants.CAN, FlywheelConstants.PIDF); }