Package edu.wpi.first.math.kinematics
Class SwerveModulePosition
java.lang.Object
edu.wpi.first.math.kinematics.SwerveModulePosition
- All Implemented Interfaces:
Interpolatable<SwerveModulePosition>,ProtobufSerializable,StructSerializable,WPISerializable,Comparable<SwerveModulePosition>
public class SwerveModulePosition
extends Object
implements Comparable<SwerveModulePosition>, Interpolatable<SwerveModulePosition>, ProtobufSerializable, StructSerializable
Represents the state of one swerve module.
-
Field Summary
FieldsModifier and TypeFieldDescriptionAngle of the module.doubleDistance measured by the wheel of the module.static final SwerveModulePositionProtoSwerveModulePosition protobuf for serialization.static final SwerveModulePositionStructSwerveModulePosition struct for serialization. -
Constructor Summary
ConstructorsConstructorDescriptionConstructs a SwerveModulePosition with zeros for distance and angle.SwerveModulePosition(double distanceMeters, Rotation2d angle) Constructs a SwerveModulePosition.SwerveModulePosition(Distance distance, Rotation2d angle) Constructs a SwerveModulePosition. -
Method Summary
Modifier and TypeMethodDescriptionintcompareTo(SwerveModulePosition other) Compares two swerve module positions.copy()Returns a copy of this swerve module position.booleaninthashCode()interpolate(SwerveModulePosition endValue, double t) Return the interpolated value.toString()
-
Field Details
-
distanceMeters
Distance measured by the wheel of the module. -
angle
Angle of the module. -
proto
SwerveModulePosition protobuf for serialization. -
struct
SwerveModulePosition struct for serialization.
-
-
Constructor Details
-
SwerveModulePosition
public SwerveModulePosition()Constructs a SwerveModulePosition with zeros for distance and angle. -
SwerveModulePosition
Constructs a SwerveModulePosition.- Parameters:
distanceMeters- The distance measured by the wheel of the module.angle- The angle of the module.
-
SwerveModulePosition
Constructs a SwerveModulePosition.- Parameters:
distance- 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 distance is higher than the other.- Specified by:
compareToin 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
-
copy
Returns a copy of this swerve module position.- Returns:
- A copy.
-
interpolate
Description copied from interface:InterpolatableReturn the interpolated value. This object is assumed to be the starting position, or lower bound.- Specified by:
interpolatein interfaceInterpolatable<SwerveModulePosition>- Parameters:
endValue- The upper bound, or end.t- How far between the lower and upper bound we are. This should be bounded in [0, 1].- Returns:
- The interpolated value.
-