[wpimath] Replace Speeds with Velocities (#8479)

I left "free speed" alone since that's the technical term for it. In
general, velocity is a vector quantity, and speed is a magnitude (i.e.,
a strictly positive value).

This PR also replaces the speed verbiage in MotorController with duty
cycle.

Fixes #8423.
This commit is contained in:
Tyler Veness
2026-03-06 14:19:15 -08:00
committed by GitHub
parent 1e39f39128
commit 9bd9656871
594 changed files with 8073 additions and 7875 deletions

View File

@@ -15,9 +15,9 @@ class Drivetrain:
"""Represents a differential drive style drivetrain."""
# 3 meters per second.
kMaxSpeed = 3.0
kMaxVelocity = 3.0
# 1/2 rotation per second.
kMaxAngularSpeed = math.pi
kMaxAngularVelocity = math.pi
kTrackwidth = 0.381 * 2
kWheelRadius = 0.0508
@@ -88,28 +88,28 @@ class Drivetrain:
self.rightLeader.setInverted(True)
wpilib.SmartDashboard.putData("Field", self.fieldSim)
def setSpeeds(self, speeds: wpimath.DifferentialDriveWheelSpeeds) -> None:
"""Sets speeds to the drivetrain motors."""
leftFeedforward = self.feedforward.calculate(speeds.left)
rightFeedforward = self.feedforward.calculate(speeds.right)
def setVelocities(self, velocities: wpimath.DifferentialDriveWheelVelocities) -> None:
"""Sets velocities to the drivetrain motors."""
leftFeedforward = self.feedforward.calculate(velocities.left)
rightFeedforward = self.feedforward.calculate(velocities.right)
leftOutput = self.leftPIDController.calculate(
self.leftEncoder.getRate(), speeds.left
self.leftEncoder.getRate(), velocities.left
)
rightOutput = self.rightPIDController.calculate(
self.rightEncoder.getRate(), speeds.right
self.rightEncoder.getRate(), velocities.right
)
self.leftLeader.setVoltage(leftOutput + leftFeedforward)
self.rightLeader.setVoltage(rightOutput + rightFeedforward)
def drive(self, xSpeed: float, rot: float) -> None:
def drive(self, xVelocity: float, rot: float) -> None:
"""Controls the robot using arcade drive.
:param xSpeed: the speed for the x axis
:param xVelocity: the velocity for the x axis
:param rot: the rotation
"""
self.setSpeeds(
self.kinematics.toWheelSpeeds(wpimath.ChassisSpeeds(xSpeed, 0, rot))
self.setVelocities(
self.kinematics.toWheelVelocities(wpimath.ChassisVelocities(xVelocity, 0, rot))
)
def updateOdometry(self) -> None:

View File

@@ -18,7 +18,7 @@ class MyRobot(wpilib.TimedRobot):
# Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0
# to 1.
self.speedLimiter = wpimath.SlewRateLimiter(3)
self.velocityLimiter = wpimath.SlewRateLimiter(3)
self.rotLimiter = wpimath.SlewRateLimiter(3)
self.drive = Drivetrain()
@@ -43,15 +43,15 @@ class MyRobot(wpilib.TimedRobot):
def autonomousPeriodic(self) -> None:
elapsed = self.timer.get()
reference = self.trajectory.sample(elapsed)
speeds = self.feedback.calculate(self.drive.getPose(), reference)
self.drive.drive(speeds.vx, speeds.omega)
velocities = self.feedback.calculate(self.drive.getPose(), reference)
self.drive.drive(velocities.vx, velocities.omega)
def teleopPeriodic(self) -> None:
# Get the x speed. We are inverting this because Xbox controllers return
# Get the x velocity. We are inverting this because Xbox controllers return
# negative values when we push forward.
xSpeed = (
-self.speedLimiter.calculate(self.controller.getLeftY())
* Drivetrain.kMaxSpeed
xVelocity = (
-self.velocityLimiter.calculate(self.controller.getLeftY())
* Drivetrain.kMaxVelocity
)
# Get the rate of angular rotation. We are inverting this because we want a
@@ -60,9 +60,9 @@ class MyRobot(wpilib.TimedRobot):
# the right by default.
rot = (
-self.rotLimiter.calculate(self.controller.getRightX())
* Drivetrain.kMaxAngularSpeed
* Drivetrain.kMaxAngularVelocity
)
self.drive.drive(xSpeed, rot)
self.drive.drive(xVelocity, rot)
def simulationPeriodic(self) -> None:
self.drive.simulationPeriodic()