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 , ADXRS450_Gyro
8+ from wpilib .drive import DifferentialDrive
99import commands2
1010import math
1111
@@ -18,29 +18,28 @@ def __init__(self) -> None:
1818 super ().__init__ ()
1919
2020 # The motors on the left side of the drive.
21- self .leftMotors = wpilib .MotorControllerGroup (
22- wpilib .PWMSparkMax (constants .DriveConstants .kLeftMotor1Port ),
23- wpilib .PWMSparkMax (constants .DriveConstants .kLeftMotor2Port ),
24- )
21+ self .left1 = PWMSparkMax (constants .DriveConstants .kLeftMotor1Port )
22+ self .left2 = PWMSparkMax (constants .DriveConstants .kLeftMotor2Port )
2523
2624 # The motors on the right side of the drive.
27- self .rightMotors = wpilib .MotorControllerGroup (
28- wpilib .PWMSparkMax (constants .DriveConstants .kRightMotor1Port ),
29- wpilib .PWMSparkMax (constants .DriveConstants .kRightMotor2Port ),
30- )
25+ self .right1 = PWMSparkMax (constants .DriveConstants .kRightMotor1Port )
26+ self .right2 = PWMSparkMax (constants .DriveConstants .kRightMotor2Port )
27+
28+ self .left1 .addFollower (self .left2 )
29+ self .right1 .addFollower (self .right2 )
3130
3231 # The robot's drive
33- self .drive = wpilib . drive . DifferentialDrive (self .leftMotors , self .rightMotors )
32+ self .drive = DifferentialDrive (self .left1 , self .right1 )
3433
3534 # The left-side drive encoder
36- self .leftEncoder = wpilib . Encoder (
35+ self .leftEncoder = Encoder (
3736 constants .DriveConstants .kLeftEncoderPorts [0 ],
3837 constants .DriveConstants .kLeftEncoderPorts [1 ],
3938 constants .DriveConstants .kLeftEncoderReversed ,
4039 )
4140
4241 # The right-side drive encoder
43- self .rightEncoder = wpilib . Encoder (
42+ self .rightEncoder = Encoder (
4443 constants .DriveConstants .kRightEncoderPorts [0 ],
4544 constants .DriveConstants .kRightEncoderPorts [1 ],
4645 constants .DriveConstants .kRightEncoderReversed ,
@@ -49,7 +48,7 @@ def __init__(self) -> None:
4948 # We need to invert one side of the drivetrain so that positive voltages
5049 # result in both sides moving forward. Depending on how your robot's
5150 # gearbox is constructed, you might have to invert the left side instead.
52- self .rightMotors .setInverted (True )
51+ self .right1 .setInverted (True )
5352
5453 # Sets the distance per pulse for the encoders
5554 self .leftEncoder .setDistancePerPulse (
@@ -59,7 +58,7 @@ def __init__(self) -> None:
5958 constants .DriveConstants .kEncoderDistancePerPulse
6059 )
6160
62- self .gyro = wpilib . ADXRS450_Gyro ()
61+ self .gyro = ADXRS450_Gyro ()
6362
6463 def arcadeDrive (self , fwd : float , rot : float ):
6564 """
@@ -83,15 +82,15 @@ def getAverageEncoderDistance(self):
8382 """
8483 return (self .leftEncoder .getDistance () + self .rightEncoder .getDistance ()) / 2.0
8584
86- def getLeftEncoder (self ) -> wpilib . Encoder :
85+ def getLeftEncoder (self ) -> Encoder :
8786 """
8887 Gets the left drive encoder.
8988
9089 :returns: the left drive encoder
9190 """
9291 return self .leftEncoder
9392
94- def getRightEncoder (self ) -> wpilib . Encoder :
93+ def getRightEncoder (self ) -> Encoder :
9594 """
9695 Gets the right drive encoder.
9796
0 commit comments