Class ChassisSpeeds

java.lang.Object
edu.wpi.first.math.kinematics.ChassisSpeeds

public class ChassisSpeeds
extends 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, 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.

  • Field Details

  • Constructor Details

    • ChassisSpeeds

      public ChassisSpeeds()
      Constructs a ChassisSpeeds with zeros for dx, dy, and theta.
    • ChassisSpeeds

      public ChassisSpeeds​(double vxMetersPerSecond, double vyMetersPerSecond, double omegaRadiansPerSecond)
      Constructs a ChassisSpeeds object.
      Parameters:
      vxMetersPerSecond - Forward velocity.
      vyMetersPerSecond - Sideways velocity.
      omegaRadiansPerSecond - Angular velocity.
  • Method Details

    • fromFieldRelativeSpeeds

      public static ChassisSpeeds fromFieldRelativeSpeeds​(double vxMetersPerSecond, double vyMetersPerSecond, double omegaRadiansPerSecond, Rotation2d robotAngle)
      Converts a user provided field-relative set of speeds into a robot-relative ChassisSpeeds object.
      Parameters:
      vxMetersPerSecond - The component of speed in the x direction relative to the field. Positive x is away from your alliance wall.
      vyMetersPerSecond - The component of speed in the y direction relative to the field. Positive y is to your left when standing behind the alliance wall.
      omegaRadiansPerSecond - 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.
    • fromFieldRelativeSpeeds

      public static ChassisSpeeds fromFieldRelativeSpeeds​(ChassisSpeeds fieldRelativeSpeeds, Rotation2d robotAngle)
      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.
    • toString

      public String toString()
      Overrides:
      toString in class Object