Class SwerveModuleConfiguration

java.lang.Object
swervelib.parser.SwerveModuleConfiguration

public class SwerveModuleConfiguration extends Object
Swerve Module configuration class which is used to configure SwerveModule.
  • Field Details

    • conversionFactors

      public final MotorConfigDouble conversionFactors
      Conversion factor for drive motor onboard PID's and angle PID's. Use SwerveMath.calculateMetersPerRotation(double, double, double) and SwerveMath.calculateDegreesPerSteeringRotation(double, double) respectively to calculate the conversion factors.
    • angleOffset

      public final double angleOffset
      Angle offset in degrees for the Swerve Module.
    • absoluteEncoderInverted

      public final boolean absoluteEncoderInverted
      Whether the absolute encoder is inverted.
    • driveMotorInverted

      public final boolean driveMotorInverted
      State of inversion of the drive motor.
    • angleMotorInverted

      public final boolean angleMotorInverted
      State of inversion of the angle motor.
    • anglePIDF

      public PIDFConfig anglePIDF
      PIDF configuration options for the angle motor closed-loop PID controller.
    • velocityPIDF

      public PIDFConfig velocityPIDF
      PIDF configuration options for the drive motor closed-loop PID controller.
    • moduleLocation

      public edu.wpi.first.math.geometry.Translation2d moduleLocation
      Swerve module location relative to the robot.
    • physicalCharacteristics

      public SwerveModulePhysicalCharacteristics physicalCharacteristics
      Physical characteristics of the swerve module.
    • driveMotor

      public SwerveMotor driveMotor
      The drive motor and angle motor of this swerve module.
    • angleMotor

      public SwerveMotor angleMotor
      The drive motor and angle motor of this swerve module.
    • absoluteEncoder

      public SwerveAbsoluteEncoder absoluteEncoder
      The Absolute Encoder for the swerve module.
    • name

      public String name
      Name for the swerve module for telemetry.
    • useCosineCompensator

      public boolean useCosineCompensator
      Should do cosine compensation when not pointing correct direction;.
  • Constructor Details

    • SwerveModuleConfiguration

      public SwerveModuleConfiguration(SwerveMotor driveMotor, SwerveMotor angleMotor, MotorConfigDouble conversionFactors, SwerveAbsoluteEncoder absoluteEncoder, double angleOffset, double xMeters, double yMeters, PIDFConfig anglePIDF, PIDFConfig velocityPIDF, SwerveModulePhysicalCharacteristics physicalCharacteristics, boolean absoluteEncoderInverted, boolean driveMotorInverted, boolean angleMotorInverted, String name, boolean useCosineCompensator)
      Construct a configuration object for swerve modules.
      Parameters:
      driveMotor - Drive SwerveMotor.
      angleMotor - Angle SwerveMotor
      absoluteEncoder - Absolute encoder SwerveAbsoluteEncoder.
      angleOffset - Absolute angle offset to 0.
      absoluteEncoderInverted - Absolute encoder inverted.
      angleMotorInverted - State of inversion of the angle motor.
      driveMotorInverted - Drive motor inverted.
      xMeters - Module location in meters from the center horizontally.
      yMeters - Module location in meters from center vertically.
      anglePIDF - Angle PIDF configuration.
      velocityPIDF - Velocity PIDF configuration.
      physicalCharacteristics - Physical characteristics of the swerve module.
      name - The name for the swerve module.
      conversionFactors - Conversion factors to be applied to the drive and angle motors.
      useCosineCompensator - Should use cosineCompensation.
    • SwerveModuleConfiguration

      public SwerveModuleConfiguration(SwerveMotor driveMotor, SwerveMotor angleMotor, MotorConfigDouble conversionFactors, SwerveAbsoluteEncoder absoluteEncoder, double angleOffset, double xMeters, double yMeters, PIDFConfig anglePIDF, PIDFConfig velocityPIDF, SwerveModulePhysicalCharacteristics physicalCharacteristics, String name, boolean useCosineCompensator)
      Construct a configuration object for swerve modules. Assumes the absolute encoder and drive motor are not inverted.
      Parameters:
      driveMotor - Drive SwerveMotor.
      angleMotor - Angle SwerveMotor
      conversionFactors - Conversion factors for angle/azimuth motors drive factors.
      absoluteEncoder - Absolute encoder SwerveAbsoluteEncoder.
      angleOffset - Absolute angle offset to 0.
      xMeters - Module location in meters from the center horizontally.
      yMeters - Module location in meters from center vertically.
      anglePIDF - Angle PIDF configuration.
      velocityPIDF - Velocity PIDF configuration.
      physicalCharacteristics - Physical characteristics of the swerve module.
      name - Name for the module.
      useCosineCompensator - Should use cosineCompensation.