Robot Core Documentation
Loading...
Searching...
No Matches
edu.wpi.first.math.kinematics.SwerveModulePosition Class Reference
Inheritance diagram for edu.wpi.first.math.kinematics.SwerveModulePosition:
edu.wpi.first.math.interpolation.Interpolatable< T > edu.wpi.first.util.protobuf.ProtobufSerializable edu.wpi.first.util.struct.StructSerializable edu.wpi.first.util.WPISerializable edu.wpi.first.util.WPISerializable

Public Member Functions

 SwerveModulePosition ()
 
 SwerveModulePosition (double distanceMeters, Rotation2d angle)
 
 SwerveModulePosition (Measure< Distance > distance, Rotation2d angle)
 
int compareTo (SwerveModulePosition other)
 
SwerveModulePosition copy ()
 
- Public Member Functions inherited from edu.wpi.first.math.interpolation.Interpolatable< 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()
 

Detailed Description

Represents the state of one swerve module.

Constructor & Destructor Documentation

◆ SwerveModulePosition() [1/3]

edu.wpi.first.math.kinematics.SwerveModulePosition.SwerveModulePosition ( )

Constructs a SwerveModulePosition with zeros for distance and angle.

◆ SwerveModulePosition() [2/3]

edu.wpi.first.math.kinematics.SwerveModulePosition.SwerveModulePosition ( double distanceMeters,
Rotation2d angle )

Constructs a SwerveModulePosition.

Parameters
distanceMetersThe distance measured by the wheel of the module.
angleThe angle of the module.

◆ SwerveModulePosition() [3/3]

edu.wpi.first.math.kinematics.SwerveModulePosition.SwerveModulePosition ( Measure< Distance > distance,
Rotation2d angle )

Constructs a SwerveModulePosition.

Parameters
distanceThe distance measured by the wheel of the module.
angleThe angle of the module.

Member Function Documentation

◆ compareTo()

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.

Parameters
otherThe other swerve module.
Returns
1 if this is greater, 0 if both are equal, -1 if other is greater.

◆ copy()

SwerveModulePosition edu.wpi.first.math.kinematics.SwerveModulePosition.copy ( )

Returns a copy of this swerve module position.

Returns
A copy.

Member Data Documentation

◆ angle

Rotation2d edu.wpi.first.math.kinematics.SwerveModulePosition.angle = Rotation2d.fromDegrees(0)

Angle of the module.

◆ distanceMeters

double edu.wpi.first.math.kinematics.SwerveModulePosition.distanceMeters

Distance measured by the wheel of the module.

◆ proto

final SwerveModulePositionProto edu.wpi.first.math.kinematics.SwerveModulePosition.proto = new SwerveModulePositionProto()
static

SwerveModulePosition protobuf for serialization.

◆ struct

final SwerveModulePositionStruct edu.wpi.first.math.kinematics.SwerveModulePosition.struct = new SwerveModulePositionStruct()
static

SwerveModulePosition struct for serialization.


The documentation for this class was generated from the following file: