Package edu.wpi.first.math.kinematics
Class SwerveModulePosition
java.lang.Object
edu.wpi.first.math.kinematics.SwerveModulePosition
- All Implemented Interfaces:
Comparable<SwerveModulePosition>
public class SwerveModulePosition extends Object implements Comparable<SwerveModulePosition>
Represents the state of one swerve module.
-
Field Summary
Fields Modifier and Type Field Description Rotation2d
angle
Angle of the module.double
distanceMeters
Distance measured by the wheel of the module. -
Constructor Summary
Constructors Constructor Description SwerveModulePosition()
Constructs a SwerveModulePosition with zeros for speed and angle.SwerveModulePosition(double distanceMeters, Rotation2d angle)
Constructs a SwerveModulePosition. -
Method Summary
-
Field Details
-
distanceMeters
Distance measured by the wheel of the module. -
angle
Angle of the module.
-
-
Constructor Details
-
SwerveModulePosition
public SwerveModulePosition()Constructs a SwerveModulePosition with zeros for speed and angle. -
SwerveModulePosition
Constructs a SwerveModulePosition.- Parameters:
distanceMeters
- The distance measured by the wheel of the module.angle
- The angle of the module.
-
-
Method Details
-
equals
-
hashCode
-
compareTo
Compares two swerve module positions. One swerve module is "greater" than the other if its speed is higher than the other.- Specified by:
compareTo
in interfaceComparable<SwerveModulePosition>
- Parameters:
other
- The other swerve module.- Returns:
- 1 if this is greater, 0 if both are equal, -1 if other is greater.
-
toString
-