Package swervelib.parser
Class SwerveModuleConfiguration
java.lang.Object
swervelib.parser.SwerveModuleConfiguration
Swerve Module configuration class which is used to configure
SwerveModule.-
Field Summary
FieldsModifier and TypeFieldDescriptionThe Absolute Encoder for the swerve module.final booleanWhether the absolute encoder is inverted.The drive motor and angle motor of this swerve module.final booleanState of inversion of the angle motor.final doubleAngle offset in degrees for the Swerve Module.PIDF configuration options for the angle motor closed-loop PID controller.final MotorConfigDoubleConversion factor for drive motor onboard PID's and angle PID's.The drive motor and angle motor of this swerve module.final booleanState of inversion of the drive motor.edu.wpi.first.math.geometry.Translation2dSwerve module location relative to the robot.Name for the swerve module for telemetry.Physical characteristics of the swerve module.PIDF configuration options for the drive motor closed-loop PID controller. -
Constructor Summary
ConstructorsConstructorDescriptionSwerveModuleConfiguration(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) Construct a configuration object for swerve modules.SwerveModuleConfiguration(SwerveMotor driveMotor, SwerveMotor angleMotor, MotorConfigDouble conversionFactors, SwerveAbsoluteEncoder absoluteEncoder, double angleOffset, double xMeters, double yMeters, PIDFConfig anglePIDF, PIDFConfig velocityPIDF, SwerveModulePhysicalCharacteristics physicalCharacteristics, String name) Construct a configuration object for swerve modules. -
Method Summary
-
Field Details
-
conversionFactors
Conversion factor for drive motor onboard PID's and angle PID's. UseSwerveMath.calculateMetersPerRotation(double, double, double)andSwerveMath.calculateDegreesPerSteeringRotation(double, double)respectively to calculate the conversion factors. -
angleOffset
public final double angleOffsetAngle offset in degrees for the Swerve Module. -
absoluteEncoderInverted
public final boolean absoluteEncoderInvertedWhether the absolute encoder is inverted. -
driveMotorInverted
public final boolean driveMotorInvertedState of inversion of the drive motor. -
angleMotorInverted
public final boolean angleMotorInvertedState of inversion of the angle motor. -
anglePIDF
PIDF configuration options for the angle motor closed-loop PID controller. -
velocityPIDF
PIDF configuration options for the drive motor closed-loop PID controller. -
moduleLocation
public edu.wpi.first.math.geometry.Translation2d moduleLocationSwerve module location relative to the robot. -
physicalCharacteristics
Physical characteristics of the swerve module. -
driveMotor
The drive motor and angle motor of this swerve module. -
angleMotor
The drive motor and angle motor of this swerve module. -
absoluteEncoder
The Absolute Encoder for the swerve module. -
name
Name for the swerve module for telemetry.
-
-
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) Construct a configuration object for swerve modules.- Parameters:
driveMotor- DriveSwerveMotor.angleMotor- AngleSwerveMotorabsoluteEncoder- Absolute encoderSwerveAbsoluteEncoder.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.
-
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) Construct a configuration object for swerve modules. Assumes the absolute encoder and drive motor are not inverted.- Parameters:
driveMotor- DriveSwerveMotor.angleMotor- AngleSwerveMotorconversionFactors- Conversion factors for angle/azimuth motors drive factors.absoluteEncoder- Absolute encoderSwerveAbsoluteEncoder.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.
-