Class SwerveModuleVelocity

java.lang.Object
org.wpilib.math.kinematics.SwerveModuleVelocity
All Implemented Interfaces:
Comparable<SwerveModuleVelocity>, Interpolatable<SwerveModuleVelocity>, ProtobufSerializable, StructSerializable, WPISerializable

Represents the velocity of one swerve module.
  • Field Details

  • Constructor Details

    • SwerveModuleVelocity

      Constructs a SwerveModuleVelocity with zeros for velocity and angle.
    • SwerveModuleVelocity

      public SwerveModuleVelocity(double velocity, Rotation2d angle)
      Constructs a SwerveModuleVelocity.
      Parameters:
      velocity - The velocity of the wheel of the module in meters per second.
      angle - The angle of the module.
    • SwerveModuleVelocity

      Constructs a SwerveModuleVelocity.
      Parameters:
      velocity - The velocity 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(SwerveModuleVelocity other)
      Compares two swerve module velocities. One swerve module is "greater" than the other if its velocity is higher than the other.
      Specified by:
      compareTo in interface Comparable<SwerveModuleVelocity>
      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 velocity 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 SwerveModuleVelocity optimize(SwerveModuleVelocity desiredVelocity, Rotation2d currentAngle)
      Deprecated.
      Use the instance method instead.
      Minimize the change in heading the desired swerve module velocity 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:
      desiredVelocity - The desired velocity.
      currentAngle - The current module angle.
      Returns:
      Optimized swerve module velocity.
    • interpolate

      Returns the linear interpolation of this SwerveModuleVelocity and another. The angle is interpolated using the shortest path between the two angles.
      Specified by:
      interpolate in interface Interpolatable<SwerveModuleVelocity>
      Parameters:
      endValue - The end value for the interpolation.
      t - How far between the two values to interpolate. This is clamped to [0, 1].
      Returns:
      The interpolated value.
    • cosineScale

      public void cosineScale(Rotation2d currentAngle)
      Scales velocity 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.