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

refactor: clean up DriveSubsystem #21

Open
wants to merge 2 commits into
base: main
Choose a base branch
from
Open
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
13 changes: 7 additions & 6 deletions src/main/java/frc/robot/subsystems/DriveSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand All @@ -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);
}

/**
Expand Down