Skip to content

Commit 2f4e96b

Browse files
committed
Update both ramsete drive examples
1 parent a4f5107 commit 2f4e96b

File tree

2 files changed

+26
-25
lines changed

2 files changed

+26
-25
lines changed

RamseteCommand/subsystems/driveSubsystem.py

Lines changed: 17 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@
66

77
from commands2 import Subsystem
88

9-
from wpilib import MotorControllerGroup, PWMSparkMax, Encoder, ADXRS450_Gyro
9+
from wpilib import PWMSparkMax, Encoder, ADXRS450_Gyro
1010
from wpilib.drive import DifferentialDrive
1111

1212
from 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):

RamseteController/drivetrain.py

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -24,16 +24,16 @@ class Drivetrain:
2424
kEncoderResolution = 4096 # counts per revolution
2525

2626
def __init__(self):
27-
leftLeader = wpilib.PWMSparkMax(1)
28-
leftFollower = wpilib.PWMSparkMax(2)
29-
rightLeader = wpilib.PWMSparkMax(3)
30-
rightFollower = wpilib.PWMSparkMax(4)
27+
self.leftLeader = wpilib.PWMSparkMax(1)
28+
self.leftFollower = wpilib.PWMSparkMax(2)
29+
self.rightLeader = wpilib.PWMSparkMax(3)
30+
self.rightFollower = wpilib.PWMSparkMax(4)
3131

3232
self.leftEncoder = wpilib.Encoder(0, 1)
3333
self.rightEncoder = wpilib.Encoder(2, 3)
3434

35-
self.leftGroup = wpilib.MotorControllerGroup(leftLeader, leftFollower)
36-
self.rightGroup = wpilib.MotorControllerGroup(rightLeader, rightFollower)
35+
self.leftLeader.addFollower(self.leftFollower)
36+
self.rightLeader.addFollower(self.rightFollower)
3737

3838
self.gyro = wpilib.AnalogGyro(0)
3939

@@ -52,7 +52,7 @@ def __init__(self):
5252
# We need to invert one side of the drivetrain so that positive voltages
5353
# result in both sides moving forward. Depending on how your robot's
5454
# gearbox is constructed, you might have to invert the left side instead.
55-
self.rightGroup.setInverted(True)
55+
self.rightLeader.setInverted(True)
5656

5757
# Set the distance per pulse for the drive encoders. We can simply use the
5858
# distance traveled for one rotation of the wheel divided by the encoder
@@ -85,8 +85,8 @@ def setSpeeds(self, speeds: wpimath.kinematics.DifferentialDriveWheelSpeeds):
8585
self.rightEncoder.getRate(), speeds.right
8686
)
8787

88-
self.leftGroup.setVoltage(leftOutput + leftFeedforward)
89-
self.rightGroup.setVoltage(rightOutput + rightFeedforward)
88+
self.leftLeader.setVoltage(leftOutput + leftFeedforward)
89+
self.rightLeader.setVoltage(rightOutput + rightFeedforward)
9090

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

0 commit comments

Comments
 (0)