DifferentialDriveKinematics

class wpimath.DifferentialDriveKinematics(trackwidth: wpimath.units.meters)

Bases: DifferentialDriveKinematicsBase

Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel velocities for a differential drive.

Inverse kinematics converts a desired chassis velocity into left and right velocity components whereas forward kinematics converts left and right component velocities into a linear and angular chassis velocity.

Constructs a differential drive kinematics object.

Parameters:

trackwidth – The trackwidth of the drivetrain. Theoretically, this is the distance between the left wheels and right wheels. However, the empirical value may be larger than the physical measured value due to scrubbing effects.

WPIStruct = <capsule object "WPyStruct">
interpolate(start: wpimath._wpimath.DifferentialDriveWheelPositions, end: wpimath._wpimath.DifferentialDriveWheelPositions, t: SupportsFloat | SupportsIndex) wpimath._wpimath.DifferentialDriveWheelPositions
toChassisAccelerations(wheelAccelerations: wpimath._wpimath.DifferentialDriveWheelAccelerations) wpimath._wpimath.ChassisAccelerations
toChassisVelocities(wheelVelocities: wpimath._wpimath.DifferentialDriveWheelVelocities) wpimath._wpimath.ChassisVelocities

Returns a chassis velocity from left and right component velocities using forward kinematics.

Parameters:

wheelVelocities – The left and right velocities.

Returns:

The chassis velocity.

toTwist2d(*args, **kwargs)

Overloaded function.

  1. toTwist2d(self: wpimath._wpimath.DifferentialDriveKinematics, leftDistance: wpimath.units.meters, rightDistance: wpimath.units.meters) -> wpimath._wpimath.Twist2d

Returns a twist from left and right distance deltas using forward kinematics.

Parameters:
  • leftDistance – The distance measured by the left encoder.

  • rightDistance – The distance measured by the right encoder.

Returns:

The resulting Twist2d.

  1. toTwist2d(self: wpimath._wpimath.DifferentialDriveKinematics, start: wpimath._wpimath.DifferentialDriveWheelPositions, end: wpimath._wpimath.DifferentialDriveWheelPositions) -> wpimath._wpimath.Twist2d

toWheelAccelerations(chassisAccelerations: wpimath._wpimath.ChassisAccelerations) wpimath._wpimath.DifferentialDriveWheelAccelerations
toWheelVelocities(chassisVelocities: wpimath._wpimath.ChassisVelocities) wpimath._wpimath.DifferentialDriveWheelVelocities

Returns left and right component velocities from a chassis velocity using inverse kinematics.

Parameters:

chassisVelocities – The linear and angular (dx and dtheta) components that represent the chassis’ velocity.

Returns:

The left and right velocities.