Package swervelib.motors
Class SwerveMotor
java.lang.Object
swervelib.motors.SwerveMotor
- All Implemented Interfaces:
AutoCloseable
- Direct Known Subclasses:
SparkFlexSwerve,SparkMaxBrushedMotorSwerve,SparkMaxSwerve,TalonFXSSwerve,TalonFXSwerve,TalonSRXSwerve,ThriftyNovaSwerve
Swerve motor abstraction which defines a standard interface for motors within a swerve module.
-
Field Summary
FieldsModifier and TypeFieldDescriptionprotected booleanWhether the swerve motor is a drive motor.final intThe maximum amount of times the swerve motor will attempt to configure a motor if failures occur.Sim motor to use, defaulted ingetSimMotor(), but can be overridden here. -
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptionabstract voidSave the configurations from flash to EEPROM.abstract voidClear the sticky faults on the motor controller.abstract voidclose()abstract voidconfigureIntegratedEncoder(double positionConversionFactor) Configure the integrated encoder for the swerve module.abstract voidconfigurePIDF(PIDFConfig config) Configure the PIDF values for the closed loop controller.abstract voidconfigurePIDWrapping(double minInput, double maxInput) Configure the PID wrapping for the position closed loop controller.abstract voidDisable PID Wrapping on the motor.abstract voidConfigure the factory defaults.abstract doubleGet the applied dutycycle output.abstract ObjectgetMotor()Get the motor object from the module.abstract doubleGet the position of the integrated encoder.abstract DCMotorGet theDCMotorof the motor class.abstract doubleGet the velocity of the integrated encoder.abstract doubleGet the voltage output of the motor controller.abstract voidset(double percentOutput) Set the percentage output.abstract SwerveMotorsetAbsoluteEncoder(SwerveAbsoluteEncoder encoder) Set the absolute encoder to be a compatible absolute encoder.abstract voidsetCurrentLimit(int currentLimit) Set the current limit for the swerve drive motor, remember this may cause jumping if used in conjunction with voltage compensation.abstract voidsetInverted(boolean inverted) Set the motor to be inverted.abstract voidsetLoopRampRate(double rampRate) Set the maximum rate the open/closed loop output can change by.abstract voidsetMotorBrake(boolean isBrakeMode) Set the idle mode.abstract voidsetPosition(double position) Set the integrated encoder position.abstract voidsetReference(double setpoint, double feedforward) Set the closed loop PID controller reference point.abstract voidsetReference(double setpoint, double feedforward, double position) Set the closed loop PID controller reference point.abstract voidsetVoltage(double voltage) Set the voltage of the motor.abstract voidsetVoltageCompensation(double nominalVoltage) Set the voltage compensation for the swerve module motor.abstract booleanQueries whether the absolute encoder is directly attached to the motor controller.
-
Field Details
-
maximumRetries
public final int maximumRetriesThe maximum amount of times the swerve motor will attempt to configure a motor if failures occur.- See Also:
-
simMotor
Sim motor to use, defaulted ingetSimMotor(), but can be overridden here.
NOTE: This will not change the simulation motor type! It is intended for use only if you are utilizing Feedforwards from PathPlanner. -
isDriveMotor
protected boolean isDriveMotorWhether the swerve motor is a drive motor.
-
-
Constructor Details
-
SwerveMotor
public SwerveMotor()
-
-
Method Details
-
close
public abstract void close()- Specified by:
closein interfaceAutoCloseable
-
factoryDefaults
public abstract void factoryDefaults()Configure the factory defaults. -
clearStickyFaults
public abstract void clearStickyFaults()Clear the sticky faults on the motor controller. -
setAbsoluteEncoder
Set the absolute encoder to be a compatible absolute encoder.- Parameters:
encoder- The encoder to use.- Returns:
- The
SwerveMotorfor single line configuration.
-
configureIntegratedEncoder
public abstract void configureIntegratedEncoder(double positionConversionFactor) Configure the integrated encoder for the swerve module. Sets the conversion factors for position and velocity.- Parameters:
positionConversionFactor- The conversion factor to apply for position.
-
configurePIDF
Configure the PIDF values for the closed loop controller. 0 is disabled or off.- Parameters:
config- Configuration class holding the PIDF values.
-
configurePIDWrapping
public abstract void configurePIDWrapping(double minInput, double maxInput) Configure the PID wrapping for the position closed loop controller.- Parameters:
minInput- Minimum PID input.maxInput- Maximum PID input.
-
disablePIDWrapping
public abstract void disablePIDWrapping()Disable PID Wrapping on the motor. -
setMotorBrake
public abstract void setMotorBrake(boolean isBrakeMode) Set the idle mode.- Parameters:
isBrakeMode- Set the brake mode.
-
setInverted
public abstract void setInverted(boolean inverted) Set the motor to be inverted.- Parameters:
inverted- State of inversion.
-
burnFlash
public abstract void burnFlash()Save the configurations from flash to EEPROM. -
set
public abstract void set(double percentOutput) Set the percentage output.- Parameters:
percentOutput- percent out for the motor controller.
-
setReference
public abstract void setReference(double setpoint, double feedforward) Set the closed loop PID controller reference point.- Parameters:
setpoint- Setpoint in meters per second or angle in degrees.feedforward- Feedforward in volt-meter-per-second or kV.
-
setReference
public abstract void setReference(double setpoint, double feedforward, double position) Set the closed loop PID controller reference point.- Parameters:
setpoint- Setpoint in meters per second or angle in degrees.feedforward- Feedforward in volt-meter-per-second or kV.position- Only used on the angle motor, the position of the motor in degrees.
-
getVoltage
public abstract double getVoltage()Get the voltage output of the motor controller.- Returns:
- Voltage output.
-
setVoltage
public abstract void setVoltage(double voltage) Set the voltage of the motor.- Parameters:
voltage- Voltage to set.
-
getAppliedOutput
public abstract double getAppliedOutput()Get the applied dutycycle output.- Returns:
- Applied dutycycle output to the motor.
-
getVelocity
public abstract double getVelocity()Get the velocity of the integrated encoder.- Returns:
- velocity in meters per second or degrees per second.
-
getPosition
public abstract double getPosition()Get the position of the integrated encoder.- Returns:
- Position in meters or degrees.
-
setPosition
public abstract void setPosition(double position) Set the integrated encoder position.- Parameters:
position- Integrated encoder position. Should be angle in degrees or meters per second.
-
setVoltageCompensation
public abstract void setVoltageCompensation(double nominalVoltage) Set the voltage compensation for the swerve module motor.- Parameters:
nominalVoltage- Nominal voltage for operation to output to.
-
setCurrentLimit
public abstract void setCurrentLimit(int currentLimit) Set the current limit for the swerve drive motor, remember this may cause jumping if used in conjunction with voltage compensation. This is useful to protect the motor from current spikes.- Parameters:
currentLimit- Current limit in AMPS at free speed.
-
setLoopRampRate
public abstract void setLoopRampRate(double rampRate) Set the maximum rate the open/closed loop output can change by.- Parameters:
rampRate- Time in seconds to go from 0 to full throttle.
-
getMotor
Get the motor object from the module.- Returns:
- Motor object.
-
getSimMotor
Get theDCMotorof the motor class.- Returns:
DCMotorof this type.
-
usingExternalFeedbackSensor
public abstract boolean usingExternalFeedbackSensor()Queries whether the absolute encoder is directly attached to the motor controller.- Returns:
- connected absolute encoder state.
-