ChassisSpeeds

class wpimath.kinematics.ChassisSpeeds(vx: wpimath.units.meters_per_second = 0, vy: wpimath.units.meters_per_second = 0, omega: wpimath.units.radians_per_second = 0)

Bases: pybind11_object

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, a ChassisSpeeds struct represents a robot’s velocity.

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.

WPIStruct = <capsule object "WPyStruct">
static discretize(*args, **kwargs)

Overloaded function.

  1. discretize(vx: wpimath.units.meters_per_second, vy: wpimath.units.meters_per_second, omega: wpimath.units.radians_per_second, dt: wpimath.units.seconds) -> wpimath.kinematics._kinematics.ChassisSpeeds

Discretizes a continuous-time chassis speed.

This function converts a continuous-time chassis speed into a discrete-time one such that when the discrete-time chassis speed is applied for one timestep, the robot moves as if the velocity components are independent (i.e., the robot moves v_x * dt along the x-axis, v_y * dt along the y-axis, and omega * dt around the z-axis).

This is useful for compensating for translational skew when translating and rotating a holonomic (swerve or mecanum) drivetrain. However, scaling down the ChassisSpeeds after discretizing (e.g., when desaturating swerve module speeds) rotates the direction of net motion in the opposite direction of rotational velocity, introducing a different translational skew which is not accounted for by discretization.

Parameters:
  • vx – Forward velocity.

  • vy – Sideways velocity.

  • omega – Angular velocity.

  • dt – The duration of the timestep the speeds should be applied for.

Returns:

Discretized ChassisSpeeds.

  1. discretize(continuousSpeeds: wpimath.kinematics._kinematics.ChassisSpeeds, dt: wpimath.units.seconds) -> wpimath.kinematics._kinematics.ChassisSpeeds

Discretizes a continuous-time chassis speed.

This function converts a continuous-time chassis speed into a discrete-time one such that when the discrete-time chassis speed is applied for one timestep, the robot moves as if the velocity components are independent (i.e., the robot moves v_x * dt along the x-axis, v_y * dt along the y-axis, and omega * dt around the z-axis).

This is useful for compensating for translational skew when translating and rotating a holonomic (swerve or mecanum) drivetrain. However, scaling down the ChassisSpeeds after discretizing (e.g., when desaturating swerve module speeds) rotates the direction of net motion in the opposite direction of rotational velocity, introducing a different translational skew which is not accounted for by discretization.

Parameters:
  • continuousSpeeds – The continuous speeds.

  • dt – The duration of the timestep the speeds should be applied for.

Returns:

Discretized ChassisSpeeds.

static fromFeet(vx: wpimath.units.feet_per_second = 0, vy: wpimath.units.feet_per_second = 0, omega: wpimath.units.radians_per_second = 0) wpimath.kinematics._kinematics.ChassisSpeeds
static fromFieldRelativeSpeeds(*args, **kwargs)

Overloaded function.

  1. fromFieldRelativeSpeeds(vx: wpimath.units.meters_per_second, vy: wpimath.units.meters_per_second, omega: wpimath.units.radians_per_second, robotAngle: wpimath.geometry._geometry.Rotation2d) -> wpimath.kinematics._kinematics.ChassisSpeeds

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

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

  • vy – 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 – The angular rate of the robot.

  • robotAngle – 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.

Returns:

ChassisSpeeds object representing the speeds in the robot’s frame of reference.

  1. fromFieldRelativeSpeeds(fieldRelativeSpeeds: wpimath.kinematics._kinematics.ChassisSpeeds, robotAngle: wpimath.geometry._geometry.Rotation2d) -> wpimath.kinematics._kinematics.ChassisSpeeds

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

Parameters:
  • fieldRelativeSpeeds – The ChassisSpeeds object representing the speeds in the field frame of reference. Positive x is away from your alliance wall. Positive y is to your left when standing behind the alliance wall.

  • robotAngle – 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.

Returns:

ChassisSpeeds object representing the speeds in the robot’s frame of reference.

static fromRobotRelativeSpeeds(*args, **kwargs)

Overloaded function.

  1. fromRobotRelativeSpeeds(vx: wpimath.units.meters_per_second, vy: wpimath.units.meters_per_second, omega: wpimath.units.radians_per_second, robotAngle: wpimath.geometry._geometry.Rotation2d) -> wpimath.kinematics._kinematics.ChassisSpeeds

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

Parameters:
  • vx – The component of speed in the x direction relative to the robot. Positive x is towards the robot’s front.

  • vy – The component of speed in the y direction relative to the robot. Positive y is towards the robot’s left.

  • omega – The angular rate of the robot.

  • robotAngle – 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.

Returns:

ChassisSpeeds object representing the speeds in the field’s frame of reference.

  1. fromRobotRelativeSpeeds(robotRelativeSpeeds: wpimath.kinematics._kinematics.ChassisSpeeds, robotAngle: wpimath.geometry._geometry.Rotation2d) -> wpimath.kinematics._kinematics.ChassisSpeeds

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

Parameters:
  • robotRelativeSpeeds – The ChassisSpeeds object representing the speeds in the robot frame of reference. Positive x is the towards robot’s front. Positive y is towards the robot’s left.

  • robotAngle – 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.

Returns:

ChassisSpeeds object representing the speeds in the field’s frame of reference.

property omega_dps
toTwist2d(dt: wpimath.units.seconds) wpimath.geometry._geometry.Twist2d

Creates a Twist2d from ChassisSpeeds.

Parameters:

dt – The duration of the timestep.

Returns:

Twist2d.

property vx_fps
property vy_fps