Class SwerveMotor

java.lang.Object
swervelib.motors.SwerveMotor
Direct Known Subclasses:
SparkFlexSwerve, SparkMaxBrushedMotorSwerve, SparkMaxSwerve, TalonFXSwerve, TalonSRXSwerve

public abstract class SwerveMotor extends Object
Swerve motor abstraction which defines a standard interface for motors within a swerve module.
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    protected boolean
    Whether the swerve motor is a drive motor.
    final int
    The maximum amount of times the swerve motor will attempt to configure a motor if failures occur.
  • Constructor Summary

    Constructors
    Constructor
    Description
     
  • Method Summary

    Modifier and Type
    Method
    Description
    abstract void
    Save the configurations from flash to EEPROM.
    abstract void
    Clear the sticky faults on the motor controller.
    abstract void
    configureIntegratedEncoder(double positionConversionFactor)
    Configure the integrated encoder for the swerve module.
    abstract void
    Configure the PIDF values for the closed loop controller.
    abstract void
    configurePIDWrapping(double minInput, double maxInput)
    Configure the PID wrapping for the position closed loop controller.
    abstract void
    Configure the factory defaults.
    abstract double
    Get the applied dutycycle output.
    abstract Object
    Get the motor object from the module.
    abstract double
    Get the position of the integrated encoder.
    abstract double
    Get the velocity of the integrated encoder.
    abstract double
    Get the voltage output of the motor controller.
    abstract boolean
    Queries whether the absolute encoder is directly attached to the motor controller.
    abstract void
    set(double percentOutput)
    Set the percentage output.
    abstract SwerveMotor
    Set the absolute encoder to be a compatible absolute encoder.
    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.
    abstract void
    setInverted(boolean inverted)
    Set the motor to be inverted.
    abstract void
    setLoopRampRate(double rampRate)
    Set the maximum rate the open/closed loop output can change by.
    abstract void
    setMotorBrake(boolean isBrakeMode)
    Set the idle mode.
    abstract void
    setPosition(double position)
    Set the integrated encoder position.
    abstract void
    setReference(double setpoint, double feedforward)
    Set the closed loop PID controller reference point.
    abstract void
    setReference(double setpoint, double feedforward, double position)
    Set the closed loop PID controller reference point.
    abstract void
    setVoltage(double voltage)
    Set the voltage of the motor.
    abstract void
    setVoltageCompensation(double nominalVoltage)
    Set the voltage compensation for the swerve module motor.

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Field Details

    • maximumRetries

      public final int maximumRetries
      The maximum amount of times the swerve motor will attempt to configure a motor if failures occur.
      See Also:
    • isDriveMotor

      protected boolean isDriveMotor
      Whether the swerve motor is a drive motor.
  • Constructor Details

    • SwerveMotor

      public SwerveMotor()
  • Method Details

    • factoryDefaults

      public abstract void factoryDefaults()
      Configure the factory defaults.
    • clearStickyFaults

      public abstract void clearStickyFaults()
      Clear the sticky faults on the motor controller.
    • setAbsoluteEncoder

      public abstract SwerveMotor setAbsoluteEncoder(SwerveAbsoluteEncoder encoder)
      Set the absolute encoder to be a compatible absolute encoder.
      Parameters:
      encoder - The encoder to use.
      Returns:
      The SwerveMotor for 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

      public abstract void configurePIDF(PIDFConfig config)
      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.
    • 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

      public abstract Object getMotor()
      Get the motor object from the module.
      Returns:
      Motor object.
    • isAttachedAbsoluteEncoder

      public abstract boolean isAttachedAbsoluteEncoder()
      Queries whether the absolute encoder is directly attached to the motor controller.
      Returns:
      connected absolute encoder state.