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

      public final Cache<Double> absolutePositionCache
      Absolute encoder position cache.
    • drivePositionCache

      public final Cache<Double> drivePositionCache
      Drive motor position cache.
    • driveVelocityCache

      public final Cache<Double> driveVelocityCache
      Drive motor velocity cache.
    • angleMotor

      private final SwerveMotor angleMotor
      Swerve Motors.
    • driveMotor

      private final SwerveMotor driveMotor
      Swerve Motors.
    • absoluteEncoder

      private final SwerveAbsoluteEncoder absoluteEncoder
      Absolute encoder for swerve drive.
    • encoderOffsetWarning

      private final Alert encoderOffsetWarning
      An Alert for if pushing the Absolute Encoder offset to the encoder fails.
    • noEncoderWarning

      private final Alert noEncoderWarning
      An Alert for if there is no Absolute Encoder on the module.
    • 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.
    • maxSpeed

      public double maxSpeed
      Maximum speed of the drive motors in meters per second.
    • lastState

      private edu.wpi.first.math.kinematics.SwerveModuleState lastState
      Last swerve module state applied.
    • angleOffset

      private double angleOffset
      Angle offset from the absolute encoder.
    • simModule

      private SwerveModuleSimulation simModule
      Simulated swerve module.
    • synchronizeEncoderQueued

      private boolean synchronizeEncoderQueued
      Encoder 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 by SwerveMath.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 from SwerveDrive you may screw up SwerveDrive.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.
    • getCosineCompensatedVelocity

      private double getCosineCompensatedVelocity(edu.wpi.first.math.kinematics.SwerveModuleState desiredState)
      Get the cosine compensated velocity to set the swerve module to.
      Parameters:
      desiredState - Desired SwerveModuleState to use.
      Returns:
      Cosine compensated velocity in meters/second.
    • 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:
      SwerveModulePosition of 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).
    • getRawAbsolutePosition

      public double getRawAbsolutePosition()
      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 from SwerveMath.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 from SwerveMath.calculateMetersPerRotation(double, double, double) or calculated.
    • getAngleMotor

      public SwerveMotor getAngleMotor()
      Get the angle SwerveMotor for the SwerveModule.
      Returns:
      SwerveMotor for the angle/steering motor of the module.
    • getDriveMotor

      public SwerveMotor getDriveMotor()
      Get the drive SwerveMotor for the SwerveModule.
      Returns:
      SwerveMotor for the drive motor of the module.
    • getAbsoluteEncoder

      public SwerveAbsoluteEncoder getAbsoluteEncoder()
      Returns:
      SwerveAbsoluteEncoder for the swerve module.
    • getConfiguration

      public SwerveModuleConfiguration getConfiguration()
      Fetch the SwerveModuleConfiguration for the SwerveModule with the parsed configurations.
      Returns:
      SwerveModuleConfiguration for the SwerveModule.
    • 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 to SmartDashboard.