Class 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 Detail

      • vxMetersPerSecond

        public double vxMetersPerSecond
        Represents forward velocity w.r.t the robot frame of reference. (Fwd is +)
      • vyMetersPerSecond

        public double vyMetersPerSecond
        Represents sideways velocity w.r.t the robot frame of reference. (Left is +)
      • omegaRadiansPerSecond

        public double omegaRadiansPerSecond
        Represents the angular velocity of the robot frame. (CCW is +)
    • Constructor Detail

      • 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 Detail

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