Class SwerveModuleConfiguration


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

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

        public final double maxSpeed
        Maximum robot speed in meters per second.
      • 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.
      • angleKV

        public double angleKV
        Angle volt-meter-per-second.
      • moduleLocation

        public edu.wpi.first.math.geometry.Translation2d moduleLocation
        Swerve module location relative to the robot.
      • 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.
    • Constructor Detail

      • SwerveModuleConfiguration

        public SwerveModuleConfiguration​(SwerveMotor driveMotor,
                                         SwerveMotor angleMotor,
                                         SwerveAbsoluteEncoder absoluteEncoder,
                                         double angleOffset,
                                         double xMeters,
                                         double yMeters,
                                         PIDFConfig anglePIDF,
                                         PIDFConfig velocityPIDF,
                                         double maxSpeed,
                                         SwerveModulePhysicalCharacteristics physicalCharacteristics,
                                         boolean absoluteEncoderInverted,
                                         boolean driveMotorInverted,
                                         boolean angleMotorInverted)
        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.
        maxSpeed - Maximum speed in meters per second.
        physicalCharacteristics - Physical characteristics of the swerve module.
      • SwerveModuleConfiguration

        public SwerveModuleConfiguration​(SwerveMotor driveMotor,
                                         SwerveMotor angleMotor,
                                         SwerveAbsoluteEncoder absoluteEncoder,
                                         double angleOffset,
                                         double xMeters,
                                         double yMeters,
                                         PIDFConfig anglePIDF,
                                         PIDFConfig velocityPIDF,
                                         double maxSpeed,
                                         SwerveModulePhysicalCharacteristics physicalCharacteristics)
        Construct a configuration object for swerve modules. Assumes the absolute encoder and drive motor are not inverted.
        Parameters:
        driveMotor - Drive SwerveMotor.
        angleMotor - Angle SwerveMotor
        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.
        maxSpeed - Maximum robot speed in meters per second.
        physicalCharacteristics - Physical characteristics of the swerve module.
    • Method Detail

      • createDriveFeedforward

        public edu.wpi.first.math.controller.SimpleMotorFeedforward createDriveFeedforward()
        Create the drive feedforward for swerve modules.
        Returns:
        Drive feedforward for drive motor on a swerve module.
      • getPositionEncoderConversion

        public double getPositionEncoderConversion​(boolean isDriveMotor)
        Get the encoder conversion for position encoders.
        Parameters:
        isDriveMotor - For the drive motor.
        Returns:
        Position encoder conversion factor.