Class SwerveModuleState

java.lang.Object
edu.wpi.first.math.kinematics.SwerveModuleState
All Implemented Interfaces:
ProtobufSerializable, StructSerializable, WPISerializable, Comparable<SwerveModuleState>

Represents the state of one swerve module.
  • Field Details

  • Constructor Details

    • SwerveModuleState

      Constructs a SwerveModuleState with zeros for speed and angle.
    • SwerveModuleState

      public SwerveModuleState(double speedMetersPerSecond, Rotation2d angle)
      Constructs a SwerveModuleState.
      Parameters:
      speedMetersPerSecond - The speed of the wheel of the module.
      angle - The angle of the module.
    • SwerveModuleState

      Constructs a SwerveModuleState.
      Parameters:
      speed - The speed of the wheel of the module.
      angle - The angle of the module.
  • Method Details

    • equals

      public boolean equals(Object obj)
      Overrides:
      equals in class Object
    • hashCode

      public int hashCode()
      Overrides:
      hashCode in class Object
    • compareTo

      public int compareTo(SwerveModuleState other)
      Compares two swerve module states. One swerve module is "greater" than the other if its speed is higher than the other.
      Specified by:
      compareTo in interface Comparable<SwerveModuleState>
      Parameters:
      other - The other swerve module.
      Returns:
      1 if this is greater, 0 if both are equal, -1 if other is greater.
    • toString

      public String toString()
      Overrides:
      toString in class Object
    • optimize

      public void optimize(Rotation2d currentAngle)
      Minimize the change in heading this swerve module state would require by potentially reversing the direction the wheel spins. If this is used with the PIDController class's continuous input functionality, the furthest a wheel will ever rotate is 90 degrees.
      Parameters:
      currentAngle - The current module angle.
    • optimize

      @Deprecated public static SwerveModuleState optimize(SwerveModuleState desiredState, Rotation2d currentAngle)
      Deprecated.
      Use the instance method instead.
      Minimize the change in heading the desired swerve module state would require by potentially reversing the direction the wheel spins. If this is used with the PIDController class's continuous input functionality, the furthest a wheel will ever rotate is 90 degrees.
      Parameters:
      desiredState - The desired state.
      currentAngle - The current module angle.
      Returns:
      Optimized swerve module state.
    • cosineScale

      public void cosineScale(Rotation2d currentAngle)
      Scales speed by cosine of angle error. This scales down movement perpendicular to the desired direction of travel that can occur when modules change directions. This results in smoother driving.
      Parameters:
      currentAngle - The current module angle.