Package swervelib
Class SwerveModule
java.lang.Object
swervelib.SwerveModule
The Swerve Module class which represents and controls Swerve Modules for the swerve drive.
-
Field Summary
Modifier and TypeFieldDescriptionprivate final SwerveAbsoluteEncoder
Absolute encoder for swerve drive.private final String
NT3 Absolute encoder read issue.Absolute encoder position cache.private final String
NT3 Adjusted Absolute angle publisher for the absolute encoder.private final SwerveMotor
Swerve Motors.private double
Angle offset from the absolute encoder.private boolean
Anti-Jitter AKA auto-centering disabled.Swerve module configuration options.private final SwerveMotor
Swerve Motors.private edu.wpi.first.math.controller.SimpleMotorFeedforward
Feedforward for the drive motor during closed loop control.Drive motor position cache.Drive motor velocity cache.private final Alert
AnAlert
for if pushing the Absolute Encoder offset to the encoder fails.private edu.wpi.first.math.kinematics.SwerveModuleState
Last swerve module state applied.double
Maximum speed of the drive motors in meters per second.int
Module number for kinematics, usually 0 to 3.private final Alert
AnAlert
for if there is no Absolute Encoder on the module.private final String
NT3 Raw Absolute Angle publisher for the absolute encoder.private final String
NT3 raw angle motor.private final String
NT3 Raw drive motor.private SwerveModuleSimulation
Simulated swerve module.private boolean
Encoder synchronization queued. -
Constructor Summary
ConstructorDescriptionSwerveModule
(int moduleNumber, SwerveModuleConfiguration moduleConfiguration, edu.wpi.first.math.controller.SimpleMotorFeedforward driveFeedforward) Construct the swerve module and initialize the swerve module motors and absolute encoder. -
Method Summary
Modifier and TypeMethodDescriptionGet theSwerveAbsoluteEncoder
for theSwerveModule
.boolean
Get if the last Absolute Encoder had a read issue, such as it does not exist.double
Get the absolute position.Get the angleSwerveMotor
for theSwerveModule
.Get the current angle/azimuth/steering motor PIDF values.Fetch theSwerveModuleConfiguration
for theSwerveModule
with the parsed configurations.private double
getCosineCompensatedVelocity
(edu.wpi.first.math.kinematics.SwerveModuleState desiredState) Get the cosine compensated velocity to set the swerve module to.Get the driveSwerveMotor
for theSwerveModule
.Get the current drive motor PIDF values.edu.wpi.first.math.kinematics.SwerveModulePosition
Get the position of the swerve module.double
Get the absolute position.double
Get the relative angle in degrees.edu.wpi.first.math.kinematics.SwerveModuleState
getState()
Get the Swerve Module state.void
Push absolute encoder offset in the memory of the encoder or controller.void
Queue synchronization of the integrated angle encoder with the absolute encoder.void
Restore internal offset in YAGSL and either sets absolute encoder offset to 0 or restores old value.void
setAngle
(double angle) Set the angle for the module.void
setAngleMotorConversionFactor
(double conversionFactor) Set the conversion factor for the angle/azimuth motor controller.void
setAngleMotorVoltageCompensation
(double optimalVoltage) Set the voltage compensation for the swerve module motor.void
setAnglePIDF
(PIDFConfig config) Set the angle/azimuth/steering motor PIDvoid
setAntiJitter
(boolean antiJitter) Set the antiJitter functionality, if true the modules will NOT auto center.void
setDesiredState
(edu.wpi.first.math.kinematics.SwerveModuleState desiredState, boolean isOpenLoop, boolean force) Set the desired state of the swerve module.void
setDriveMotorConversionFactor
(double conversionFactor) Set the conversion factor for the drive motor controller.void
setDriveMotorVoltageCompensation
(double optimalVoltage) Set the voltage compensation for the swerve module motor.void
setDrivePIDF
(PIDFConfig config) Set the drive PIDF values.void
setFeedforward
(edu.wpi.first.math.controller.SimpleMotorFeedforward drive) Set the feedforward attributes to the given parameters.void
setMotorBrake
(boolean brake) Set the brake mode.void
Update data sent toSmartDashboard
.
-
Field Details
-
configuration
Swerve module configuration options. -
absolutePositionCache
Absolute encoder position cache. -
drivePositionCache
Drive motor position cache. -
driveVelocityCache
Drive motor velocity cache. -
angleMotor
Swerve Motors. -
driveMotor
Swerve Motors. -
absoluteEncoder
Absolute encoder for swerve drive. -
encoderOffsetWarning
AnAlert
for if pushing the Absolute Encoder offset to the encoder fails. -
noEncoderWarning
AnAlert
for if there is no Absolute Encoder on the module. -
rawAbsoluteAngleName
NT3 Raw Absolute Angle publisher for the absolute encoder. -
adjAbsoluteAngleName
NT3 Adjusted Absolute angle publisher for the absolute encoder. -
absoluteEncoderIssueName
NT3 Absolute encoder read issue. -
rawAngleName
NT3 raw angle motor. -
rawDriveName
NT3 Raw drive motor. -
moduleNumber
public int moduleNumberModule number for kinematics, usually 0 to 3. front left -> front right -> back left -> back right. -
driveMotorFeedforward
private edu.wpi.first.math.controller.SimpleMotorFeedforward driveMotorFeedforwardFeedforward for the drive motor during closed loop control. -
maxSpeed
public double maxSpeedMaximum speed of the drive motors in meters per second. -
antiJitterEnabled
private boolean antiJitterEnabledAnti-Jitter AKA auto-centering disabled. -
lastState
private edu.wpi.first.math.kinematics.SwerveModuleState lastStateLast swerve module state applied. -
angleOffset
private double angleOffsetAngle offset from the absolute encoder. -
simModule
Simulated swerve module. -
synchronizeEncoderQueued
private boolean synchronizeEncoderQueuedEncoder synchronization queued.
-
-
Constructor Details
-
SwerveModule
public SwerveModule(int moduleNumber, SwerveModuleConfiguration moduleConfiguration, edu.wpi.first.math.controller.SimpleMotorFeedforward driveFeedforward) Construct the swerve module and initialize the swerve module motors and absolute encoder.- Parameters:
moduleNumber
- Module number for kinematics.moduleConfiguration
- Module constants containing CAN ID's and offsets.driveFeedforward
- Drive motor feedforward created bySwerveMath.createDriveFeedforward(double, double, double)
.
-
-
Method Details
-
setAngleMotorVoltageCompensation
public void setAngleMotorVoltageCompensation(double optimalVoltage) Set the voltage compensation for the swerve module motor.- Parameters:
optimalVoltage
- Nominal voltage for operation to output to.
-
setDriveMotorVoltageCompensation
public void setDriveMotorVoltageCompensation(double optimalVoltage) Set the voltage compensation for the swerve module motor.- Parameters:
optimalVoltage
- Nominal voltage for operation to output to.
-
queueSynchronizeEncoders
public void queueSynchronizeEncoders()Queue synchronization of the integrated angle encoder with the absolute encoder. -
setAntiJitter
public void setAntiJitter(boolean antiJitter) Set the antiJitter functionality, if true the modules will NOT auto center. Pushes the offsets to the angle motor controllers as well.- Parameters:
antiJitter
- Anti-Jitter state desired.
-
setFeedforward
public void setFeedforward(edu.wpi.first.math.controller.SimpleMotorFeedforward drive) Set the feedforward attributes to the given parameters.- Parameters:
drive
- Drive motor feedforward for the module.
-
setDrivePIDF
Set the drive PIDF values.- Parameters:
config
-PIDFConfig
of that should be set.
-
getDrivePIDF
Get the current drive motor PIDF values.- Returns:
PIDFConfig
of the drive motor.
-
setAnglePIDF
Set the angle/azimuth/steering motor PID- Parameters:
config
-PIDFConfig
of that should be set.
-
getAnglePIDF
Get the current angle/azimuth/steering motor PIDF values.- Returns:
PIDFConfig
of the angle motor.
-
setDesiredState
public void setDesiredState(edu.wpi.first.math.kinematics.SwerveModuleState desiredState, boolean isOpenLoop, boolean force) Set the desired state of the swerve module.
WARNING: If you are not using one of the functions fromSwerveDrive
you may screw upSwerveDrive.kinematics
- Parameters:
desiredState
- Desired swerve module state.isOpenLoop
- Whether to use open loop (direct percent) or direct velocity control.force
- Disables optimizations that prevent movement in the angle motor and forces the desired state onto the swerve module.
-
getCosineCompensatedVelocity
private double getCosineCompensatedVelocity(edu.wpi.first.math.kinematics.SwerveModuleState desiredState) Get the cosine compensated velocity to set the swerve module to.- Parameters:
desiredState
- DesiredSwerveModuleState
to use.- Returns:
- Cosine compensated velocity in meters/second.
-
setAngle
public void setAngle(double angle) Set the angle for the module.- Parameters:
angle
- Angle in degrees.
-
getState
public edu.wpi.first.math.kinematics.SwerveModuleState getState()Get the Swerve Module state.- Returns:
- Current SwerveModule state.
-
getPosition
public edu.wpi.first.math.kinematics.SwerveModulePosition getPosition()Get the position of the swerve module.- Returns:
SwerveModulePosition
of the swerve module.
-
getAbsolutePosition
public double getAbsolutePosition()Get the absolute position. Falls back to relative position on reading failure.- Returns:
- Absolute encoder angle in degrees in the range [0, 360).
-
getRawAbsolutePosition
public double getRawAbsolutePosition()Get the absolute position. Falls back to relative position on reading failure.- Returns:
- Absolute encoder angle in degrees in the range [0, 360).
-
getRelativePosition
public double getRelativePosition()Get the relative angle in degrees.- Returns:
- Angle in degrees.
-
setMotorBrake
public void setMotorBrake(boolean brake) Set the brake mode.- Parameters:
brake
- Set the brake mode.
-
setAngleMotorConversionFactor
public void setAngleMotorConversionFactor(double conversionFactor) Set the conversion factor for the angle/azimuth motor controller.- Parameters:
conversionFactor
- Angle motor conversion factor for PID, should be generated fromSwerveMath.calculateDegreesPerSteeringRotation(double, double)
or calculated.
-
setDriveMotorConversionFactor
public void setDriveMotorConversionFactor(double conversionFactor) Set the conversion factor for the drive motor controller.- Parameters:
conversionFactor
- Drive motor conversion factor for PID, should be generated fromSwerveMath.calculateMetersPerRotation(double, double, double)
or calculated.
-
getAngleMotor
Get the angleSwerveMotor
for theSwerveModule
.- Returns:
SwerveMotor
for the angle/steering motor of the module.
-
getDriveMotor
Get the driveSwerveMotor
for theSwerveModule
.- Returns:
SwerveMotor
for the drive motor of the module.
-
getAbsoluteEncoder
Get theSwerveAbsoluteEncoder
for theSwerveModule
.- Returns:
SwerveAbsoluteEncoder
for the swerve module.
-
getConfiguration
Fetch theSwerveModuleConfiguration
for theSwerveModule
with the parsed configurations.- Returns:
SwerveModuleConfiguration
for theSwerveModule
.
-
pushOffsetsToControllers
public void pushOffsetsToControllers()Push absolute encoder offset in the memory of the encoder or controller. Also removes the internal angle offset. -
restoreInternalOffset
public void restoreInternalOffset()Restore internal offset in YAGSL and either sets absolute encoder offset to 0 or restores old value. -
getAbsoluteEncoderReadIssue
public boolean getAbsoluteEncoderReadIssue()Get if the last Absolute Encoder had a read issue, such as it does not exist.- Returns:
- If the last Absolute Encoder had a read issue, or absolute encoder does not exist.
-
updateTelemetry
public void updateTelemetry()Update data sent toSmartDashboard
.
-