Robot Core Documentation
|
Public Member Functions | |
SwerveModuleState () | |
SwerveModuleState (double speedMetersPerSecond, Rotation2d angle) | |
SwerveModuleState (Measure< Velocity< Distance > > speed, Rotation2d angle) | |
int | compareTo (SwerveModuleState other) |
Static Public Member Functions | |
static SwerveModuleState | optimize (SwerveModuleState desiredState, Rotation2d currentAngle) |
Public Attributes | |
double | speedMetersPerSecond |
Rotation2d | angle = Rotation2d.fromDegrees(0) |
Static Public Attributes | |
static final SwerveModuleStateProto | proto = new SwerveModuleStateProto() |
static final SwerveModuleStateStruct | struct = new SwerveModuleStateStruct() |
Represents the state of one swerve module.
edu.wpi.first.math.kinematics.SwerveModuleState.SwerveModuleState | ( | ) |
Constructs a SwerveModuleState with zeros for speed and angle.
edu.wpi.first.math.kinematics.SwerveModuleState.SwerveModuleState | ( | double | speedMetersPerSecond, |
Rotation2d | angle ) |
Constructs a SwerveModuleState.
speedMetersPerSecond | The speed of the wheel of the module. |
angle | The angle of the module. |
edu.wpi.first.math.kinematics.SwerveModuleState.SwerveModuleState | ( | Measure< Velocity< Distance > > | speed, |
Rotation2d | angle ) |
Constructs a SwerveModuleState.
speed | The speed of the wheel of the module. |
angle | The angle of the module. |
int edu.wpi.first.math.kinematics.SwerveModuleState.compareTo | ( | SwerveModuleState | other | ) |
Compares two swerve module states. One swerve module is "greater" than the other if its speed is higher than the other.
other | The other swerve module. |
|
static |
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.
desiredState | The desired state. |
currentAngle | The current module angle. |
Rotation2d edu.wpi.first.math.kinematics.SwerveModuleState.angle = Rotation2d.fromDegrees(0) |
Angle of the module.
|
static |
SwerveModuleState protobuf for serialization.
double edu.wpi.first.math.kinematics.SwerveModuleState.speedMetersPerSecond |
Speed of the wheel of the module.
|
static |
SwerveModuleState struct for serialization.