Class DAREJNI
-
Nested Class Summary
Nested classes/interfaces inherited from class edu.wpi.first.math.jni.WPIMathJNI
WPIMathJNI.Helper
-
Method Summary
Modifier and TypeMethodDescriptionstatic void
dareABQR
(double[] A, double[] B, double[] Q, double[] R, int states, int inputs, double[] S) Computes the unique stabilizing solution X to the discrete-time algebraic Riccati equation.static void
dareABQRN
(double[] A, double[] B, double[] Q, double[] R, double[] N, int states, int inputs, double[] S) Computes the unique stabilizing solution X to the discrete-time algebraic Riccati equation.static void
dareNoPrecondABQR
(double[] A, double[] B, double[] Q, double[] R, int states, int inputs, double[] S) Computes the unique stabilizing solution X to the discrete-time algebraic Riccati equation.static void
dareNoPrecondABQRN
(double[] A, double[] B, double[] Q, double[] R, double[] N, int states, int inputs, double[] S) Computes the unique stabilizing solution X to the discrete-time algebraic Riccati equation.Methods inherited from class edu.wpi.first.math.jni.WPIMathJNI
forceLoad
-
Method Details
-
dareNoPrecondABQR
public static void dareNoPrecondABQR(double[] A, double[] B, double[] Q, double[] R, int states, int inputs, double[] S) 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. Solves the discrete algebraic Riccati equation.
- Parameters:
A
- Array containing elements of A in row-major order.B
- Array containing elements of B in row-major order.Q
- Array containing elements of Q in row-major order.R
- Array containing elements of R in row-major order.states
- Number of states in A matrix.inputs
- Number of inputs in B matrix.S
- Array storage for DARE solution.
-
dareNoPrecondABQRN
public static void dareNoPrecondABQRN(double[] A, double[] B, double[] Q, double[] R, double[] N, int states, int inputs, double[] S) 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 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 − NR⁻¹Nᵀ isn't symmetric positive semidefinite
- R isn't symmetric positive definite
- The (A − BR⁻¹Nᵀ, 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.
- Parameters:
A
- Array containing elements of A in row-major order.B
- Array containing elements of B in row-major order.Q
- Array containing elements of Q in row-major order.R
- Array containing elements of R in row-major order.N
- Array containing elements of N in row-major order.states
- Number of states in A matrix.inputs
- Number of inputs in B matrix.S
- Array storage for DARE solution.
-
dareABQR
public static void dareABQR(double[] A, double[] B, double[] Q, double[] R, int states, int inputs, double[] S) 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
- Parameters:
A
- Array containing elements of A in row-major order.B
- Array containing elements of B in row-major order.Q
- Array containing elements of Q in row-major order.R
- Array containing elements of R in row-major order.states
- Number of states in A matrix.inputs
- Number of inputs in B matrix.S
- Array storage for DARE solution.- 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.
-
dareABQRN
public static void dareABQRN(double[] A, double[] B, double[] Q, double[] R, double[] N, int states, int inputs, double[] S) 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 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
- Parameters:
A
- Array containing elements of A in row-major order.B
- Array containing elements of B in row-major order.Q
- Array containing elements of Q in row-major order.R
- Array containing elements of R in row-major order.N
- Array containing elements of N in row-major order.states
- Number of states in A matrix.inputs
- Number of inputs in B matrix.S
- Array storage for DARE solution.- Throws:
IllegalArgumentException
- if Q − NR⁻¹Nᵀ isn't symmetric positive semidefinite.IllegalArgumentException
- if R isn't symmetric positive definite.IllegalArgumentException
- if the (A − BR⁻¹Nᵀ, B) pair isn't stabilizable.IllegalArgumentException
- if the (A, C) pair where Q = CᵀC isn't detectable.
-