Package swervelib
Class SwerveModule
- java.lang.Object
-
- swervelib.SwerveModule
-
public class SwerveModule extends Object
The Swerve Module class which represents and controls Swerve Modules for the swerve drive.
-
-
Field Summary
Fields Modifier and Type Field Description private SwerveAbsoluteEncoderabsoluteEncoderAbsolute encoder for swerve drive.doubleangleCurrent state.private SwerveMotorangleMotorSwerve Motors.private doubleangleOffsetAngle offset from the absolute encoder.SwerveModuleConfigurationconfigurationSwerve module configuration options.private SwerveMotordriveMotorSwerve Motors.doubledtCurrent state.doublefakePosCurrent state.edu.wpi.first.math.controller.SimpleMotorFeedforwardfeedforwardFeedforward for drive motor during closed loop control.doublelastAngleLast angle set for the swerve module.doublelastTimeCurrent state.intmoduleNumberModule number for kinematics, usually 0 to 3.doubleomegaCurrent state.doublespeedCurrent state.private edu.wpi.first.wpilibj.TimertimeTimer for simulation.
-
Constructor Summary
Constructors Constructor Description SwerveModule(int moduleNumber, SwerveModuleConfiguration moduleConfiguration)Construct the swerve module and initialize the swerve module motors and absolute encoder.
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description doublegetCANCoder()Get the CANCoder absolute position.edu.wpi.first.math.kinematics.SwerveModulePositiongetPosition()doublegetRelativeEncoder()Get the relative encoder angle in degrees.SwerveModuleState2getState()Get the Swerve Module state.voidsetAngle(double angle)Set the angle for the module.voidsetDesiredState(SwerveModuleState2 desiredState, boolean isOpenLoop)Set the desired state of the swerve module.voidsetMotorBrake(boolean brake)Set the brake mode.voidsynchronizeEncoders()Synchronize the integrated angle encoder with the absolute encoder.
-
-
-
Field Detail
-
configuration
public final SwerveModuleConfiguration configuration
Swerve module configuration options.
-
angleOffset
private final double angleOffset
Angle offset from the absolute encoder.
-
angleMotor
private final SwerveMotor angleMotor
Swerve Motors.
-
driveMotor
private final SwerveMotor driveMotor
Swerve Motors.
-
absoluteEncoder
private final SwerveAbsoluteEncoder absoluteEncoder
Absolute encoder for swerve drive.
-
moduleNumber
public int moduleNumber
Module number for kinematics, usually 0 to 3. front left -> front right -> back left -> back right.
-
feedforward
public edu.wpi.first.math.controller.SimpleMotorFeedforward feedforward
Feedforward for drive motor during closed loop control.
-
lastAngle
public double lastAngle
Last angle set for the swerve module.
-
angle
public double angle
Current state.
-
omega
public double omega
Current state.
-
speed
public double speed
Current state.
-
fakePos
public double fakePos
Current state.
-
lastTime
public double lastTime
Current state.
-
dt
public double dt
Current state.
-
time
private edu.wpi.first.wpilibj.Timer time
Timer for simulation.
-
-
Constructor Detail
-
SwerveModule
public SwerveModule(int moduleNumber, SwerveModuleConfiguration moduleConfiguration)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 Detail
-
synchronizeEncoders
public void synchronizeEncoders()
Synchronize the integrated angle encoder with the absolute encoder.
-
setDesiredState
public void setDesiredState(SwerveModuleState2 desiredState, boolean isOpenLoop)
Set the desired state of the swerve module.- Parameters:
desiredState- Desired swerve module state.isOpenLoop- Whether to use open loop (direct percent) or direct velocity control.
-
setAngle
public void setAngle(double angle)
Set the angle for the module.- Parameters:
angle- Angle in degrees.
-
getState
public SwerveModuleState2 getState()
Get the Swerve Module state.- Returns:
- Current SwerveModule state.
-
getPosition
public edu.wpi.first.math.kinematics.SwerveModulePosition getPosition()
-
getCANCoder
public double getCANCoder()
Get the CANCoder absolute position.- Returns:
- Absolute encoder angle in degrees.
-
getRelativeEncoder
public double getRelativeEncoder()
Get the relative encoder angle in degrees.- Returns:
- Angle in degrees.
-
setMotorBrake
public void setMotorBrake(boolean brake)
Set the brake mode.- Parameters:
brake- Set the brake mode.
-
-