Class SwerveModuleState2

java.lang.Object
edu.wpi.first.math.kinematics.SwerveModuleState
swervelib.math.SwerveModuleState2
All Implemented Interfaces:
Comparable<edu.wpi.first.math.kinematics.SwerveModuleState>

public class SwerveModuleState2 extends edu.wpi.first.math.kinematics.SwerveModuleState
Second order kinematics swerve module state.
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    edu.wpi.first.math.geometry.Rotation2d
    Swerve module angle as a Rotation2d.
    double
    Rad per sec
    double
    Swerve module speed in meters per second.
  • Constructor Summary

    Constructors
    Constructor
    Description
    Constructs a SwerveModuleState with zeros for speed and angle.
    SwerveModuleState2(double speedMetersPerSecond, edu.wpi.first.math.geometry.Rotation2d angle, double omegaRadPerSecond)
    Constructs a SwerveModuleState.
  • Method Summary

    Methods inherited from class edu.wpi.first.math.kinematics.SwerveModuleState

    compareTo, equals, hashCode, optimize, toString

    Methods inherited from class java.lang.Object

    clone, finalize, getClass, notify, notifyAll, wait, wait, wait
  • Field Details

    • speedMetersPerSecond

      public double speedMetersPerSecond
      Swerve module speed in meters per second.
    • omegaRadPerSecond

      public double omegaRadPerSecond
      Rad per sec
    • angle

      public edu.wpi.first.math.geometry.Rotation2d angle
      Swerve module angle as a Rotation2d.
  • Constructor Details

    • SwerveModuleState2

      public SwerveModuleState2()
      Constructs a SwerveModuleState with zeros for speed and angle.
    • SwerveModuleState2

      public SwerveModuleState2(double speedMetersPerSecond, edu.wpi.first.math.geometry.Rotation2d angle, double omegaRadPerSecond)
      Constructs a SwerveModuleState.
      Parameters:
      speedMetersPerSecond - The speed of the wheel of the module.
      angle - The angle of the module.
      omegaRadPerSecond - The angular velocity of the module.