44# the WPILib BSD license file in the root directory of this project.
55#
66
7- import wpilib
8- import wpilib .drive
7+ from wpilib import PWMSparkMax , Encoder
8+ from wpilib .drive import DifferentialDrive
99import commands2
1010
1111import constants
@@ -15,31 +15,30 @@ class DriveSubsystem(commands2.Subsystem):
1515 # Creates a new DriveSubsystem
1616 def __init__ (self ) -> None :
1717 super ().__init__ ()
18+
19+ # The motors on the left side of the drive.
20+ self .left1 = PWMSparkMax (constants .DriveConstants .kLeftMotor1Port )
21+ self .left2 = PWMSparkMax (constants .DriveConstants .kLeftMotor2Port )
1822
19- # The motors on the left side of the drive
20- self .left_motors = wpilib .MotorControllerGroup (
21- wpilib .PWMSparkMax (constants .DriveConstants .kLeftMotor1Port ),
22- wpilib .PWMSparkMax (constants .DriveConstants .kLeftMotor2Port ),
23- )
23+ # The motors on the right side of the drive.
24+ self .right1 = PWMSparkMax (constants .DriveConstants .kRightMotor1Port )
25+ self .right2 = PWMSparkMax (constants .DriveConstants .kRightMotor2Port )
2426
25- # The motors on the right side of the drive
26- self .right_motors = wpilib .MotorControllerGroup (
27- wpilib .PWMSparkMax (constants .DriveConstants .kRightMotor1Port ),
28- wpilib .PWMSparkMax (constants .DriveConstants .kRightMotor2Port ),
29- )
27+ self .left1 .addFollower (self .left2 )
28+ self .right1 .addFollower (self .right2 )
3029
3130 # The robot's drive
32- self .drive = wpilib . drive . DifferentialDrive (self .left_motors , self .right_motors )
31+ self .drive = DifferentialDrive (self .left1 , self .right1 )
3332
3433 # The left-side drive encoder
35- self .left_encoder = wpilib . Encoder (
34+ self .left_encoder = Encoder (
3635 constants .DriveConstants .kLeftEncoderPorts [0 ],
3736 constants .DriveConstants .kLeftEncoderPorts [1 ],
3837 constants .DriveConstants .kLeftEncoderReversed ,
3938 )
4039
4140 # The right-side drive encoder
42- self .right_encoder = wpilib . Encoder (
41+ self .right_encoder = Encoder (
4342 constants .DriveConstants .kRightEncoderPorts [0 ],
4443 constants .DriveConstants .kRightEncoderPorts [1 ],
4544 constants .DriveConstants .kRightEncoderReversed ,
@@ -56,7 +55,7 @@ def __init__(self) -> None:
5655 # We need to invert one side of the drivetrain so that positive voltages
5756 # result in both sides moving forward. Depending on how your robot's
5857 # gearbox is constructed, you might have to invert the left side instead.
59- self .right_motors .setInverted (True )
58+ self .right1 .setInverted (True )
6059
6160 def arcadeDrive (self , fwd : float , rot : float ) -> None :
6261 """Drives the robot using arcade controls.
@@ -80,14 +79,14 @@ def getAverageEncoderDistance(self) -> float:
8079 self .left_encoder .getDistance () + self .right_encoder .getDistance ()
8180 ) / 2.0
8281
83- def getLeftEncoder (self ) -> wpilib . Encoder :
82+ def getLeftEncoder (self ) -> Encoder :
8483 """Gets the left drive encoder.
8584
8685 :returns: the left drive encoder
8786 """
8887 return self .left_encoder
8988
90- def getRightEncoder (self ) -> wpilib . Encoder :
89+ def getRightEncoder (self ) -> Encoder :
9190 """Gets the right drive encoder.
9291
9392 :returns: the right drive encoder
0 commit comments