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 TypeFieldDescriptionAbsolute encoder position cache.Swerve module configuration options.Drive motor position cache.Drive motor velocity cache.double
Maximum speed of the drive motors in meters per second.final int
Module number for kinematics, usually 0 to 3. -
Constructor Summary
ConstructorDescriptionSwerveModule
(int moduleNumber, SwerveModuleConfiguration moduleConfiguration, 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.Get the driveSwerveMotor
for theSwerveModule
.Get the current drive motor PIDF values.Get the position of the swerve module.double
Get the absolute position.double
Get the relative angle in degrees.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
(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
setEncoderAutoSynchronize
(boolean enabled) Enable auto synchronization for encoders during a match.void
setEncoderAutoSynchronize
(boolean enabled, double deadband) Enable auto synchronization for encoders during a match.void
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. -
moduleNumber
public final int moduleNumberModule number for kinematics, usually 0 to 3. front left -> front right -> back left -> back right. -
maxSpeed
public double maxSpeedMaximum speed of the drive motors in meters per second.
-
-
Constructor Details
-
SwerveModule
public SwerveModule(int moduleNumber, SwerveModuleConfiguration moduleConfiguration, 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. -
setEncoderAutoSynchronize
public void setEncoderAutoSynchronize(boolean enabled, double deadband) Enable auto synchronization for encoders during a match. This will only occur when the modules are not moving for a few seconds.- Parameters:
enabled
- Enable statedeadband
- Deadband in degrees, default is 3 degrees.
-
setEncoderAutoSynchronize
public void setEncoderAutoSynchronize(boolean enabled) Enable auto synchronization for encoders during a match. This will only occur when the modules are not moving for a few seconds.- Parameters:
enabled
- Enable state
-
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
Set the feedforward attributes to the given parameters.- Parameters:
drive
- Drive motor feedforward for the module.
-
getDrivePIDF
Get the current drive motor PIDF values.- Returns:
PIDFConfig
of the drive motor.
-
setDrivePIDF
Set the drive PIDF values.- Parameters:
config
-PIDFConfig
of that should be set.
-
getAnglePIDF
Get the current angle/azimuth/steering motor PIDF values.- Returns:
PIDFConfig
of the angle motor.
-
setAnglePIDF
Set the angle/azimuth/steering motor PID- Parameters:
config
-PIDFConfig
of that should be set.
-
setDesiredState
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.
-
setAngle
public void setAngle(double angle) Set the angle for the module.- Parameters:
angle
- Angle in degrees.
-
getState
Get the Swerve Module state.- Returns:
- Current SwerveModule state.
-
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
.
-
pushOffsetsToEncoders
public void pushOffsetsToEncoders()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
.
-