Package edu.wpi.first.math.kinematics
Class SwerveModuleState
java.lang.Object
edu.wpi.first.math.kinematics.SwerveModuleState
- All Implemented Interfaces:
Comparable<SwerveModuleState>
public class SwerveModuleState extends Object implements Comparable<SwerveModuleState>
Represents the state of one swerve module.
-
Field Summary
Fields Modifier and Type Field Description Rotation2d
angle
Angle of the module.double
speedMetersPerSecond
Speed of the wheel of the module. -
Constructor Summary
Constructors Constructor Description SwerveModuleState()
Constructs a SwerveModuleState with zeros for speed and angle.SwerveModuleState(double speedMetersPerSecond, Rotation2d angle)
Constructs a SwerveModuleState. -
Method Summary
Modifier and Type Method Description int
compareTo(SwerveModuleState other)
Compares two swerve module states.boolean
equals(Object obj)
int
hashCode()
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.String
toString()
-
Field Details
-
speedMetersPerSecond
Speed of the wheel of the module. -
angle
Angle of the module.
-
-
Constructor Details
-
SwerveModuleState
public SwerveModuleState()Constructs a SwerveModuleState with zeros for speed and angle. -
SwerveModuleState
Constructs a SwerveModuleState.- Parameters:
speedMetersPerSecond
- The speed of the wheel of the module.angle
- The angle of the module.
-
-
Method Details
-
equals
-
hashCode
-
compareTo
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 interfaceComparable<SwerveModuleState>
- Parameters:
other
- The other swerve module.- Returns:
- 1 if this is greater, 0 if both are equal, -1 if other is greater.
-
toString
-
optimize
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.
-