From 17fbc039997709602fb54c2164f527ff138ace54 Mon Sep 17 00:00:00 2001 From: "Keenan D. Buckley" Date: Fri, 27 Mar 2020 13:42:20 -0600 Subject: [PATCH] Changed subsystem variables to private where applicable May need to be changed later, but try to use methods to access these variables instead of accessing them directly, as it fits better with the command based model and will be easier to rewrite should motors change, usage changes, etc. --- .../java/frc4388/robot/subsystems/Drive.java | 16 ++++++++++------ src/main/java/frc4388/robot/subsystems/LED.java | 4 ++-- 2 files changed, 12 insertions(+), 8 deletions(-) diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index a0444f3..3323992 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -27,12 +27,12 @@ public class Drive extends SubsystemBase { // Put methods for controlling this subsystem // here. Call these from Commands. - public WPI_TalonSRX m_leftFrontMotor = new WPI_TalonSRX(DriveConstants.DRIVE_LEFT_FRONT_CAN_ID); - public WPI_TalonSRX m_rightFrontMotor = new WPI_TalonSRX(DriveConstants.DRIVE_RIGHT_FRONT_CAN_ID); - public WPI_TalonSRX m_leftBackMotor = new WPI_TalonSRX(DriveConstants.DRIVE_LEFT_BACK_CAN_ID); - public WPI_TalonSRX m_rightBackMotor = new WPI_TalonSRX(DriveConstants.DRIVE_RIGHT_BACK_CAN_ID); - public DifferentialDrive m_driveTrain = new DifferentialDrive(m_leftFrontMotor, m_rightFrontMotor); - public RobotGyro m_gyro = new RobotGyro(new PigeonIMU(DriveConstants.DRIVE_PIGEON_ID)); + private WPI_TalonSRX m_leftFrontMotor = new WPI_TalonSRX(DriveConstants.DRIVE_LEFT_FRONT_CAN_ID); + private WPI_TalonSRX m_rightFrontMotor = new WPI_TalonSRX(DriveConstants.DRIVE_RIGHT_FRONT_CAN_ID); + private WPI_TalonSRX m_leftBackMotor = new WPI_TalonSRX(DriveConstants.DRIVE_LEFT_BACK_CAN_ID); + private WPI_TalonSRX m_rightBackMotor = new WPI_TalonSRX(DriveConstants.DRIVE_RIGHT_BACK_CAN_ID); + private DifferentialDrive m_driveTrain = new DifferentialDrive(m_leftFrontMotor, m_rightFrontMotor); + private RobotGyro m_gyro = new RobotGyro(new PigeonIMU(DriveConstants.DRIVE_PIGEON_ID)); /** * Add your docs here. @@ -77,6 +77,10 @@ public class Drive extends SubsystemBase { m_driveTrain.arcadeDrive(move, steer); } + public RobotGyro getRobotGyro(){ + return m_gyro; + } + private void updateSmartDashboard() { // Examples of the functionality of RobotGyro diff --git a/src/main/java/frc4388/robot/subsystems/LED.java b/src/main/java/frc4388/robot/subsystems/LED.java index e550623..a2a6f1e 100644 --- a/src/main/java/frc4388/robot/subsystems/LED.java +++ b/src/main/java/frc4388/robot/subsystems/LED.java @@ -20,8 +20,8 @@ import frc4388.utility.LEDPatterns; */ public class LED extends SubsystemBase { - public float currentLED; - public Spark LEDController; + private float currentLED; + private Spark LEDController; /** * Add your docs here.