From 65cf0dd3a31b2f5692fe21b9965028514d23a079 Mon Sep 17 00:00:00 2001 From: nathanrsxtn <37890449+nathanrsxtn@users.noreply.github.com> Date: Thu, 28 Apr 2022 01:04:35 -0600 Subject: [PATCH] Add follower drive motors Change bindings to one button per tube Add LiveWindow setup --- build.gradle | 2 +- simgui-ds.json | 85 -------------- simgui-window.json | 60 ---------- simgui.json | 20 ---- src/main/java/frc4388/robot/Constants.java | 18 +-- .../java/frc4388/robot/RobotContainer.java | 110 +++++++----------- src/main/java/frc4388/robot/RobotMap.java | 53 ++++++--- .../java/frc4388/robot/subsystems/Drive.java | 8 +- .../java/frc4388/robot/subsystems/Horn.java | 2 +- .../frc4388/robot/subsystems/Shooter.java | 2 +- 10 files changed, 100 insertions(+), 260 deletions(-) delete mode 100644 simgui-ds.json delete mode 100644 simgui-window.json delete mode 100644 simgui.json diff --git a/build.gradle b/build.gradle index 91f7cb0..a7d1915 100644 --- a/build.gradle +++ b/build.gradle @@ -1,6 +1,6 @@ plugins { id "java" - id "edu.wpi.first.GradleRIO" version "2022.2.1" + id "edu.wpi.first.GradleRIO" version "2022.4.1" } sourceCompatibility = JavaVersion.VERSION_11 diff --git a/simgui-ds.json b/simgui-ds.json deleted file mode 100644 index 763d6fe..0000000 --- a/simgui-ds.json +++ /dev/null @@ -1,85 +0,0 @@ -{ - "keyboardJoysticks": [ - { - "axisConfig": [ - { - "decKey": 65, - "incKey": 68 - }, - { - "decKey": 87, - "incKey": 83 - }, - { - "decKey": 69, - "decayRate": 0.0, - "incKey": 82, - "keyRate": 0.009999999776482582 - } - ], - "axisCount": 3, - "buttonCount": 6, - "buttonKeys": [ - 90, - 88, - 67, - 86, - 66, - 78 - ], - "povConfig": [ - { - "key0": 73, - "key180": 75, - "key270": 74, - "key90": 76 - } - ], - "povCount": 1 - }, - { - "axisCount": 2, - "buttonCount": 4, - "buttonKeys": [ - 77, - 44, - 46, - 47 - ], - "povCount": 0 - }, - { - "axisConfig": [ - { - "decKey": 263, - "incKey": 262 - }, - { - "decKey": 265, - "incKey": 264 - } - ], - "axisCount": 2, - "buttonCount": 6, - "buttonKeys": [ - 260, - 268, - 266, - 261, - 269, - 267 - ], - "povCount": 0 - }, - { - "axisCount": 0, - "buttonCount": 0, - "povCount": 0 - } - ], - "robotJoysticks": [ - { - "guid": "Keyboard0" - } - ] -} diff --git a/simgui-window.json b/simgui-window.json deleted file mode 100644 index 9f80ebe..0000000 --- a/simgui-window.json +++ /dev/null @@ -1,60 +0,0 @@ -{ - "MainWindow": { - "GLOBAL": { - "height": "720", - "maximized": "0", - "style": "0", - "userScale": "2", - "width": "1280", - "xpos": "-1", - "ypos": "-1" - } - }, - "Window": { - "###FMS": { - "Collapsed": "0", - "Pos": "5,540", - "Size": "235,169" - }, - "###Joysticks": { - "Collapsed": "0", - "Pos": "250,465", - "Size": "796,155" - }, - "###Keyboard 0 Settings": { - "Collapsed": "0", - "Pos": "10,50", - "Size": "300,560" - }, - "###NetworkTables": { - "Collapsed": "0", - "Pos": "250,86", - "Size": "750,376" - }, - "###Other Devices": { - "Collapsed": "0", - "Pos": "1025,20", - "Size": "250,695" - }, - "###System Joysticks": { - "Collapsed": "0", - "Pos": "5,350", - "Size": "192,218" - }, - "###Timing": { - "Collapsed": "0", - "Pos": "5,150", - "Size": "135,127" - }, - "Debug##Default": { - "Collapsed": "0", - "Pos": "60,60", - "Size": "400,400" - }, - "Robot State": { - "Collapsed": "0", - "Pos": "5,20", - "Size": "92,99" - } - } -} diff --git a/simgui.json b/simgui.json deleted file mode 100644 index 5861a49..0000000 --- a/simgui.json +++ /dev/null @@ -1,20 +0,0 @@ -{ - "NTProvider": { - "types": { - "/FMSInfo": "FMSInfo", - "/LiveWindow/Drive": "Subsystem", - "/LiveWindow/Horn": "Subsystem", - "/LiveWindow/Shooter": "Subsystem", - "/LiveWindow/Ungrouped/DifferentialDrive[1]": "DifferentialDrive", - "/LiveWindow/Ungrouped/Scheduler": "Scheduler" - } - }, - "NetworkTables": { - "SmartDashboard": { - "Shooter": { - "open": true - }, - "open": true - } - } -} diff --git a/src/main/java/frc4388/robot/Constants.java b/src/main/java/frc4388/robot/Constants.java index 0c9a10c..9599799 100644 --- a/src/main/java/frc4388/robot/Constants.java +++ b/src/main/java/frc4388/robot/Constants.java @@ -11,19 +11,21 @@ package frc4388.robot; */ public final class Constants { public static final class DriveConstants { - public static final int DRIVE_LEFT_CAN_ID = 2; - public static final int DRIVE_RIGHT_CAN_ID = 3; + public static final int DRIVE_LEFT_LEADER_CAN_ID = 2; + public static final int DRIVE_RIGHT_LEADER_CAN_ID = 3; + public static final int DRIVE_LEFT_FOLLOWER_CAN_ID = 4; + public static final int DRIVE_RIGHT_FOLLOWER_CAN_ID = 5; } public static final class ShooterConstants { - public static final int SHOOTER_LOWER_LEFTER_SOLENOID_ID = 1; - public static final int SHOOTER_LOWER_LEFT_SOLENOID_ID = 2; + public static final int SHOOTER_LOWER_LEFTER_SOLENOID_ID = 1; + public static final int SHOOTER_LOWER_LEFT_SOLENOID_ID = 2; public static final int SHOOTER_LOWER_RIGHT_SOLENOID_ID = 3; - public static final int SHOOTER_LOWER_RIGHTER_SOLENOID_ID = 4; - public static final int SHOOTER_UPPER_LEFTER_SOLENOID_ID = 5; - public static final int SHOOTER_UPPER_LEFT_SOLENOID_ID = 6; + public static final int SHOOTER_LOWER_RIGHTER_SOLENOID_ID = 4; + public static final int SHOOTER_UPPER_LEFTER_SOLENOID_ID = 5; + public static final int SHOOTER_UPPER_LEFT_SOLENOID_ID = 6; public static final int SHOOTER_UPPER_RIGHT_SOLENOID_ID = 7; - public static final int SHOOTER_UPPER_RIGHTER_SOLENOID_ID = 8; + public static final int SHOOTER_UPPER_RIGHTER_SOLENOID_ID = 8; } public static final class HornConstants { diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index 73e6476..fbdd020 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -1,11 +1,10 @@ package frc4388.robot; -import edu.wpi.first.networktables.EntryListenerFlags; -import edu.wpi.first.networktables.NetworkTableEntry; -import edu.wpi.first.networktables.NetworkTableInstance; +import edu.wpi.first.util.sendable.Sendable; import edu.wpi.first.wpilibj.GenericHID; import edu.wpi.first.wpilibj.GenericHID.RumbleType; import edu.wpi.first.wpilibj.XboxController; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.CommandGroupBase; import edu.wpi.first.wpilibj2.command.InstantCommand; @@ -30,27 +29,22 @@ public class RobotContainer { private final RobotMap m_robotMap = new RobotMap(); /* Subsystems */ - private final Drive m_robotDrive = new Drive(m_robotMap.driveLeftMotor, m_robotMap.driveRightMotor, m_robotMap.driveBase); - private final Shooter[][] m_robotShooterRows = { - { - new Shooter(m_robotMap.shooterLowerLefterSolenoid), - new Shooter(m_robotMap.shooterLowerLeftSolenoid), - new Shooter(m_robotMap.shooterLowerRightSolenoid), - new Shooter(m_robotMap.shooterLowerRighterSolenoid), - }, - { - new Shooter(m_robotMap.shooterUpperLefterSolenoid), - new Shooter(m_robotMap.shooterUpperLeftSolenoid), - new Shooter(m_robotMap.shooterUpperRightSolenoid), - new Shooter(m_robotMap.shooterUpperRighterSolenoid) - } - }; + private final Drive m_robotDrive = new Drive(m_robotMap.driveLeftLeaderMotor, m_robotMap.driveRightLeaderMotor, m_robotMap.driveBase); + + private final Shooter m_robotShooterLowerLefterSolenoid = new Shooter(m_robotMap.shooterLowerLefterSolenoid); + private final Shooter m_robotShooterLowerLeftSolenoid = new Shooter(m_robotMap.shooterLowerLeftSolenoid); + private final Shooter m_robotShooterLowerRightSolenoid = new Shooter(m_robotMap.shooterLowerRightSolenoid); + private final Shooter m_robotShooterLowerRighterSolenoid = new Shooter(m_robotMap.shooterLowerRighterSolenoid); + + private final Shooter m_robotShooterUpperLefterSolenoid = new Shooter(m_robotMap.shooterUpperLefterSolenoid); + private final Shooter m_robotShooterUpperLeftSolenoid = new Shooter(m_robotMap.shooterUpperLeftSolenoid); + private final Shooter m_robotShooterUpperRightSolenoid = new Shooter(m_robotMap.shooterUpperRightSolenoid); + private final Shooter m_robotShooterUpperRighterSolenoid = new Shooter(m_robotMap.shooterUpperRighterSolenoid); + private final Horn m_robotHorn = new Horn(m_robotMap.hornSolenoid); /* Controllers */ private final XboxController m_controller = new XboxController(OIConstants.CONTROLLER_ID); - private final NetworkTableInteger m_shooterRowIndex = new NetworkTableInteger("Shooter/Row", 0, 0, 1); - private final NetworkTableInteger m_shooterColumnIndex = new NetworkTableInteger("Shooter/Column", 0, 0, 3); /** * The container for the robot. Contains subsystems, OI devices, and commands. @@ -70,57 +64,41 @@ public class RobotContainer { * {@link edu.wpi.first.wpilibj2.command.button.JoystickButton}. */ private void configureButtonBindings() { - // B Button: Fire Selected Shooter - new JoystickButton(getController(), XboxController.Button.kB.value).whenPressed(this::fireShooterWithFeedback); - // A Button: Sound Horn - new JoystickButton(getController(), XboxController.Button.kA.value).whenPressed(() -> m_robotHorn.set(true)).whenReleased(() -> m_robotHorn.set(false)); - // Right Bumper: Shift Column Selection Right - new JoystickButton(getController(), XboxController.Button.kRightBumper.value).whenPressed(() -> m_shooterColumnIndex.set(m_shooterColumnIndex.get() + 1)); - // Left Bumper: Shift Column Selection Left - new JoystickButton(getController(), XboxController.Button.kLeftBumper.value).whenPressed(() -> m_shooterColumnIndex.set(m_shooterColumnIndex.get() - 1)); - // D-Pad Down: Select Lower Shooter Row - new POVButton(getController(), 180).whenPressed(() -> m_shooterRowIndex.set(0)); - // D-Pad Up: Select Upper Shooter Row - new POVButton(getController(), 0).whenPressed(() -> m_shooterRowIndex.set(1)); - // D-Pad Left: Select Righter Shooter Column - new POVButton(getController(), 90).whenPressed(() -> m_shooterColumnIndex.set(3)); - // D-Pad Right: Select Lefter Shooter Column - new POVButton(getController(), 270).whenPressed(() -> m_shooterColumnIndex.set(0)); + // Y Button: Fire Upper Lefter Shooter + new JoystickButton(getController(), XboxController.Button.kY.value).whenPressed(putToDashboard("Y", new InstantCommand(() -> fireShooterWithFeedback(m_robotShooterUpperLefterSolenoid)).withName("Fire Upper Lefter"))); + // B Button: Fire Upper Right Shooter + new JoystickButton(getController(), XboxController.Button.kB.value).whenPressed(putToDashboard("B", new InstantCommand(() -> fireShooterWithFeedback(m_robotShooterUpperRightSolenoid)).withName("Fire Upper Right"))); + // A Button: Fire Upper Righter Shooter + new JoystickButton(getController(), XboxController.Button.kA.value).whenPressed(putToDashboard("A", new InstantCommand(() -> fireShooterWithFeedback(m_robotShooterUpperRighterSolenoid)).withName("Fire Upper Righter"))); + // X Button: Fire Upper Left Shooter + new JoystickButton(getController(), XboxController.Button.kX.value).whenPressed(putToDashboard("X", new InstantCommand(() -> fireShooterWithFeedback(m_robotShooterUpperLeftSolenoid)).withName("Fire Upper Left"))); + + // D-Pad Up: Fire Lower Lefter Shooter + new POVButton(getController(), 0).whenPressed(putToDashboard("Up", new InstantCommand(() -> fireShooterWithFeedback(m_robotShooterLowerLefterSolenoid)).withName("Fire Lower Lefter"))); + // D-Pad Right: Fire Lower Right Shooter + new POVButton(getController(), 90).whenPressed(putToDashboard("Right", new InstantCommand(() -> fireShooterWithFeedback(m_robotShooterLowerRightSolenoid)).withName("Fire Lower Right"))); + // D-Pad Left: Fire Lower Righter Shooter + new POVButton(getController(), 180).whenPressed(putToDashboard("Down", new InstantCommand(() -> fireShooterWithFeedback(m_robotShooterLowerRighterSolenoid)).withName("Fire Lower Righter"))); + // D-Pad Up: Fire Lower Left Shooter + new POVButton(getController(), 270).whenPressed(putToDashboard("Left", new InstantCommand(() -> fireShooterWithFeedback(m_robotShooterLowerLeftSolenoid)).withName("Fire Lower Left"))); + + // Right Bumper: Sound Horn + new JoystickButton(getController(), XboxController.Button.kRightBumper.value).whenPressed(() -> m_robotHorn.set(true)).whenReleased(() -> m_robotHorn.set(false)); + // Left Bumper: Sound Horn + new JoystickButton(getController(), XboxController.Button.kLeftBumper.value).whenPressed(() -> m_robotHorn.set(true)).whenReleased(() -> m_robotHorn.set(false)); } - private void fireShooterWithFeedback() { - boolean fired = m_robotShooterRows[m_shooterRowIndex.get()][m_shooterColumnIndex.get()].set(true); - RumbleType rumbleType = m_shooterColumnIndex.get() < 2 ? RumbleType.kLeftRumble : RumbleType.kRightRumble; + private static T putToDashboard(String key, T data) { + SmartDashboard.putData(key, data); + return data; + } + + private void fireShooterWithFeedback(Shooter shooter) { + boolean fired = shooter.set(true); + RumbleType rumbleType = shooter.getName().contains("Left") ? RumbleType.kLeftRumble : RumbleType.kRightRumble; double value = fired ? 0.3 : 0.6; double duration = fired ? 0.3 : 0.4; CommandGroupBase.sequence(new InstantCommand(() -> getController().setRumble(rumbleType, value)), new WaitCommand(duration), new InstantCommand(() -> getController().setRumble(rumbleType, 0.0))).schedule(); - System.out.println(m_shooterRowIndex.get() + ":" + m_shooterColumnIndex.get()); - } - - private static class NetworkTableInteger { - private final NetworkTableEntry m_entry; - private final int m_defaultValue; - - public NetworkTableInteger(String name, int defaultValue, int minValue, int maxValue) { - m_defaultValue = defaultValue; - m_entry = NetworkTableInstance.getDefault().getTable("SmartDashboard").getEntry(name); - m_entry.setDouble(m_defaultValue); - m_entry.addListener(event -> { - if (event.value.isDouble()) { - double entryValue = event.value.getDouble(); - double safeValue = Math.max(minValue, Math.min((int) entryValue, maxValue)); - if (entryValue != safeValue) event.getEntry().setDouble(safeValue); - } else event.getEntry().setDouble(m_defaultValue); - }, EntryListenerFlags.kImmediate | EntryListenerFlags.kNew | EntryListenerFlags.kUpdate); - } - - public int get() { - return (int) m_entry.getDouble(m_defaultValue); - } - - public void set(int value) { - m_entry.setDouble(value); - } } /** diff --git a/src/main/java/frc4388/robot/RobotMap.java b/src/main/java/frc4388/robot/RobotMap.java index 17ba0b1..2283460 100644 --- a/src/main/java/frc4388/robot/RobotMap.java +++ b/src/main/java/frc4388/robot/RobotMap.java @@ -14,39 +14,49 @@ import static frc4388.robot.Constants.ShooterConstants.*; import com.ctre.phoenix.motorcontrol.NeutralMode; import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX; +import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.PneumaticsModuleType; import edu.wpi.first.wpilibj.Solenoid; import edu.wpi.first.wpilibj.drive.DifferentialDrive; /** - * Defines and holds all I/O objects on the Roborio. This is useful for unit testing and + * Defines and holds all I/O objects on the roboRIO. This is useful for unit testing and * modularization. */ public class RobotMap { public RobotMap() { configureDriveMotorControllers(); + configureLiveWindow(); } /* Drive Subsystem */ - public final WPI_TalonSRX driveLeftMotor = new WPI_TalonSRX(DRIVE_LEFT_CAN_ID); - public final WPI_TalonSRX driveRightMotor = new WPI_TalonSRX(DRIVE_RIGHT_CAN_ID); - public final DifferentialDrive driveBase = new DifferentialDrive(driveLeftMotor, driveRightMotor); + public final WPI_TalonSRX driveLeftLeaderMotor = new WPI_TalonSRX(DRIVE_LEFT_LEADER_CAN_ID); + public final WPI_TalonSRX driveRightLeaderMotor = new WPI_TalonSRX(DRIVE_RIGHT_LEADER_CAN_ID); + public final WPI_TalonSRX driveLeftFollowerMotor = new WPI_TalonSRX(DRIVE_LEFT_FOLLOWER_CAN_ID); + public final WPI_TalonSRX driveRightFollowerMotor = new WPI_TalonSRX(DRIVE_RIGHT_FOLLOWER_CAN_ID); - void configureDriveMotorControllers() { - /* factory default values */ - driveLeftMotor.configFactoryDefault(); - driveRightMotor.configFactoryDefault(); + public final DifferentialDrive driveBase = new DifferentialDrive(driveLeftLeaderMotor, driveRightLeaderMotor); - /* set neutral mode */ - driveLeftMotor.setNeutralMode(NeutralMode.Brake); - driveRightMotor.setNeutralMode(NeutralMode.Brake); + private void configureDriveMotorControllers() { + driveLeftLeaderMotor.configFactoryDefault(); + driveRightLeaderMotor.configFactoryDefault(); + driveLeftFollowerMotor.configFactoryDefault(); + driveRightFollowerMotor.configFactoryDefault(); + + driveLeftLeaderMotor.setNeutralMode(NeutralMode.Brake); + driveRightLeaderMotor.setNeutralMode(NeutralMode.Brake); + driveLeftFollowerMotor.setNeutralMode(NeutralMode.Brake); + driveRightFollowerMotor.setNeutralMode(NeutralMode.Brake); + + driveLeftFollowerMotor.follow(driveLeftLeaderMotor); + driveRightFollowerMotor.follow(driveRightLeaderMotor); } - /* Horn subsystem */ + /* Horn Subsystem */ public final Solenoid hornSolenoid = new Solenoid(PneumaticsModuleType.REVPH, HORN_SOLENOID_ID); - /* Shooter subsystem */ + /* Shooter Subsystem */ public final Solenoid shooterLowerLefterSolenoid = new Solenoid(PneumaticsModuleType.REVPH, SHOOTER_LOWER_LEFTER_SOLENOID_ID); public final Solenoid shooterLowerLeftSolenoid = new Solenoid(PneumaticsModuleType.REVPH, SHOOTER_LOWER_LEFT_SOLENOID_ID); public final Solenoid shooterLowerRightSolenoid = new Solenoid(PneumaticsModuleType.REVPH, SHOOTER_LOWER_RIGHT_SOLENOID_ID); @@ -56,4 +66,21 @@ public class RobotMap { public final Solenoid shooterUpperRightSolenoid = new Solenoid(PneumaticsModuleType.REVPH, SHOOTER_UPPER_RIGHT_SOLENOID_ID); public final Solenoid shooterUpperRighterSolenoid = new Solenoid(PneumaticsModuleType.REVPH, SHOOTER_UPPER_RIGHTER_SOLENOID_ID); + + private void configureLiveWindow() { + SendableRegistry.setName(driveLeftFollowerMotor, "Drive", "Left Follower Motor"); + SendableRegistry.setName(driveRightFollowerMotor, "Drive", "Right Follower Motor"); + SendableRegistry.setName(driveBase, "Drive", "Drive Base"); + + SendableRegistry.setName(hornSolenoid, "Horn", "Solenoid"); + + SendableRegistry.setName(shooterLowerLefterSolenoid, "Shooter", "Lower Lefter Solenoid"); + SendableRegistry.setName(shooterLowerLeftSolenoid, "Shooter", "Lower Left Solenoid"); + SendableRegistry.setName(shooterLowerRightSolenoid, "Shooter", "Lower Right Solenoid"); + SendableRegistry.setName(shooterLowerRighterSolenoid, "Shooter", "Lower Righter Solenoid"); + SendableRegistry.setName(shooterUpperLefterSolenoid, "Shooter", "Upper Lefter Solenoid"); + SendableRegistry.setName(shooterUpperLeftSolenoid, "Shooter", "Upper Left Solenoid"); + SendableRegistry.setName(shooterUpperRightSolenoid, "Shooter", "Upper Right Solenoid"); + SendableRegistry.setName(shooterUpperRighterSolenoid, "Shooter", "Upper Righter Solenoid"); + } } diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 2fd869f..2496e2f 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -6,16 +6,14 @@ import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj2.command.SubsystemBase; public class Drive extends SubsystemBase { - private WPI_TalonSRX m_leftMotor; - private WPI_TalonSRX m_rightMotor; - private DifferentialDrive m_driveBase; + private final WPI_TalonSRX m_leftMotor; + private final WPI_TalonSRX m_rightMotor; + private final DifferentialDrive m_driveBase; public Drive(WPI_TalonSRX leftMotor, WPI_TalonSRX rightMotor, DifferentialDrive driveBase) { m_leftMotor = leftMotor; m_rightMotor = rightMotor; m_driveBase = driveBase; - addChild("Left Motor", m_leftMotor); - addChild("Right Motor", m_rightMotor); } public void arcadeDrive(double xSpeed, double zRotation) { diff --git a/src/main/java/frc4388/robot/subsystems/Horn.java b/src/main/java/frc4388/robot/subsystems/Horn.java index fd3039c..d532fa0 100644 --- a/src/main/java/frc4388/robot/subsystems/Horn.java +++ b/src/main/java/frc4388/robot/subsystems/Horn.java @@ -4,7 +4,7 @@ import edu.wpi.first.wpilibj.Solenoid; import edu.wpi.first.wpilibj2.command.SubsystemBase; public class Horn extends SubsystemBase { - private Solenoid m_solenoid; + private final Solenoid m_solenoid; public Horn(Solenoid solenoid) { m_solenoid = solenoid; diff --git a/src/main/java/frc4388/robot/subsystems/Shooter.java b/src/main/java/frc4388/robot/subsystems/Shooter.java index 84f4d30..fc2afec 100644 --- a/src/main/java/frc4388/robot/subsystems/Shooter.java +++ b/src/main/java/frc4388/robot/subsystems/Shooter.java @@ -4,7 +4,7 @@ import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.wpilibj.Solenoid; public class Shooter extends SubsystemBase { - Solenoid m_solenoid; + private final Solenoid m_solenoid; public Shooter(Solenoid solenoid) { m_solenoid = solenoid;