Class SwerveModuleState

    • Constructor Detail

      • SwerveModuleState

        public 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.
    • Method Detail

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

        public static SwerveModuleState optimize​(SwerveModuleState desiredState,
                                                 Rotation2d currentAngle)
        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.