Class DARE

java.lang.Object
edu.wpi.first.math.DARE

public final class DARE
extends Object
DARE solver utility functions.
  • Method Summary

    Modifier and Type Method Description
    static <States extends Num,​ Inputs extends Num>
    Matrix<States,​States>
    dare​(Matrix<States,​States> A, Matrix<States,​Inputs> B, Matrix<States,​States> Q, Matrix<Inputs,​Inputs> R)
    Computes the unique stabilizing solution X to the discrete-time algebraic Riccati equation.
    static <States extends Num,​ Inputs extends Num>
    Matrix<States,​States>
    dare​(Matrix<States,​States> A, Matrix<States,​Inputs> B, Matrix<States,​States> Q, Matrix<Inputs,​Inputs> R, Matrix<States,​Inputs> N)
    Computes the unique stabilizing solution X to the discrete-time algebraic Riccati equation.
    static <States extends Num,​ Inputs extends Num>
    Matrix<States,​States>
    dareDetail​(Matrix<States,​States> A, Matrix<States,​Inputs> B, Matrix<States,​States> Q, Matrix<Inputs,​Inputs> R)
    Computes the unique stabilizing solution X to the discrete-time algebraic Riccati equation.
    static <States extends Num,​ Inputs extends Num>
    Matrix<States,​States>
    dareDetail​(Matrix<States,​States> A, Matrix<States,​Inputs> B, Matrix<States,​States> Q, Matrix<Inputs,​Inputs> R, Matrix<States,​Inputs> N)
    Computes the unique stabilizing solution X to the discrete-time algebraic Riccati equation.

    Methods inherited from class java.lang.Object

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

    • dareDetail

      public static <States extends Num,​ Inputs extends Num> Matrix<States,​States> dareDetail​(Matrix<States,​States> A, Matrix<States,​Inputs> B, Matrix<States,​States> Q, Matrix<Inputs,​Inputs> R)
      Computes the unique stabilizing solution X to the discrete-time algebraic Riccati equation.

      AᵀXA − X − AᵀXB(BᵀXB + R)⁻¹BᵀXA + Q = 0

      This internal function skips expensive precondition checks for increased performance. The solver may hang if any of the following occur:

      • Q isn't symmetric positive semidefinite
      • R isn't symmetric positive definite
      • The (A, B) pair isn't stabilizable
      • The (A, C) pair where Q = CᵀC isn't detectable

      Only use this function if you're sure the preconditions are met.

      Type Parameters:
      States - Number of states.
      Inputs - Number of inputs.
      Parameters:
      A - System matrix.
      B - Input matrix.
      Q - State cost matrix.
      R - Input cost matrix.
      Returns:
      Solution of DARE.
    • dareDetail

      public static <States extends Num,​ Inputs extends Num> Matrix<States,​States> dareDetail​(Matrix<States,​States> A, Matrix<States,​Inputs> B, Matrix<States,​States> Q, Matrix<Inputs,​Inputs> R, Matrix<States,​Inputs> N)
      Computes the unique stabilizing solution X to the discrete-time algebraic Riccati equation.

      AᵀXA − X − (AᵀXB + N)(BᵀXB + R)⁻¹(BᵀXA + Nᵀ) + Q = 0

      This is equivalent to solving the original DARE:

      A₂ᵀXA₂ − X − A₂ᵀXB(BᵀXB + R)⁻¹BᵀXA₂ + Q₂ = 0

      where A₂ and Q₂ are a change of variables:

      A₂ = A − BR⁻¹Nᵀ and Q₂ = Q − NR⁻¹Nᵀ

      This overload of the DARE is useful for finding the control law uₖ that minimizes the following cost function subject to xₖ₊₁ = Axₖ + Buₖ.

           ∞ [xₖ]ᵀ[Q  N][xₖ]
       J = Σ [uₖ] [Nᵀ R][uₖ] ΔT
          k=0
       

      This is a more general form of the following. The linear-quadratic regulator is the feedback control law uₖ that minimizes the following cost function subject to xₖ₊₁ = Axₖ + Buₖ:

           ∞
       J = Σ (xₖᵀQxₖ + uₖᵀRuₖ) ΔT
          k=0
       

      This can be refactored as:

           ∞ [xₖ]ᵀ[Q 0][xₖ]
       J = Σ [uₖ] [0 R][uₖ] ΔT
          k=0
       

      This internal function skips expensive precondition checks for increased performance. The solver may hang if any of the following occur:

      • Q₂ isn't symmetric positive semidefinite
      • R isn't symmetric positive definite
      • The (A₂, B) pair isn't stabilizable
      • The (A₂, C) pair where Q₂ = CᵀC isn't detectable

      Only use this function if you're sure the preconditions are met.

      Type Parameters:
      States - Number of states.
      Inputs - Number of inputs.
      Parameters:
      A - System matrix.
      B - Input matrix.
      Q - State cost matrix.
      R - Input cost matrix.
      N - State-input cross-term cost matrix.
      Returns:
      Solution of DARE.
    • dare

      public static <States extends Num,​ Inputs extends Num> Matrix<States,​States> dare​(Matrix<States,​States> A, Matrix<States,​Inputs> B, Matrix<States,​States> Q, Matrix<Inputs,​Inputs> R)
      Computes the unique stabilizing solution X to the discrete-time algebraic Riccati equation.

      AᵀXA − X − AᵀXB(BᵀXB + R)⁻¹BᵀXA + Q = 0

      Type Parameters:
      States - Number of states.
      Inputs - Number of inputs.
      Parameters:
      A - System matrix.
      B - Input matrix.
      Q - State cost matrix.
      R - Input cost matrix.
      Returns:
      Solution of DARE.
      Throws:
      IllegalArgumentException - if Q isn't symmetric positive semidefinite.
      IllegalArgumentException - if R isn't symmetric positive definite.
      IllegalArgumentException - if the (A, B) pair isn't stabilizable.
      IllegalArgumentException - if the (A, C) pair where Q = CᵀC isn't detectable.
    • dare

      public static <States extends Num,​ Inputs extends Num> Matrix<States,​States> dare​(Matrix<States,​States> A, Matrix<States,​Inputs> B, Matrix<States,​States> Q, Matrix<Inputs,​Inputs> R, Matrix<States,​Inputs> N)
      Computes the unique stabilizing solution X to the discrete-time algebraic Riccati equation.

      AᵀXA − X − (AᵀXB + N)(BᵀXB + R)⁻¹(BᵀXA + Nᵀ) + Q = 0

      This is equivalent to solving the original DARE:

      A₂ᵀXA₂ − X − A₂ᵀXB(BᵀXB + R)⁻¹BᵀXA₂ + Q₂ = 0

      where A₂ and Q₂ are a change of variables:

      A₂ = A − BR⁻¹Nᵀ and Q₂ = Q − NR⁻¹Nᵀ

      This overload of the DARE is useful for finding the control law uₖ that minimizes the following cost function subject to xₖ₊₁ = Axₖ + Buₖ.

           ∞ [xₖ]ᵀ[Q  N][xₖ]
       J = Σ [uₖ] [Nᵀ R][uₖ] ΔT
          k=0
       

      This is a more general form of the following. The linear-quadratic regulator is the feedback control law uₖ that minimizes the following cost function subject to xₖ₊₁ = Axₖ + Buₖ:

           ∞
       J = Σ (xₖᵀQxₖ + uₖᵀRuₖ) ΔT
          k=0
       

      This can be refactored as:

           ∞ [xₖ]ᵀ[Q 0][xₖ]
       J = Σ [uₖ] [0 R][uₖ] ΔT
          k=0
       
      Type Parameters:
      States - Number of states.
      Inputs - Number of inputs.
      Parameters:
      A - System matrix.
      B - Input matrix.
      Q - State cost matrix.
      R - Input cost matrix.
      N - State-input cross-term cost matrix.
      Returns:
      Solution of DARE.
      Throws:
      IllegalArgumentException - if Q₂ isn't symmetric positive semidefinite.
      IllegalArgumentException - if R isn't symmetric positive definite.
      IllegalArgumentException - if the (A₂, B) pair isn't stabilizable.
      IllegalArgumentException - if the (A₂, C) pair where Q₂ = CᵀC isn't detectable.