Robot Core Documentation
Loading...
Searching...
No Matches
edu.wpi.first.math.kinematics.SwerveModuleState Class Reference
Inheritance diagram for edu.wpi.first.math.kinematics.SwerveModuleState:
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

 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()
 

Detailed Description

Represents the state of one swerve module.

Constructor & Destructor Documentation

◆ SwerveModuleState() [1/3]

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

Constructs a SwerveModuleState with zeros for speed and angle.

◆ SwerveModuleState() [2/3]

edu.wpi.first.math.kinematics.SwerveModuleState.SwerveModuleState ( double speedMetersPerSecond,
Rotation2d angle )

Constructs a SwerveModuleState.

Parameters
speedMetersPerSecondThe speed of the wheel of the module.
angleThe angle of the module.

◆ SwerveModuleState() [3/3]

edu.wpi.first.math.kinematics.SwerveModuleState.SwerveModuleState ( Measure< Velocity< Distance > > speed,
Rotation2d angle )

Constructs a SwerveModuleState.

Parameters
speedThe speed of the wheel of the module.
angleThe angle of the module.

Member Function Documentation

◆ compareTo()

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.

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

◆ optimize()

static SwerveModuleState edu.wpi.first.math.kinematics.SwerveModuleState.optimize ( SwerveModuleState desiredState,
Rotation2d currentAngle )
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.

Parameters
desiredStateThe desired state.
currentAngleThe current module angle.
Returns
Optimized swerve module state.

Member Data Documentation

◆ angle

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

Angle of the module.

◆ proto

final SwerveModuleStateProto edu.wpi.first.math.kinematics.SwerveModuleState.proto = new SwerveModuleStateProto()
static

SwerveModuleState protobuf for serialization.

◆ speedMetersPerSecond

double edu.wpi.first.math.kinematics.SwerveModuleState.speedMetersPerSecond

Speed of the wheel of the module.

◆ struct

final SwerveModuleStateStruct edu.wpi.first.math.kinematics.SwerveModuleState.struct = new SwerveModuleStateStruct()
static

SwerveModuleState struct for serialization.


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