Package yams.math

Class LQRConfig

java.lang.Object
yams.math.LQRConfig

public class LQRConfig extends Object
LQR Configuration for LQRController
  • Constructor Details

  • Method Details

    • getType

      public LQRConfig.LQRType getType()
      Get the LQRConfig.LQRType of the LQR.
      Returns:
      LQRConfig.LQRType of the LQR.
    • getPeriod

      public Time getPeriod()
      Get the loop time for the LQR.
      Returns:
      Time for the loop time.
    • withRelms

      public LQRConfig withRelms(Voltage relms)
      Set the control effort for the LQR.
      Parameters:
      relms - Control effort (voltage) tolerance. Decrease this to more heavily penalize control effort, or make the controller less aggressive. 12 is a good starting point because that is the (approximate) maximum voltage of a battery.
      Returns:
      LQRConfig for chaining.
    • withControlEffort

      public LQRConfig withControlEffort(Voltage effort)
      Set the control effort for the LQR.
      Parameters:
      effort - Control effort (voltage) tolerance. Decrease this to more heavily penalize control effort, or make the controller less aggressive. 12 is a good starting point because that is the (approximate) maximum voltage of a battery.
      Returns:
      LQRConfig for chaining.
    • withMaxVoltage

      public LQRConfig withMaxVoltage(Voltage voltage)
      Set the maximum voltage for the LinearSystemLoop.
      Parameters:
      voltage - Maximum voltage output.
      Returns:
      LQRConfig for chaining.
    • withMeasurementDelay

      public LQRConfig withMeasurementDelay(Time delay)
      Set the measurement delay of the LQR.
      Parameters:
      delay - Measurement delay.
      Returns:
      LQRConfig for chaining.
    • withAgressiveness

      public LQRConfig withAgressiveness(double agressiveness)
      Agressiveness of the LQR, howfast it will attempt to achieve the desired state.
      Parameters:
      agressiveness - Usually 10, arbitrary scale.
      Returns:
      LQRConfig for chaining.
    • withFlyWheel

      public LQRConfig withFlyWheel(AngularVelocity qelms, AngularVelocity modelTrust, AngularVelocity encoderTrust)
      Construct a Flywheel LQR Configuration.
      Parameters:
      qelms - Velocity error tolerance. Decrease this to more heavily penalize state excursion, or make the controller behave more starting point because that is the (approximate) maximum voltage of a battery.
      modelTrust - Standard deviation of the model, represented in AngularVelocity.
      encoderTrust - Standard deviation of the encoder, represented in AngularVelocity.
      Returns:
      LQRConfig for chaining.
    • withElevator

      public LQRConfig withElevator(Distance qelmsPosition, LinearVelocity qelmsVelocity, Distance modelPositionTrust, LinearVelocity modelVelocityTrust, Distance encoderPositionTrust, Mass mass, Distance drumRadius)
      Construct an Elevator LQR Configuration.
      Parameters:
      qelmsPosition - Position error tolerance, in meters. Decrease this to more heavily penalize state excursion, or make the controller behave more aggressively. This can be tuned to balance the position and velocity errors.
      qelmsVelocity - Velocity error tolerance, in meters per second. Decrease this to more heavily penalize state excursion, or make the controller behave more aggressively. This can be tuned to balance the position and velocity errors.
      modelPositionTrust - Standard deviation of the model position, represented in Distance.
      modelVelocityTrust - Standard deviation of the model velocity, represented in LinearVelocity.
      encoderPositionTrust - Standard deviation of the encoder position, represented in Distance.
      mass - Mass of the elevator, represented in Mass.
      drumRadius - Radius of the elevator drum, represented in Distance.
      Returns:
      LQRConfig for chaining.
    • withArm

      public LQRConfig withArm(Angle qelmsPosition, AngularVelocity qelmsVelocity, Angle modelPositionTrust, AngularVelocity modelVelocityTrust, Angle encoderPositionTrust)
      Construct an Arm LQR Configuration.
      Parameters:
      qelmsPosition - Position error tolerance, in rotations. Decrease this to more heavily penalize state excursion, or make the controller behave more aggressively. This can be tuned to balance the position and velocity errors.
      qelmsVelocity - Velocity error tolerance, in rotations per second. Decrease this to more heavily penalize state excursion, or make the controller behave more aggressively. This can be tuned to balance the position and velocity errors.
      modelPositionTrust - Standard deviation of the model position, represented in Angle.
      modelVelocityTrust - Standard deviation of the model velocity, represented in AngularVelocity.
      encoderPositionTrust - Standard deviation of the encoder position, represented in Angle.
      Returns:
      LQRConfig for chaining.
    • getSystem

      public LinearSystem<?,?,?> getSystem()
      Get the LinearSystem for the LQR. with LinearSystemId
      Returns:
      LinearSystem for the LQR.
    • getKalmanFilter

      public KalmanFilter<?,?,?> getKalmanFilter(LinearSystem<?,?,?> plant)
      Get the KalmanFilter for the LQR.
      Parameters:
      plant - LinearSystem for the LQR, fetched from getSystem().
      Returns:
      KalmanFilter for the LQR.
    • getRegulator

      public LinearQuadraticRegulator<?,?,?> getRegulator(LinearSystem<?,?,?> plant)
      Parameters:
      plant - LinearSystem for the LQR, fetched from getSystem().
      Returns:
      LinearQuadraticRegulator for the LQR.
    • getLoop

      public LinearSystemLoop<?,?,?> getLoop(LinearSystem<?,?,?> plant, LinearQuadraticRegulator<?,?,?> controller, KalmanFilter<?,?,?> observer)
      Parameters:
      plant - LinearSystem for the LQR, fetched from getSystem()
      controller - LinearQuadraticRegulator for the LQR, fetched from getRegulator(LinearSystem)
      observer - KalmanFilter for the LQR, fetched from getKalmanFilter(LinearSystem)
      Returns:
      LinearSystemLoop for the LQR.
    • getLoop

      public LinearSystemLoop<?,?,?> getLoop()
      Get the LinearSystemLoop with the currently configured LQR.
      Returns:
      LinearSystemLoop for the LQR.