Skip to content

Commit 242924b

Browse files
authored
Update examples using MotorControllerGroup (#130)
Based on wpilibsuite/allwpilib#6053, I updated the following examples: - Armbot - ArmBotOffboard - DifferentialDriveBot - GyroDriveCommands - FrisbeeBot - HatchbotInlined - HatchbotTraditional - RamseteCommand - RamseteController These are all of the available examples from said PR that could be updated.
1 parent 7d601c3 commit 242924b

File tree

9 files changed

+124
-118
lines changed

9 files changed

+124
-118
lines changed

ArmBot/subsystems/drivesubsystem.py

Lines changed: 17 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -4,8 +4,8 @@
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
99
import commands2
1010

1111
import constants
@@ -16,30 +16,29 @@ class DriveSubsystem(commands2.Subsystem):
1616
def __init__(self) -> None:
1717
super().__init__()
1818

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-
)
19+
# The motors on the left side of the drive.
20+
self.left1 = PWMSparkMax(constants.DriveConstants.kLeftMotor1Port)
21+
self.left2 = PWMSparkMax(constants.DriveConstants.kLeftMotor2Port)
2422

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-
)
23+
# The motors on the right side of the drive.
24+
self.right1 = PWMSparkMax(constants.DriveConstants.kRightMotor1Port)
25+
self.right2 = PWMSparkMax(constants.DriveConstants.kRightMotor2Port)
26+
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

ArmBotOffboard/subsystems/drivesubsystem.py

Lines changed: 20 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -4,42 +4,43 @@
44
# the WPILib BSD license file in the root directory of this project.
55
#
66

7+
import typing
8+
79
import commands2
810
import commands2.cmd
11+
from wpilib import PWMSparkMax, Encoder
12+
from wpilib.drive import DifferentialDrive
13+
914
import constants
10-
import wpilib
11-
import wpilib.drive
12-
import typing
1315

1416

1517
class DriveSubsystem(commands2.Subsystem):
1618
def __init__(self) -> None:
1719
super().__init__()
1820

1921
# The motors on the left side of the drive.
20-
self.left = wpilib.MotorControllerGroup(
21-
wpilib.PWMSparkMax(constants.kLeftMotor1Port),
22-
wpilib.PWMSparkMax(constants.kLeftMotor2Port),
23-
)
22+
self.left1 = PWMSparkMax(constants.kLeftMotor1Port)
23+
self.left2 = PWMSparkMax(constants.kLeftMotor2Port)
2424

2525
# The motors on the right side of the drive.
26-
self.right = wpilib.MotorControllerGroup(
27-
wpilib.PWMSparkMax(constants.kRightMotor1Port),
28-
wpilib.PWMSparkMax(constants.kRightMotor2Port),
29-
)
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)
3031

3132
# The robot's drive
32-
self.drive = wpilib.drive.DifferentialDrive(self.left, self.right)
33+
self.drive = DifferentialDrive(self.left1, self.right1)
3334

3435
# The left-side drive encoder
35-
self.left_encoder = wpilib.Encoder(
36+
self.left_encoder = Encoder(
3637
constants.kLeftEncoderPorts[0],
3738
constants.kLeftEncoderPorts[1],
3839
constants.kLeftEncoderReversed,
3940
)
4041

4142
# The right-side drive encoder
42-
self.right_encoder = wpilib.Encoder(
43+
self.right_encoder = Encoder(
4344
constants.kRightEncoderPorts[0],
4445
constants.kRightEncoderPorts[1],
4546
constants.kRightEncoderReversed,
@@ -52,7 +53,7 @@ def __init__(self) -> None:
5253
# We need to invert one side of the drivetrain so that positive voltages
5354
# result in both sides moving forward. Depending on how your robot's
5455
# gearbox is constructed, you might have to invert the left side instead.
55-
self.right.setInverted(True)
56+
self.right1.setInverted(True)
5657

5758
def arcadeDriveCommand(
5859
self, fwd: typing.Callable[[], float], rot: typing.Callable[[], float]
@@ -71,8 +72,8 @@ def arcadeDriveCommand(
7172

7273
def resetEncoders(self) -> None:
7374
"""Resets the drive encoders to currently read a position of 0."""
74-
self.left.reset()
75-
self.right.reset()
75+
self.left_encoder.reset()
76+
self.right_encoder.reset()
7677

7778
def getAverageEncoderDistance(self) -> float:
7879
"""Gets the average distance of the two encoders.
@@ -82,15 +83,15 @@ def getAverageEncoderDistance(self) -> float:
8283
"""
8384
return (self.left_encoder.getDistance() + self.right_encoder.getDistance()) / 2
8485

85-
def getLeftEncoder(self) -> wpilib.Encoder:
86+
def getLeftEncoder(self) -> Encoder:
8687
"""Gets the left drive encoder.
8788
8889
Returns:
8990
The left drive encoder.
9091
"""
9192
return self.left_encoder
9293

93-
def getRightEncoder(self) -> wpilib.Encoder:
94+
def getRightEncoder(self) -> Encoder:
9495
"""Gets the right drive encoder.
9596
9697
Returns:

DifferentialDriveBot/drivetrain.py

Lines changed: 16 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -23,17 +23,23 @@ class Drivetrain:
2323
ENCODER_RESOLUTION = 4096 # counts per revolution
2424

2525
def __init__(self):
26-
leftLeader = wpilib.PWMSparkMax(1)
27-
leftFollower = wpilib.PWMSparkMax(2)
28-
rightLeader = wpilib.PWMSparkMax(3)
29-
rightFollower = wpilib.PWMSparkMax(4)
26+
self.leftLeader = wpilib.PWMSparkMax(1)
27+
self.leftFollower = wpilib.PWMSparkMax(2)
28+
self.rightLeader = wpilib.PWMSparkMax(3)
29+
self.rightFollower = wpilib.PWMSparkMax(4)
30+
31+
# Make sure both motors for each side are in the same group
32+
self.leftLeader.addFollower(self.leftFollower)
33+
self.rightLeader.addFollower(self.rightFollower)
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.rightLeader.setInverted(True)
3039

3140
self.leftEncoder = wpilib.Encoder(0, 1)
3241
self.rightEncoder = wpilib.Encoder(2, 3)
3342

34-
self.leftGroup = wpilib.MotorControllerGroup(leftLeader, leftFollower)
35-
self.rightGroup = wpilib.MotorControllerGroup(rightLeader, rightFollower)
36-
3743
self.gyro = wpilib.AnalogGyro(0)
3844

3945
self.leftPIDController = wpimath.controller.PIDController(1.0, 0.0, 0.0)
@@ -48,11 +54,6 @@ def __init__(self):
4854

4955
self.gyro.reset()
5056

51-
# We need to invert one side of the drivetrain so that positive voltages
52-
# result in both sides moving forward. Depending on how your robot's
53-
# gearbox is constructed, you might have to invert the left side instead.
54-
self.rightGroup.setInverted(True)
55-
5657
# Set the distance per pulse for the drive encoders. We can simply use the
5758
# distance traveled for one rotation of the wheel divided by the encoder
5859
# resolution.
@@ -84,8 +85,9 @@ def setSpeeds(self, speeds: wpimath.kinematics.DifferentialDriveWheelSpeeds):
8485
self.rightEncoder.getRate(), speeds.right
8586
)
8687

87-
self.leftGroup.setVoltage(leftOutput + leftFeedforward)
88-
self.rightGroup.setVoltage(rightOutput + rightFeedforward)
88+
# Controls the left and right sides of the robot using the calculated outputs
89+
self.leftLeader.setVoltage(leftOutput + leftFeedforward)
90+
self.rightLeader.setVoltage(rightOutput + rightFeedforward)
8991

9092
def drive(self, xSpeed, rot):
9193
"""Drives the robot with the given linear velocity and angular velocity."""

FrisbeeBot/subsystems/drivesubsystem.py

Lines changed: 15 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -4,8 +4,8 @@
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
99
import commands2
1010

1111
import constants
@@ -17,29 +17,28 @@ def __init__(self) -> None:
1717
super().__init__()
1818

1919
# The motors on the left side of the drive.
20-
self.leftMotors = wpilib.MotorControllerGroup(
21-
wpilib.PWMSparkMax(constants.DriveConstants.kLeftMotor1Port),
22-
wpilib.PWMSparkMax(constants.DriveConstants.kLeftMotor2Port),
23-
)
20+
self.left1 = PWMSparkMax(constants.DriveConstants.kLeftMotor1Port)
21+
self.left2 = PWMSparkMax(constants.DriveConstants.kLeftMotor2Port)
2422

2523
# The motors on the right side of the drive.
26-
self.rightMotors = wpilib.MotorControllerGroup(
27-
wpilib.PWMSparkMax(constants.DriveConstants.kRightMotor1Port),
28-
wpilib.PWMSparkMax(constants.DriveConstants.kRightMotor2Port),
29-
)
24+
self.right1 = PWMSparkMax(constants.DriveConstants.kRightMotor1Port)
25+
self.right2 = PWMSparkMax(constants.DriveConstants.kRightMotor2Port)
26+
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.leftMotors, self.rightMotors)
31+
self.drive = DifferentialDrive(self.left1, self.right1)
3332

3433
# The left-side drive encoder
35-
self.leftEncoder = wpilib.Encoder(
34+
self.leftEncoder = 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.rightEncoder = wpilib.Encoder(
41+
self.rightEncoder = Encoder(
4342
constants.DriveConstants.kRightEncoderPorts[0],
4443
constants.DriveConstants.kRightEncoderPorts[1],
4544
constants.DriveConstants.kRightEncoderReversed,
@@ -48,7 +47,7 @@ def __init__(self) -> None:
4847
# We need to invert one side of the drivetrain so that positive voltages
4948
# result in both sides moving forward. Depending on how your robot's
5049
# gearbox is constructed, you might have to invert the left side instead.
51-
self.rightMotors.setInverted(True)
50+
self.right1.setInverted(True)
5251

5352
# Sets the distance per pulse for the encoders
5453
self.leftEncoder.setDistancePerPulse(
@@ -80,15 +79,15 @@ def getAverageEncoderDistance(self):
8079
"""
8180
return (self.leftEncoder.getDistance() + self.rightEncoder.getDistance()) / 2.0
8281

83-
def getLeftEncoder(self) -> wpilib.Encoder:
82+
def getLeftEncoder(self) -> Encoder:
8483
"""
8584
Gets the left drive encoder.
8685
8786
:returns: the left drive encoder
8887
"""
8988
return self.leftEncoder
9089

91-
def getRightEncoder(self) -> wpilib.Encoder:
90+
def getRightEncoder(self) -> Encoder:
9291
"""
9392
Gets the right drive encoder.
9493

GyroDriveCommands/subsystems/drivesubsystem.py

Lines changed: 16 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -4,8 +4,8 @@
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
99
import commands2
1010
import 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

Comments
 (0)