66
77from commands2 import Subsystem
88
9- from wpilib import MotorControllerGroup , PWMSparkMax , Encoder , ADXRS450_Gyro
9+ from wpilib import PWMSparkMax , Encoder , ADXRS450_Gyro
1010from wpilib .drive import DifferentialDrive
1111
1212from wpimath .kinematics import DifferentialDriveOdometry , DifferentialDriveWheelSpeeds
@@ -19,19 +19,23 @@ def __init__(self):
1919 super ().__init__ ()
2020
2121 # The motors on the left side of the drive.
22- self .leftMotors = MotorControllerGroup (
23- PWMSparkMax (constants .kLeftMotor1Port ),
24- PWMSparkMax (constants .kLeftMotor2Port ),
25- )
22+ self .left1 = PWMSparkMax (constants .kLeftMotor1Port )
23+ self .left2 = PWMSparkMax (constants .kLeftMotor2Port )
2624
2725 # The motors on the right side of the drive.
28- self .rightMotors = MotorControllerGroup (
29- PWMSparkMax (constants .kRightMotor1Port ),
30- PWMSparkMax (constants .kRightMotor2Port ),
31- )
26+ self .right1 = PWMSparkMax (constants .kRightMotor1Port )
27+ self .right2 = PWMSparkMax (constants .kRightMotor2Port )
28+
29+ self .left1 .addFollower (self .left2 )
30+ self .right1 .addFollower (self .right2 )
3231
3332 # The robot's drive
34- self .drive = DifferentialDrive (self .leftMotors , self .rightMotors )
33+ self .drive = DifferentialDrive (self .left1 , self .right1 )
34+
35+ # We need to invert one side of the drivetrain so that positive voltages
36+ # result in both sides moving forward. Depending on how your robot's
37+ # gearbox is constructed, you might have to invert the left side instead.
38+ self .right1 .setInverted (True )
3539
3640 # The left-side drive encoder
3741 self .leftEncoder = Encoder (
@@ -50,10 +54,7 @@ def __init__(self):
5054 # The gyro sensor
5155 self .gyro = ADXRS450_Gyro ()
5256
53- # We need to invert one side of the drivetrain so that positive voltages
54- # result in both sides moving forward. Depending on how your robot's
55- # gearbox is constructed, you might have to invert the left side instead.
56- self .rightMotors .setInverted (True )
57+
5758
5859 # Sets the distance per pulse for the encoders
5960 self .leftEncoder .setDistancePerPulse (constants .kEncoderDistancePerPulse )
@@ -101,8 +102,8 @@ def arcadeDrive(self, fwd, rot):
101102
102103 def tankDriveVolts (self , leftVolts , rightVolts ):
103104 """Controls the left and right sides of the drive directly with voltages."""
104- self .leftMotors .setVoltage (leftVolts )
105- self .rightMotors .setVoltage (rightVolts )
105+ self .left1 .setVoltage (leftVolts )
106+ self .right1 .setVoltage (rightVolts )
106107 self .drive .feed ()
107108
108109 def resetEncoders (self ):
0 commit comments