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 Details

    • 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.
    • simModule

      private SwerveModuleSimulation simModule
      Simulated swerve module.
  • Constructor Details

    • 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 Details

    • 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()
      Get the position of the swerve module.
      Returns:
      SwerveModulePosition of 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.