API Reference

All units are assumed to be SI units unless specified otherwise.

wpilib.geometry

class wpilib.geometry.Rotation2d(*args)

Bases: object

A rotation in a 2d coordinate frame represented a point on the unit circle.

__add__(other)

Adds two rotations together, with the result bounded between -pi and pi.

Return type

Rotation2d

__eq__(other)

Return self==value.

Return type

bool

__init__(*args)

Constructs a Rotation2d.

This can either be called with zero or one arguments:

Parameters

value (float) – The value in radians (default 0).

… or with two arguments:

Parameters
  • x (float) – The x component or cosine of the rotation.

  • y (float) – The y component or sine of the rotation.

In this case the x and y do not need to be normalised.

__mul__(other)

Multiplies the current rotation by a scalar.

Return type

Rotation2d

__neg__()

Takes the inverse of the current rotation.

This is simply the negative of the current angular value.

Return type

Rotation2d

__repr__()

Return repr(self).

Return type

str

__rmul__(other)

Multiplies the current rotation by a scalar.

Return type

Rotation2d

__sub__(other)

Subtracts the other rotation from self.

Return type

Rotation2d

cos

The cosine of the rotation.

classmethod fromDegrees(degrees)

Creates a Rotation2d with the given degrees value.

Return type

Rotation2d

getDegrees()

Returns the value of the rotation in degrees.

Return type

float

getRadians()

Returns the value of the rotation in radians.

Return type

float

sin

The sine of the rotation.

tan()

Returns the tangent of the rotation.

Return type

float

value

The value of the rotation in radians.

class wpilib.geometry.Translation2d(x=0, y=0)

Bases: object

Represents a translation in 2d space.

This object can be used to represent a point or a vector.

This assumes that you are using conventional mathematical axes. When the robot is placed on the origin, facing toward the X direction, moving forward increases the X, whereas moving to the left increases the Y.

__abs__()

Returns the norm of this translation.

This is equivalent to the norm method.

Return type

float

__add__(other)

Adds two translations in 2d space.

Return type

Translation2d

__eq__(other)

Return self==value.

Return type

bool

__init__(x=0, y=0)

Initialize self. See help(type(self)) for accurate signature.

__mul__(other)

Multiplies the translation by a scalar.

Return type

Translation2d

__neg__()

Takes the inverse of the translation.

Return type

Translation2d

__rmul__(other)

Multiplies the translation by a scalar.

Return type

Translation2d

__sub__(other)

Subtracts the other translation from self.

Return type

Translation2d

__truediv__(other)

Divides the translation by a scalar.

Return type

Translation2d

getDistance(other)

Calculates the distance between two translations in 2d space.

Return type

float

norm()

Returns the norm, or distance from the origin to the translation.

Return type

float

rotateBy(other)

Applies a rotation to the translation in 2d space.

This multiplies the translation vector by a counterclockwise rotation matrix of the given angle:

[x_new]   [other.cos, -other.sin][x]
[y_new] = [other.sin,  other.cos][y]

For example, rotating a Translation2d(2, 0) by 90 degrees will return a Translation2d(0, 2).

Parameters

other (Rotation2d) – The rotation to rotate the translation by.

Return type

Translation2d

Returns

The new rotated translation.

x

The X component of the translation.

y

The Y component of the translation.

class wpilib.geometry.Twist2d(dx=0, dy=0, dtheta=0)

Bases: object

A change in distance along arc since the last pose update.

We can use ideas from differential calculus to create new Pose2ds from a Twist2d and vice versa.

A Twist can be used to represent a difference between two poses.

__eq__(other)

Return self==value.

Return type

bool

__init__(dx=0, dy=0, dtheta=0)

Initialize self. See help(type(self)) for accurate signature.

dtheta

Angular “dtheta” component (radians)

dx

Linear “dx” component

dy

Linear “dy” component

class wpilib.geometry.Transform2d(translation=Translation2d(x=0, y=0), rotation=Rotation2d(0))

Bases: object

Represents a transformation for a Pose2d.

__init__(translation=Translation2d(x=0, y=0), rotation=Rotation2d(0))

Initialize self. See help(type(self)) for accurate signature.

__mul__(other)

Multiplies the transform by a scalar.

Return type

Transform2d

__rmul__(other)

Multiplies the transform by a scalar.

Return type

Transform2d

class wpilib.geometry.Pose2d(*args, rotation=None)

Bases: object

Represents a 2d pose containing translational and rotational elements.

__add__(other)

Transforms the pose by the given transformation.

[x_new]   [cos, -sin, 0][transform.x]
[y_new] = [sin,  cos, 0][transform.y]
[t_new]   [0,    0,   1][transform.t]
Parameters

other (Transform2d) – The transform to transform the pose by.

Return type

Pose2d

Returns

The transformed pose.

__init__(*args, rotation=None)

Initialize self. See help(type(self)) for accurate signature.

__sub__(other)

Returns the Transform2d that maps the other pose to self.

Parameters

other (Pose2d) – The initial pose of the transformation.

Return type

Transform2d

Returns

The transform that maps the other pose to the current pose.

exp(twist)

Obtain a new Pose2d from a (constant curvature) velocity.

See <https://file.tavsys.net/control/state-space-guide.pdf> section on nonlinear pose estimation for derivation.

The twist is a change in pose in the robot’s coordinate frame since the previous pose update. When the user runs exp() on the previous known field-relative pose with the argument being the twist, the user will receive the new field-relative pose.

“Exp” represents the pose exponential, which is solving a differential equation moving the pose forward in time.

Parameters

twist (Twist2d) – The change in pose in the robot’s coordinate frame since the previous pose update. For example, if a non-holonomic robot moves forward 0.01 meters and changes angle by 0.5 degrees since the previous pose update, the twist would be Twist2d(0.01, 0.0, math.radians(0.5))

Return type

Pose2d

Returns

The new pose of the robot.

log(end)

Returns a Twist2d that maps this pose to the end pose.

If c = a.log(b), then a.exp(c) = b.

Parameters

end (Pose2d) – The end pose for the transformation.

Return type

Twist2d

Returns

The twist that maps self to end.

relativeTo(other)

Returns the other pose relative to the current pose.

This function can often be used for trajectory tracking or pose stabilization algorithms to get the error between the reference and the current pose.

Parameters

other (Pose2d) – The pose that is the origin of the new coordinate frame that the current pose will be converted into.

Return type

Pose2d

Returns

The current pose relative to the new origin pose.

wpilib.kinematics

class wpilib.kinematics.ChassisSpeeds

Bases: tuple

Represents the speed of a robot chassis.

Although this struct contains similar members compared to a Twist2d, they do NOT represent the same thing. Whereas a Twist2d represents a change in pose w.r.t. to the robot frame of reference, this ChassisSpeeds struct represents a velocity w.r.t. to the robot frame of reference.

A strictly non-holonomic drivetrain, such as a differential drive, should never have a dy component because it can never move sideways. Holonomic drivetrains such as swerve and mecanum will often have all three components.

classmethod fromFieldRelativeSpeeds(vx, vy, omega, robotAngle)

Converts a user provided field-relative set of speeds into a robot-relative ChassisSpeeds object.

Parameters
  • vx (float) – The component of speed in the x direction relative to the field. Positive x is away from your alliance wall.

  • vy (float) – The component of speed in the y direction relative to the field. Positive y is to your left when standing behind the alliance wall.

  • omega (float) – The angular rate of the robot.

  • robotAngle (Rotation2d) – The angle of the robot as measured by a gyroscope. The robot’s angle is considered to be zero when it is facing directly away from your alliance station wall. Remember that this should be CCW positive.

Return type

ChassisSpeeds

Returns

Object representing the speeds in the robot’s frame of reference.

property omega

Represents the angular velocity of the robot frame. (CCW is +)

property vx

Represents forward velocity w.r.t the robot frame of reference. (Fwd is +)

property vy

Represents strafe velocity w.r.t the robot frame of reference. (Left is +)

class wpilib.kinematics.swerve.SwerveModuleState(speed=0, angle=Rotation2d(0))

Bases: object

Represents the state of one swerve module.

angle

Angle of the module.

speed

Speed of the wheel of the module.

class wpilib.kinematics.swerve.SwerveDriveKinematics(*wheels)

Bases: object

Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual module states (speed and angle).

The inverse kinematics (converting from a desired chassis velocity to individual module states) uses the relative locations of the modules with respect to the center of rotation. The center of rotation for inverse kinematics is also variable. This means that you can set your set your center of rotation in a corner of the robot to perform special evasion maneuvers.

Forward kinematics (converting an array of module states into the overall chassis motion) is performs the exact opposite of what inverse kinematics does. Since this is an overdetermined system (more equations than variables), we use a least-squares approximation.

The inverse kinematics: [moduleStates] = [moduleLocations] * [chassisSpeeds] We take the Moore-Penrose pseudoinverse of [moduleLocations] and then multiply by [moduleStates] to get our chassis speeds.

Forward kinematics is also used for odometry – determining the position of the robot on the field using encoders and a gyro.

static normalizeWheelSpeeds(moduleStates, attainableMaxSpeed)

Normalizes the wheel speeds using some max attainable speed.

Sometimes, after inverse kinematics, the requested speed from a/several modules may be above the max attainable speed for the driving motor on that module. To fix this issue, one can “normalize” all the wheel speeds to make sure that all requested module speeds are below the absolute threshold, while maintaining the ratio of speeds between modules.

Parameters
  • moduleStates (List[SwerveModuleState]) – Reference to list of module states. The list will be mutated with the normalized speeds!

  • attainableMaxSpeed (float) – The absolute max speed that a module can reach.

Return type

None

toChassisSpeeds(*wheel_states)

Performs forward kinematics to return the resulting chassis state from the given module states.

This method is often used for odometry – determining the robot’s position on the field using data from the real-world speed and angle of each module on the robot.

Parameters

wheel_states (SwerveModuleState) – The state of the modules (as a SwerveModuleState type) as measured from respective encoders and gyros. The order of the swerve module states should be same as passed into the constructor of this class.

Return type

ChassisSpeeds

Returns

The resulting chassis speed.

toSwerveModuleStates(chassisSpeeds, centerOfRotation=Translation2d(x=0, y=0))

Performs inverse kinematics to return the module states from a desired chassis velocity.

This method is often used to convert joystick values into module speeds and angles.

This function also supports variable centers of rotation. During normal operations, the center of rotation is usually the same as the physical center of the robot; therefore, the argument is defaulted to that use case. However, if you wish to change the center of rotation for evasive maneuvers, vision alignment, or for any other use case, you can do so.

Parameters
  • chassisSpeeds (ChassisSpeeds) – The desired chassis speed.

  • centerOfRotation (Translation2d) – The center of rotation. For example, if you set the center of rotation at one corner of the robot and provide a chassis speed that only has a dtheta component, the robot will rotate around that corner.

Return type

List[SwerveModuleState]

Returns

An array containing the module states. Use caution because these module states are not normalized. Sometimes, a user input may cause one of the module speeds to go above the attainable max velocity. Use the normalizeWheelSpeeds() function to rectify this issue.

class wpilib.kinematics.swerve.SwerveDriveOdometry(kinematics, gyroAngle, initialPose=None)

Bases: object

Class for swerve drive odometry.

Odometry allows you to track the robot’s position on the field over a course of a match using readings from your swerve drive encoders and swerve azimuth encoders.

Teams can use odometry during the autonomous period for complex tasks like path following. Furthermore, odometry can be used for latency compensation when using computer-vision systems.

getPose()

Returns the position of the robot on the field.

Return type

Pose2d

resetPosition(pose, gyroAngle)

Resets the robot’s position on the field.

The gyroscope angle does not need to be reset here on the user’s robot code. The library automatically takes care of offsetting the gyro angle.

Parameters
  • pose (Pose2d) – The position on the field that your robot is at.

  • gyroAngle (Rotation2d) – The angle reported by the gyroscope.

Return type

None

updateWithTime(currentTime, gyroAngle, *module_states)

Updates the robot’s position on the field using forward kinematics and integration of the pose over time.

This method takes in the current time as a parameter to calculate period (difference between two timestamps). The period is used to calculate the change in distance from a velocity. This also takes in an angle parameter which is used instead of the angular rate that is calculated from forward kinematics.

Parameters
  • currentTime (float) – The current time.

  • gyroAngle (Rotation2d) – The angle reported by the gyroscope.

  • module_states (SwerveModuleState) – The current state of all swerve modules. Please provide the states in the same order in which you instantiated your SwerveDriveKinematics.

Return type

Pose2d

Returns

The new pose of the robot.