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 final 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.doubleLast angle set for the swerve module.doubleLast velocity set for the swerve module.intModule number for kinematics, usually 0 to 3.private SwerveModuleSimulationSimulated swerve module.private booleanEncoder synchronization queued. -
Constructor Summary
ConstructorsConstructorDescriptionSwerveModule(int moduleNumber, SwerveModuleConfiguration moduleConfiguration) Construct the swerve module and initialize the swerve module motors and absolute encoder. -
Method Summary
Modifier and TypeMethodDescriptiondoubleGet 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.getState()Get the Swerve Module state.voidQueue synchronization of the integrated angle encoder with the absolute encoder.voidsetAngle(double angle) Set the angle for the module.voidsetDesiredState(SwerveModuleState2 desiredState, boolean isOpenLoop, boolean force) Set the desired state of the swerve module.voidsetMotorBrake(boolean brake) Set the brake mode.
-
Field Details
-
configuration
Swerve module configuration options. -
angleOffset
private final double angleOffsetAngle offset from the absolute encoder. -
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. -
lastAngle
public double lastAngleLast angle set for the swerve module. -
lastVelocity
public double lastVelocityLast velocity set for the swerve module. -
simModule
Simulated swerve module. -
synchronizeEncoderQueued
private boolean synchronizeEncoderQueuedEncoder synchronization queued.
-
-
Constructor Details
-
SwerveModule
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.
-
-
Method Details
-
queueSynchronizeEncoders
public void queueSynchronizeEncoders()Queue synchronization of the integrated angle encoder with the absolute encoder. -
setDesiredState
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
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.
-
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.
-