4
4
# the WPILib BSD license file in the root directory of this project.
5
5
#
6
6
7
- import wpilib
8
- import wpilib .drive
7
+ from wpilib import PWMSparkMax , Encoder , ADXRS450_Gyro
8
+ from wpilib .drive import DifferentialDrive
9
9
import commands2
10
10
import math
11
11
@@ -18,29 +18,28 @@ def __init__(self) -> None:
18
18
super ().__init__ ()
19
19
20
20
# 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 )
25
23
26
24
# 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 )
31
30
32
31
# The robot's drive
33
- self .drive = wpilib . drive . DifferentialDrive (self .leftMotors , self .rightMotors )
32
+ self .drive = DifferentialDrive (self .left1 , self .right1 )
34
33
35
34
# The left-side drive encoder
36
- self .leftEncoder = wpilib . Encoder (
35
+ self .leftEncoder = Encoder (
37
36
constants .DriveConstants .kLeftEncoderPorts [0 ],
38
37
constants .DriveConstants .kLeftEncoderPorts [1 ],
39
38
constants .DriveConstants .kLeftEncoderReversed ,
40
39
)
41
40
42
41
# The right-side drive encoder
43
- self .rightEncoder = wpilib . Encoder (
42
+ self .rightEncoder = Encoder (
44
43
constants .DriveConstants .kRightEncoderPorts [0 ],
45
44
constants .DriveConstants .kRightEncoderPorts [1 ],
46
45
constants .DriveConstants .kRightEncoderReversed ,
@@ -49,7 +48,7 @@ def __init__(self) -> None:
49
48
# We need to invert one side of the drivetrain so that positive voltages
50
49
# result in both sides moving forward. Depending on how your robot's
51
50
# gearbox is constructed, you might have to invert the left side instead.
52
- self .rightMotors .setInverted (True )
51
+ self .right1 .setInverted (True )
53
52
54
53
# Sets the distance per pulse for the encoders
55
54
self .leftEncoder .setDistancePerPulse (
@@ -59,7 +58,7 @@ def __init__(self) -> None:
59
58
constants .DriveConstants .kEncoderDistancePerPulse
60
59
)
61
60
62
- self .gyro = wpilib . ADXRS450_Gyro ()
61
+ self .gyro = ADXRS450_Gyro ()
63
62
64
63
def arcadeDrive (self , fwd : float , rot : float ):
65
64
"""
@@ -83,15 +82,15 @@ def getAverageEncoderDistance(self):
83
82
"""
84
83
return (self .leftEncoder .getDistance () + self .rightEncoder .getDistance ()) / 2.0
85
84
86
- def getLeftEncoder (self ) -> wpilib . Encoder :
85
+ def getLeftEncoder (self ) -> Encoder :
87
86
"""
88
87
Gets the left drive encoder.
89
88
90
89
:returns: the left drive encoder
91
90
"""
92
91
return self .leftEncoder
93
92
94
- def getRightEncoder (self ) -> wpilib . Encoder :
93
+ def getRightEncoder (self ) -> Encoder :
95
94
"""
96
95
Gets the right drive encoder.
97
96
0 commit comments