Robot Core Documentation
|
Public Member Functions | |
SwerveModulePosition () | |
SwerveModulePosition (double distanceMeters, Rotation2d angle) | |
SwerveModulePosition (Measure< Distance > distance, Rotation2d angle) | |
int | compareTo (SwerveModulePosition other) |
SwerveModulePosition | copy () |
![]() | |
T | interpolate (T endValue, double t) |
Public Attributes | |
double | distanceMeters |
Rotation2d | angle = Rotation2d.fromDegrees(0) |
Static Public Attributes | |
static final SwerveModulePositionProto | proto = new SwerveModulePositionProto() |
static final SwerveModulePositionStruct | struct = new SwerveModulePositionStruct() |
Represents the state of one swerve module.
edu.wpi.first.math.kinematics.SwerveModulePosition.SwerveModulePosition | ( | ) |
Constructs a SwerveModulePosition with zeros for distance and angle.
edu.wpi.first.math.kinematics.SwerveModulePosition.SwerveModulePosition | ( | double | distanceMeters, |
Rotation2d | angle ) |
Constructs a SwerveModulePosition.
distanceMeters | The distance measured by the wheel of the module. |
angle | The angle of the module. |
edu.wpi.first.math.kinematics.SwerveModulePosition.SwerveModulePosition | ( | Measure< Distance > | distance, |
Rotation2d | angle ) |
Constructs a SwerveModulePosition.
distance | The distance measured by the wheel of the module. |
angle | The angle of the module. |
int edu.wpi.first.math.kinematics.SwerveModulePosition.compareTo | ( | SwerveModulePosition | other | ) |
Compares two swerve module positions. One swerve module is "greater" than the other if its distance is higher than the other.
other | The other swerve module. |
SwerveModulePosition edu.wpi.first.math.kinematics.SwerveModulePosition.copy | ( | ) |
Returns a copy of this swerve module position.
Rotation2d edu.wpi.first.math.kinematics.SwerveModulePosition.angle = Rotation2d.fromDegrees(0) |
Angle of the module.
double edu.wpi.first.math.kinematics.SwerveModulePosition.distanceMeters |
Distance measured by the wheel of the module.
|
static |
SwerveModulePosition protobuf for serialization.
|
static |
SwerveModulePosition struct for serialization.