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
FieldsModifier and TypeFieldDescriptionprivate final SwerveAbsoluteEncoderAbsolute encoder for swerve drive.private final SwerveMotorSwerve Motors.private doubleAngle offset from the absolute encoder.Swerve module configuration options.private final SwerveMotorSwerve Motors.edu.wpi.first.math.controller.SimpleMotorFeedforwardFeedforward for drive motor during closed loop control.edu.wpi.first.math.kinematics.SwerveModuleStateLast swerve module state applied.doubleMaximum speed of the drive motors in meters per second.intModule number for kinematics, usually 0 to 3.private SwerveModuleSimulationSimulated swerve module.private booleanEncoder synchronization queued. -
Constructor Summary
ConstructorsConstructorDescriptionSwerveModule(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 TypeMethodDescriptionbooleanGet if the last Absolute Encoder had a read issue, such as it does not exist.doubleGet the absolute position.Get the angleSwerveMotorfor theSwerveModule.Fetch theSwerveModuleConfigurationfor theSwerveModulewith the parsed configurations.Get the driveSwerveMotorfor theSwerveModule.edu.wpi.first.math.kinematics.SwerveModulePositionGet the position of the swerve module.doubleGet the relative angle in degrees.edu.wpi.first.math.kinematics.SwerveModuleStategetState()Get the Swerve Module state.voidPush absolute encoder offset in the memory of the encoder or controller.voidQueue synchronization of the integrated angle encoder with the absolute encoder.voidRestore internal offset in YAGSL and either sets absolute encoder offset to 0 or restores old value.voidsetAngle(double angle) Set the angle for the module.voidsetAngleMotorConversionFactor(double conversionFactor) Set the conversion factor for the angle/azimuth motor controller.voidsetAngleMotorVoltageCompensation(double optimalVoltage) Set the voltage compensation for the swerve module motor.voidsetDesiredState(edu.wpi.first.math.kinematics.SwerveModuleState desiredState, boolean isOpenLoop, boolean force) Set the desired state of the swerve module.voidsetDriveMotorConversionFactor(double conversionFactor) Set the conversion factor for the drive motor controller.voidsetDriveMotorVoltageCompensation(double optimalVoltage) Set the voltage compensation for the swerve module motor.voidsetMotorBrake(boolean brake) Set the brake mode.voidUpdate data sent toSmartDashboard.
-
Field Details
-
configuration
Swerve module configuration options. -
angleMotor
Swerve Motors. -
driveMotor
Swerve Motors. -
absoluteEncoder
Absolute encoder for swerve drive. -
moduleNumber
public int moduleNumberModule number for kinematics, usually 0 to 3. front left -> front right -> back left -> back right. -
feedforward
public edu.wpi.first.math.controller.SimpleMotorFeedforward feedforwardFeedforward for drive motor during closed loop control. -
maxSpeed
public double maxSpeedMaximum speed of the drive motors in meters per second. -
lastState
public 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. -
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 fromSwerveDriveyou 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
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:
SwerveModulePositionof 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).
-
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 angleSwerveMotorfor theSwerveModule.- Returns:
SwerveMotorfor the angle/steering motor of the module.
-
getDriveMotor
Get the driveSwerveMotorfor theSwerveModule.- Returns:
SwerveMotorfor the drive motor of the module.
-
getConfiguration
Fetch theSwerveModuleConfigurationfor theSwerveModulewith the parsed configurations.- Returns:
SwerveModuleConfigurationfor 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.
-