2020-12-26 14:12:05 -08:00
|
|
|
|
// Copyright (c) FIRST and other WPILib contributors.
|
|
|
|
|
|
// Open Source Software; you can modify and/or share it under the terms of
|
|
|
|
|
|
// the WPILib BSD license file in the root directory of this project.
|
2020-07-24 08:34:30 -07:00
|
|
|
|
|
2020-08-07 09:38:13 -07:00
|
|
|
|
package edu.wpi.first.math;
|
2020-07-24 08:34:30 -07:00
|
|
|
|
|
2020-12-29 22:45:16 -08:00
|
|
|
|
import org.ejml.simple.SimpleMatrix;
|
2020-08-07 09:38:13 -07:00
|
|
|
|
|
2023-05-14 22:23:00 -07:00
|
|
|
|
public final class DARE {
|
2023-06-09 00:11:26 -04:00
|
|
|
|
private DARE() {
|
|
|
|
|
|
throw new UnsupportedOperationException("This is a utility class!");
|
|
|
|
|
|
}
|
2020-07-24 08:34:30 -07:00
|
|
|
|
|
|
|
|
|
|
/**
|
2022-12-26 14:32:13 -05:00
|
|
|
|
* Solves the discrete algebraic Riccati equation.
|
2020-07-24 08:34:30 -07:00
|
|
|
|
*
|
|
|
|
|
|
* @param A System matrix.
|
|
|
|
|
|
* @param B Input matrix.
|
|
|
|
|
|
* @param Q State cost matrix.
|
|
|
|
|
|
* @param R Input cost matrix.
|
|
|
|
|
|
* @return Solution of DARE.
|
|
|
|
|
|
*/
|
2023-05-14 22:23:00 -07:00
|
|
|
|
public static SimpleMatrix dare(SimpleMatrix A, SimpleMatrix B, SimpleMatrix Q, SimpleMatrix R) {
|
2023-08-11 23:25:43 -07:00
|
|
|
|
var S = new SimpleMatrix(A.getNumRows(), A.getNumCols());
|
2023-05-14 22:23:00 -07:00
|
|
|
|
WPIMathJNI.dare(
|
2020-12-29 22:45:16 -08:00
|
|
|
|
A.getDDRM().getData(),
|
|
|
|
|
|
B.getDDRM().getData(),
|
|
|
|
|
|
Q.getDDRM().getData(),
|
|
|
|
|
|
R.getDDRM().getData(),
|
2023-08-11 23:25:43 -07:00
|
|
|
|
A.getNumCols(),
|
|
|
|
|
|
B.getNumCols(),
|
2020-12-29 22:45:16 -08:00
|
|
|
|
S.getDDRM().getData());
|
2020-07-24 08:34:30 -07:00
|
|
|
|
return S;
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/**
|
2022-12-26 14:32:13 -05:00
|
|
|
|
* Solves the discrete algebraic Riccati equation.
|
2020-07-24 08:34:30 -07:00
|
|
|
|
*
|
2021-06-10 20:46:47 -07:00
|
|
|
|
* @param <States> Number of states.
|
|
|
|
|
|
* @param <Inputs> Number of inputs.
|
2020-07-24 08:34:30 -07:00
|
|
|
|
* @param A System matrix.
|
|
|
|
|
|
* @param B Input matrix.
|
|
|
|
|
|
* @param Q State cost matrix.
|
|
|
|
|
|
* @param R Input cost matrix.
|
|
|
|
|
|
* @return Solution of DARE.
|
|
|
|
|
|
*/
|
2023-05-14 22:23:00 -07:00
|
|
|
|
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) {
|
|
|
|
|
|
return new Matrix<>(dare(A.getStorage(), B.getStorage(), Q.getStorage(), R.getStorage()));
|
2020-07-24 08:34:30 -07:00
|
|
|
|
}
|
2021-02-15 18:17:55 -08:00
|
|
|
|
|
|
|
|
|
|
/**
|
2022-12-26 14:32:13 -05:00
|
|
|
|
* Solves the discrete algebraic Riccati equation.
|
2021-02-15 18:17:55 -08:00
|
|
|
|
*
|
|
|
|
|
|
* @param A System matrix.
|
|
|
|
|
|
* @param B Input matrix.
|
|
|
|
|
|
* @param Q State cost matrix.
|
|
|
|
|
|
* @param R Input cost matrix.
|
|
|
|
|
|
* @param N State-input cross-term cost matrix.
|
|
|
|
|
|
* @return Solution of DARE.
|
|
|
|
|
|
*/
|
2023-05-14 22:23:00 -07:00
|
|
|
|
public static SimpleMatrix dare(
|
2021-02-15 18:17:55 -08:00
|
|
|
|
SimpleMatrix A, SimpleMatrix B, SimpleMatrix Q, SimpleMatrix R, SimpleMatrix N) {
|
|
|
|
|
|
// See
|
|
|
|
|
|
// https://en.wikipedia.org/wiki/Linear%E2%80%93quadratic_regulator#Infinite-horizon,_discrete-time_LQR
|
|
|
|
|
|
// for the change of variables used here.
|
|
|
|
|
|
var scrA = A.minus(B.mult(R.solve(N.transpose())));
|
|
|
|
|
|
var scrQ = Q.minus(N.mult(R.solve(N.transpose())));
|
|
|
|
|
|
|
2023-08-11 23:25:43 -07:00
|
|
|
|
var S = new SimpleMatrix(A.getNumRows(), A.getNumCols());
|
2023-05-14 22:23:00 -07:00
|
|
|
|
WPIMathJNI.dare(
|
2021-02-15 18:17:55 -08:00
|
|
|
|
scrA.getDDRM().getData(),
|
|
|
|
|
|
B.getDDRM().getData(),
|
|
|
|
|
|
scrQ.getDDRM().getData(),
|
|
|
|
|
|
R.getDDRM().getData(),
|
2023-08-11 23:25:43 -07:00
|
|
|
|
A.getNumCols(),
|
|
|
|
|
|
B.getNumCols(),
|
2021-02-15 18:17:55 -08:00
|
|
|
|
S.getDDRM().getData());
|
|
|
|
|
|
return S;
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/**
|
2022-12-26 14:32:13 -05:00
|
|
|
|
* Solves the discrete algebraic Riccati equation.
|
2021-02-15 18:17:55 -08:00
|
|
|
|
*
|
2021-06-10 20:46:47 -07:00
|
|
|
|
* @param <States> Number of states.
|
|
|
|
|
|
* @param <Inputs> Number of inputs.
|
2021-02-15 18:17:55 -08:00
|
|
|
|
* @param A System matrix.
|
|
|
|
|
|
* @param B Input matrix.
|
|
|
|
|
|
* @param Q State cost matrix.
|
|
|
|
|
|
* @param R Input cost matrix.
|
|
|
|
|
|
* @param N State-input cross-term cost matrix.
|
|
|
|
|
|
* @return Solution of DARE.
|
|
|
|
|
|
*/
|
2023-05-14 22:23:00 -07:00
|
|
|
|
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) {
|
|
|
|
|
|
// This is a change of variables to make the DARE that includes Q, R, and N
|
|
|
|
|
|
// cost matrices fit the form of the DARE that includes only Q and R cost
|
|
|
|
|
|
// matrices.
|
|
|
|
|
|
//
|
|
|
|
|
|
// 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ᵀ
|
2021-02-15 18:17:55 -08:00
|
|
|
|
return new Matrix<>(
|
2023-05-14 22:23:00 -07:00
|
|
|
|
dare(
|
|
|
|
|
|
A.minus(B.times(R.solve(N.transpose()))).getStorage(),
|
|
|
|
|
|
B.getStorage(),
|
|
|
|
|
|
Q.minus(N.times(R.solve(N.transpose()))).getStorage(),
|
|
|
|
|
|
R.getStorage()));
|
2021-02-15 18:17:55 -08:00
|
|
|
|
}
|
2020-07-24 08:34:30 -07:00
|
|
|
|
}
|