Skip to content

Commit 52fe595

Browse files
authored
Merge pull request #250 from pjreiniger/copybara_allwpilib_to_mostrobotpy
[copybara] Resync allwpilib
2 parents e13aab1 + b144a30 commit 52fe595

File tree

175 files changed

+1674
-1567
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

175 files changed

+1674
-1567
lines changed

examples/robot/AddressableLED/robot.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -32,8 +32,8 @@ def __init__(self) -> None:
3232
self.kLedSpacing = 1 / 120.0
3333

3434
# Create a new pattern that scrolls the rainbow pattern across the LED strip, moving at a
35-
# speed of 1 meter per second.
36-
self.scrollingRainbow = self.rainbow.scrollAtAbsoluteSpeed(
35+
# velocity of 1 meter per second.
36+
self.scrollingRainbow = self.rainbow.scrollAtAbsoluteVelocity(
3737
1,
3838
self.kLedSpacing,
3939
)

examples/robot/ArmSimulation/subsystems/arm.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -76,7 +76,7 @@ def simulationPeriodic(self) -> None:
7676
# In this method, we update our simulation of what our arm is doing
7777
# First, we set our "inputs" (voltages)
7878
self.armSim.setInput(
79-
[self.motor.get() * wpilib.RobotController.getBatteryVoltage()]
79+
[self.motor.getDutyCycle() * wpilib.RobotController.getBatteryVoltage()]
8080
)
8181

8282
# Next, we update it. The standard loop time is 20ms.
@@ -111,4 +111,4 @@ def reachSetpoint(self) -> None:
111111
self.motor.setVoltage(pidOutput)
112112

113113
def stop(self) -> None:
114-
self.motor.set(0.0)
114+
self.motor.setDutyCycle(0.0)

examples/robot/DifferentialDriveBot/drivetrain.py

Lines changed: 16 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
class Drivetrain:
1313
"""Represents a differential drive style drivetrain."""
1414

15-
kMaxSpeed = 3.0 # meters per second
16-
kMaxAngularSpeed = 2 * math.pi # one rotation per second
15+
kMaxVelocity = 3.0 # meters per second
16+
kMaxAngularVelocity = 2 * math.pi # one rotation per second
1717

1818
kTrackwidth = 0.381 * 2 # meters
1919
kWheelRadius = 0.0508 # meters
@@ -68,35 +68,37 @@ def __init__(self) -> None:
6868
self.rightEncoder.getDistance(),
6969
)
7070

71-
def setSpeeds(self, speeds: wpimath.DifferentialDriveWheelSpeeds) -> None:
72-
"""Sets the desired wheel speeds.
71+
def setVelocities(
72+
self, velocities: wpimath.DifferentialDriveWheelVelocities
73+
) -> None:
74+
"""Sets the desired wheel velocities.
7375
74-
:param speeds: The desired wheel speeds.
76+
:param velocities: The desired wheel velocities.
7577
"""
76-
leftFeedforward = self.feedforward.calculate(speeds.left)
77-
rightFeedforward = self.feedforward.calculate(speeds.right)
78+
leftFeedforward = self.feedforward.calculate(velocities.left)
79+
rightFeedforward = self.feedforward.calculate(velocities.right)
7880

7981
leftOutput = self.leftPIDController.calculate(
80-
self.leftEncoder.getRate(), speeds.left
82+
self.leftEncoder.getRate(), velocities.left
8183
)
8284
rightOutput = self.rightPIDController.calculate(
83-
self.rightEncoder.getRate(), speeds.right
85+
self.rightEncoder.getRate(), velocities.right
8486
)
8587

8688
# Controls the left and right sides of the robot using the calculated outputs
8789
self.leftLeader.setVoltage(leftOutput + leftFeedforward)
8890
self.rightLeader.setVoltage(rightOutput + rightFeedforward)
8991

90-
def drive(self, xSpeed: float, rot: float) -> None:
92+
def drive(self, xVelocity: float, rot: float) -> None:
9193
"""Drives the robot with the given linear velocity and angular velocity.
9294
93-
:param xSpeed: Linear velocity in m/s.
95+
:param xVelocity: Linear velocity in m/s.
9496
:param rot: Angular velocity in rad/s.
9597
"""
96-
wheelSpeeds = self.kinematics.toWheelSpeeds(
97-
wpimath.ChassisSpeeds(xSpeed, 0.0, rot)
98+
wheelVelocities = self.kinematics.toWheelVelocities(
99+
wpimath.ChassisVelocities(xVelocity, 0.0, rot)
98100
)
99-
self.setSpeeds(wheelSpeeds)
101+
self.setVelocities(wheelVelocities)
100102

101103
def updateOdometry(self) -> None:
102104
"""Updates the field-relative position."""

examples/robot/DifferentialDriveBot/robot.py

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -19,19 +19,19 @@ def __init__(self) -> None:
1919
self.drive = Drivetrain()
2020

2121
# Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0 to 1.
22-
self.speedLimiter = wpimath.SlewRateLimiter(3)
22+
self.velocityLimiter = wpimath.SlewRateLimiter(3)
2323
self.rotLimiter = wpimath.SlewRateLimiter(3)
2424

2525
def autonomousPeriodic(self) -> None:
2626
self.teleopPeriodic()
2727
self.drive.updateOdometry()
2828

2929
def teleopPeriodic(self) -> None:
30-
# Get the x speed. We are inverting this because Xbox controllers return
30+
# Get the x velocity. We are inverting this because Xbox controllers return
3131
# negative values when we push forward.
32-
xSpeed = (
33-
-self.speedLimiter.calculate(self.controller.getLeftY())
34-
* Drivetrain.kMaxSpeed
32+
xVelocity = (
33+
-self.velocityLimiter.calculate(self.controller.getLeftY())
34+
* Drivetrain.kMaxVelocity
3535
)
3636

3737
# Get the rate of angular rotation. We are inverting this because we want a
@@ -40,7 +40,7 @@ def teleopPeriodic(self) -> None:
4040
# the right by default.
4141
rot = (
4242
-self.rotLimiter.calculate(self.controller.getRightX())
43-
* Drivetrain.kMaxAngularSpeed
43+
* Drivetrain.kMaxAngularVelocity
4444
)
4545

46-
self.drive.drive(xSpeed, rot)
46+
self.drive.drive(xVelocity, rot)

examples/robot/DifferentialDrivePoseEstimator/drivetrain.py

Lines changed: 18 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -17,8 +17,8 @@
1717
class Drivetrain:
1818
"""Represents a differential drive style drivetrain."""
1919

20-
kMaxSpeed = 3.0 # meters per second
21-
kMaxAngularSpeed = math.tau # one rotation per second
20+
kMaxVelocity = 3.0 # meters per second
21+
kMaxAngularVelocity = math.tau # one rotation per second
2222

2323
kTrackwidth = 0.381 * 2 # meters
2424
kWheelRadius = 0.0508 # meters
@@ -111,33 +111,35 @@ def __init__(self, cameraToObjectTopic: ntcore.DoubleArrayTopic) -> None:
111111
wpilib.SmartDashboard.putData("Field", self.fieldSim)
112112
wpilib.SmartDashboard.putData("FieldEstimation", self.fieldApproximation)
113113

114-
def setSpeeds(self, speeds: wpimath.DifferentialDriveWheelSpeeds) -> None:
115-
"""Sets the desired wheel speeds.
114+
def setVelocities(
115+
self, velocities: wpimath.DifferentialDriveWheelVelocities
116+
) -> None:
117+
"""Sets the desired wheel velocities.
116118
117-
:param speeds: The desired wheel speeds.
119+
:param velocities: The desired wheel velocities.
118120
"""
119-
leftFeedforward = self.feedforward.calculate(speeds.left)
120-
rightFeedforward = self.feedforward.calculate(speeds.right)
121+
leftFeedforward = self.feedforward.calculate(velocities.left)
122+
rightFeedforward = self.feedforward.calculate(velocities.right)
121123

122124
leftOutput = self.leftPIDController.calculate(
123-
self.leftEncoder.getRate(), speeds.left
125+
self.leftEncoder.getRate(), velocities.left
124126
)
125127
rightOutput = self.rightPIDController.calculate(
126-
self.rightEncoder.getRate(), speeds.right
128+
self.rightEncoder.getRate(), velocities.right
127129
)
128130
self.leftLeader.setVoltage(leftOutput + leftFeedforward)
129131
self.rightLeader.setVoltage(rightOutput + rightFeedforward)
130132

131-
def drive(self, xSpeed: float, rot: float) -> None:
133+
def drive(self, xVelocity: float, rot: float) -> None:
132134
"""Drives the robot with the given linear velocity and angular velocity.
133135
134-
:param xSpeed: Linear velocity in m/s.
136+
:param xVelocity: Linear velocity in m/s.
135137
:param rot: Angular velocity in rad/s.
136138
"""
137-
wheelSpeeds = self.kinematics.toWheelSpeeds(
138-
wpimath.ChassisSpeeds(xSpeed, 0.0, rot)
139+
wheelVelocities = self.kinematics.toWheelVelocities(
140+
wpimath.ChassisVelocities(xVelocity, 0.0, rot)
139141
)
140-
self.setSpeeds(wheelSpeeds)
142+
self.setVelocities(wheelVelocities)
141143

142144
def publishCameraToObject(
143145
self,
@@ -242,8 +244,8 @@ def simulationPeriodic(self) -> None:
242244
# simulation, and write the simulated positions and velocities to our
243245
# simulated encoder and gyro.
244246
self.drivetrainSimulator.setInputs(
245-
self.leftLeader.get() * wpilib.RobotController.getInputVoltage(),
246-
self.rightLeader.get() * wpilib.RobotController.getInputVoltage(),
247+
self.leftLeader.getDutyCycle() * wpilib.RobotController.getInputVoltage(),
248+
self.rightLeader.getDutyCycle() * wpilib.RobotController.getInputVoltage(),
247249
)
248250
self.drivetrainSimulator.update(0.02)
249251

examples/robot/DifferentialDrivePoseEstimator/robot.py

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@ def __init__(self) -> None:
2323
self.drive = Drivetrain(self.doubleArrayTopic)
2424

2525
# Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0 to 1.
26-
self.speedLimiter = wpimath.SlewRateLimiter(3)
26+
self.velocityLimiter = wpimath.SlewRateLimiter(3)
2727
self.rotLimiter = wpimath.SlewRateLimiter(3)
2828

2929
def autonomousPeriodic(self) -> None:
@@ -37,16 +37,16 @@ def robotPeriodic(self) -> None:
3737
self.drive.periodic()
3838

3939
def teleopPeriodic(self) -> None:
40-
# Get the x speed. We are inverting this because Xbox controllers return
40+
# Get the x velocity. We are inverting this because Xbox controllers return
4141
# negative values when we push forward.
42-
xSpeed = -self.speedLimiter.calculate(self.controller.getLeftY())
43-
xSpeed *= Drivetrain.kMaxSpeed
42+
xVelocity = -self.velocityLimiter.calculate(self.controller.getLeftY())
43+
xVelocity *= Drivetrain.kMaxVelocity
4444

4545
# Get the rate of angular rotation. We are inverting this because we want a
4646
# positive value when we pull to the left (remember, CCW is positive in
4747
# mathematics). Xbox controllers return positive values when you pull to
4848
# the right by default.
4949
rot = -self.rotLimiter.calculate(self.controller.getRightX())
50-
rot *= Drivetrain.kMaxAngularSpeed
50+
rot *= Drivetrain.kMaxAngularVelocity
5151

52-
self.drive.drive(xSpeed, rot)
52+
self.drive.drive(xVelocity, rot)

examples/robot/DriveDistanceOffboard/constants.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@ class DriveConstants:
3232

3333
kp = 1.0
3434

35-
kMaxSpeed = 3.0 # m/s
35+
kMaxVelocity = 3.0 # m/s
3636
kMaxAcceleration = 3.0 # m/s²
3737

3838

examples/robot/DriveDistanceOffboard/examplesmartmotorcontroller.py

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@
88
import enum
99

1010

11-
class ExampleSmartMotorController(wpilib.MotorController):
11+
class ExampleSmartMotorController:
1212
"""A simplified stub class that simulates the API of a common "smart" motor controller.
1313
Has no actual functionality.
1414
"""
@@ -25,7 +25,7 @@ def __init__(self, port: int) -> None:
2525
port: The port for the controller.
2626
"""
2727
super().__init__()
28-
self._speed = 0.0
28+
self._velocity = 0.0
2929
self._inverted = False
3030
self._leader = None
3131

@@ -79,11 +79,11 @@ def resetEncoder(self) -> None:
7979
"""Resets the encoder to zero distance."""
8080
pass
8181

82-
def set(self, speed: float) -> None:
83-
self._speed = -speed if self._inverted else speed
82+
def set(self, velocity: float) -> None:
83+
self._velocity = -velocity if self._inverted else velocity
8484

8585
def get(self) -> float:
86-
return self._speed
86+
return self._velocity
8787

8888
def setInverted(self, isInverted: bool) -> None:
8989
self._inverted = isInverted
@@ -92,7 +92,7 @@ def getInverted(self) -> bool:
9292
return self._inverted
9393

9494
def disable(self) -> None:
95-
self._speed = 0.0
95+
self._velocity = 0.0
9696

9797
def stopMotor(self) -> None:
98-
self._speed = 0.0
98+
self._velocity = 0.0

examples/robot/DriveDistanceOffboard/robotcontainer.py

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -25,10 +25,10 @@ def __init__(self):
2525
self.robotDrive = subsystems.drivesubsystem.DriveSubsystem()
2626

2727
# Retained command references
28-
self.driveFullSpeed = commands2.cmd.runOnce(
28+
self.driveFullVelocity = commands2.cmd.runOnce(
2929
lambda: self.robotDrive.setMaxOutput(1), self.robotDrive
3030
)
31-
self.driveHalfSpeed = commands2.cmd.runOnce(
31+
self.driveHalfVelocity = commands2.cmd.runOnce(
3232
lambda: self.robotDrive.setMaxOutput(0.5), self.robotDrive
3333
)
3434

@@ -65,9 +65,9 @@ def configureButtonBindings(self):
6565

6666
# We can bind commands while retaining references to them in RobotContainer
6767

68-
# Drive at half speed when the bumper is held
69-
self.driverController.rightBumper().onTrue(self.driveHalfSpeed).onFalse(
70-
self.driveFullSpeed
68+
# Drive at half velocity when the bumper is held
69+
self.driverController.rightBumper().onTrue(self.driveHalfVelocity).onFalse(
70+
self.driveFullVelocity
7171
)
7272

7373
# Drive forward by 3 meters when the 'A' button is pressed, with a timeout of 10 seconds

examples/robot/DriveDistanceOffboard/subsystems/drivesubsystem.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -59,11 +59,11 @@ def __init__(self) -> None:
5959
)
6060

6161
# The robot's drive
62-
self.drive = wpilib.DifferentialDrive(self.leftLeader, self.rightLeader)
62+
self.drive = wpilib.DifferentialDrive(self.leftLeader.set, self.rightLeader.set)
6363

6464
self.profile = wpimath.TrapezoidProfile(
6565
wpimath.TrapezoidProfile.Constraints(
66-
constants.DriveConstants.kMaxSpeed,
66+
constants.DriveConstants.kMaxVelocity,
6767
constants.DriveConstants.kMaxAcceleration,
6868
)
6969
)

0 commit comments

Comments
 (0)