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.doubleCurrent state.private final SwerveMotorSwerve Motors.private final doubleAngle offset from the absolute encoder.Swerve module configuration options.private final SwerveMotorSwerve Motors.doubleCurrent state.doubleCurrent state.edu.wpi.first.math.controller.SimpleMotorFeedforwardFeedforward for drive motor during closed loop control.doubleLast angle set for the swerve module.doubleCurrent state.intModule number for kinematics, usually 0 to 3.doubleCurrent state.doubleCurrent state.private edu.wpi.first.wpilibj.TimerTimer for simulation. -
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.edu.wpi.first.math.kinematics.SwerveModulePositionGet the position of the swerve module.doubleGet the relative angle in degrees.getState()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.voidSynchronize the integrated angle encoder with the absolute encoder.
-
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. -
angle
public double angleCurrent state. -
omega
public double omegaCurrent state. -
speed
public double speedCurrent state. -
fakePos
public double fakePosCurrent state. -
lastTime
public double lastTimeCurrent state. -
dt
public double dtCurrent state. -
time
private edu.wpi.first.wpilibj.Timer timeTimer for simulation.
-
-
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
-
synchronizeEncoders
public void synchronizeEncoders()Synchronize the integrated angle encoder with the absolute encoder. -
setDesiredState
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
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.- Returns:
- Absolute encoder angle in degrees.
-
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.
-