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.doubleAngle volt-meter-per-second.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.The drive motor and angle motor of this swerve module.final booleanState of inversion of the drive motor.final doubleMaximum robot speed in meters per second.edu.wpi.first.math.geometry.Translation2dSwerve module location relative to the robot.Physical characteristics of the swerve module.PIDF configuration options for the drive motor closed-loop PID controller. -
Constructor Summary
ConstructorsConstructorDescriptionSwerveModuleConfiguration(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.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. -
Method Summary
Modifier and TypeMethodDescriptionedu.wpi.first.math.controller.SimpleMotorFeedforwardCreate the drive feedforward for swerve modules.doublegetPositionEncoderConversion(boolean isDriveMotor) Get the encoder conversion for position encoders.
-
Field Details
-
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. -
maxSpeed
public final double maxSpeedMaximum robot speed in meters per second. -
anglePIDF
PIDF configuration options for the angle motor closed-loop PID controller. -
velocityPIDF
PIDF configuration options for the drive motor closed-loop PID controller. -
angleKV
public double angleKVAngle volt-meter-per-second. -
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.
-
-
Constructor Details
-
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- 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.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- DriveSwerveMotor.angleMotor- AngleSwerveMotorabsoluteEncoder- 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.maxSpeed- Maximum robot speed in meters per second.physicalCharacteristics- Physical characteristics of the swerve module.
-
-
Method Details
-
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.
-