Package swervelib

Class SwerveModule

java.lang.Object
swervelib.SwerveModule
All Implemented Interfaces:
AutoCloseable

public class SwerveModule extends Object implements AutoCloseable
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.
    • moduleNumber

      public final int moduleNumber
      Module number for kinematics, usually 0 to 3. front left -> front right -> back left -> back right.
  • 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

    • close

      public void close()
      Specified by:
      close in interface AutoCloseable
    • getDefaultFeedforward

      public SimpleMotorFeedforward getDefaultFeedforward()
      Get the default SimpleMotorFeedforward for the swerve module drive motor.
      Returns:
      SimpleMotorFeedforward using motor details.
    • setModuleStateOptimization

      public void setModuleStateOptimization(boolean optimizationState)
      Set utilization of SwerveModuleState.optimize(Rotation2d) which should be disabled for some debugging.
      Parameters:
      optimizationState - Optimization enabled.
    • getModuleStateOptimization

      public boolean getModuleStateOptimization()
      Check if the module state optimization used by SwerveModuleState.optimize(Rotation2d) is enabled.
      Returns:
      optimization state.
    • 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.
    • setEncoderAutoSynchronize

      public void setEncoderAutoSynchronize(boolean enabled, double deadband)
      Enable auto synchronization for encoders during a match. This will only occur when the modules are not moving for a few seconds.
      Parameters:
      enabled - Enable state
      deadband - Deadband in degrees, default is 3 degrees.
    • setEncoderAutoSynchronize

      public void setEncoderAutoSynchronize(boolean enabled)
      Enable auto synchronization for encoders during a match. This will only occur when the modules are not moving for a few seconds.
      Parameters:
      enabled - Enable state
    • setAntiJitter

      public void setAntiJitter(boolean antiJitter)
      Set the antiJitter functionality, if true the modules will NOT auto center. Pushes the offsets to the angle motor controllers as well.
      Parameters:
      antiJitter - Anti-Jitter state desired.
    • setFeedforward

      public void setFeedforward(SimpleMotorFeedforward drive)
      Set the feedforward attributes to the given parameters.
      Parameters:
      drive - Drive motor feedforward for the module.
    • getDrivePIDF

      public PIDFConfig getDrivePIDF()
      Get the current drive motor PIDF values.
      Returns:
      PIDFConfig of the drive motor.
    • setDrivePIDF

      public void setDrivePIDF(PIDFConfig config)
      Set the drive PIDF values.
      Parameters:
      config - PIDFConfig of that should be set.
    • getAnglePIDF

      public PIDFConfig getAnglePIDF()
      Get the current angle/azimuth/steering motor PIDF values.
      Returns:
      PIDFConfig of the angle motor.
    • setAnglePIDF

      public void setAnglePIDF(PIDFConfig config)
      Set the angle/azimuth/steering motor PID
      Parameters:
      config - PIDFConfig of that should be set.
    • setDesiredState

      public void setDesiredState(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.
    • setDesiredState

      public void setDesiredState(SwerveModuleState desiredState, boolean isOpenLoop, double driveFeedforwardVoltage)
      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.
      driveFeedforwardVoltage - Drive motor controller feedforward as a voltage.
    • applyStateOptimizations

      public void applyStateOptimizations(SwerveModuleState desiredState)
      Apply the SwerveModuleState.optimize(Rotation2d) function if the module state optimization is enabled while debugging.
      Parameters:
      desiredState - The desired state to apply the optimization to.
    • applyAntiJitter

      public void applyAntiJitter(SwerveModuleState desiredState, boolean force)
      Apply anti-jitter to the desired state. This will prevent the module from rotating if the speed requested is too low. If force is true, the anti-jitter will not be applied.
      Parameters:
      desiredState - The desired state to apply the anti-jitter to.
      force - Whether to ignore the antiJitterEnabled state and apply the anti-jitter anyway.
    • setAngle

      public void setAngle(double angle)
      Set the angle for the module.
      Parameters:
      angle - Angle in degrees.
    • getState

      public SwerveModuleState getState()
      Get the Swerve Module state.
      Returns:
      Current SwerveModule state.
    • getPosition

      public 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.
    • useExternalFeedbackSensor

      public void useExternalFeedbackSensor()
      Use external sensors for the feedback of the angle/azimuth/steer controller.
    • useInternalFeedbackSensor

      public void useInternalFeedbackSensor()
      Use external sensors for the feedback of the angle/azimuth/steer controller.
    • pushOffsetsToEncoders

      @Deprecated public void pushOffsetsToEncoders()
      Deprecated.
      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.
    • getMaxVelocity

      public LinearVelocity getMaxVelocity()
      Get the maximum module velocity as a LinearVelocity based on the RPM and gear ratio.
      Returns:
      LinearVelocity max velocity of the drive wheel.
    • getMaxDriveVelocityMetersPerSecond

      public double getMaxDriveVelocityMetersPerSecond()
      Get the maximum drive velocity of the module in Meters Per Second.
      Returns:
      Maximum drive motor velocity in Meters Per Second.
    • getMaxAngularVelocity

      public AngularVelocity getMaxAngularVelocity()
      Get the maximum module angular velocity as a AngularVelocity based on the RPM and gear ratio.
      Returns:
      AngularVelocity max velocity of the angle/azimuth.
    • updateTelemetry

      public void updateTelemetry()
      Update data sent to SmartDashboard.
    • invalidateCache

      public void invalidateCache()
      Invalidate the Cache objects used by SwerveModule.
    • getSimModule

      public SwerveModuleSimulation getSimModule()
      Obtains the SwerveModuleSimulation used in simulation.
      Returns:
      the module simulation, null if this method is called on a real robot
    • configureModuleSimulation

      public void configureModuleSimulation(SwerveModuleSimulation swerveModuleSimulation, SwerveModulePhysicalCharacteristics physicalCharacteristics)
      Configure the simModule with the MapleSim SwerveModuleSimulation
      Parameters:
      swerveModuleSimulation - MapleSim SwerveModuleSimulation to configure with.
      physicalCharacteristics - SwerveModulePhysicalCharacteristics that represent the swerve drive.