From fbc485190a33c48a3bfdf911c33359d61dfdedd9 Mon Sep 17 00:00:00 2001 From: LeonardAbbas Date: Sat, 1 Oct 2022 07:51:29 -0700 Subject: [PATCH] refactor: made leftMotors a member variable and cleaned up DriveSubsystem --- .../java/frc/robot/subsystems/DriveSubsystem.java | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/DriveSubsystem.java b/src/main/java/frc/robot/subsystems/DriveSubsystem.java index 508f757..d9e5eff 100644 --- a/src/main/java/frc/robot/subsystems/DriveSubsystem.java +++ b/src/main/java/frc/robot/subsystems/DriveSubsystem.java @@ -14,10 +14,15 @@ /** Subsystem that controls the drivetrain of the robot. */ public class DriveSubsystem extends SubsystemBase { + private final MotorControllerGroup m_leftMotors = new MotorControllerGroup( + new WPI_TalonSRX(DriveConstants.kLeftMotor1Port), + new WPI_TalonSRX(DriveConstants.kLeftMotor2Port)); + private final MotorControllerGroup m_rightMotors = new MotorControllerGroup( - new WPI_TalonSRX(DriveConstants.kRightMotor1Port), new WPI_TalonSRX(DriveConstants.kRightMotor2Port)); + new WPI_TalonSRX(DriveConstants.kRightMotor1Port), + new WPI_TalonSRX(DriveConstants.kRightMotor2Port)); - private final DifferentialDrive m_drive; + private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotors, m_rightMotors); private double m_fwd, m_rot, m_maxOutput; @@ -26,10 +31,6 @@ public class DriveSubsystem extends SubsystemBase { */ public DriveSubsystem() { m_rightMotors.setInverted(true); - m_drive = new DifferentialDrive( - new MotorControllerGroup( - new WPI_TalonSRX(DriveConstants.kLeftMotor1Port), new WPI_TalonSRX(DriveConstants.kLeftMotor2Port)), - m_rightMotors); } /**