10#include <Eigen/Cholesky>
41template <
int States,
int Inputs>
43 const Eigen::Matrix<double, States, Inputs>& B,
44 const Eigen::Matrix<double, States, States>& Q) {
46 if ((Q - Q.transpose()).norm() > 1
e-10) {
47 std::string msg =
fmt::format(
"Q isn't symmetric!\n\nQ =\n{}\n", Q);
48 throw std::invalid_argument(msg);
60 auto Q_ldlt = Q.ldlt();
61 if (Q_ldlt.info() != Eigen::Success ||
62 (Q_ldlt.vectorD().array() < 0.0).any()) {
64 fmt::format(
"Q isn't positive semidefinite!\n\nQ =\n{}\n", Q);
65 throw std::invalid_argument(msg);
69 if (!IsStabilizable<States, Inputs>(A, B)) {
71 "The (A, B) pair isn't stabilizable!\n\nA =\n{}\nB =\n{}\n", A, B);
72 throw std::invalid_argument(msg);
80 Eigen::Matrix<double, States, States> C =
81 Q_ldlt.vectorD().cwiseSqrt().asDiagonal() *
82 Eigen::Matrix<double, States, States>{Q_ldlt.matrixL().transpose()} *
83 Q_ldlt.transpositionsP();
85 if (!IsDetectable<States, States>(A, C)) {
87 "The (A, C) pair where Q = CᵀC isn't detectable!\n\nA =\n{}\nQ "
90 throw std::invalid_argument(msg);
118template <
int States,
int Inputs>
119Eigen::Matrix<double, States, States>
DARE(
120 const Eigen::Matrix<double, States, States>& A,
121 const Eigen::Matrix<double, States, Inputs>& B,
122 const Eigen::Matrix<double, States, States>& Q,
123 const Eigen::LLT<Eigen::Matrix<double, Inputs, Inputs>>& R_llt) {
124 using StateMatrix = Eigen::Matrix<double, States, States>;
134 StateMatrix G_k = B * R_llt.solve(B.transpose());
140 StateMatrix H_k1 = Q;
146 StateMatrix W = StateMatrix::Identity(H_k.rows(), H_k.cols()) + G_k * H_k;
148 auto W_solver = W.lu();
151 StateMatrix V_1 = W_solver.solve(A_k);
166 StateMatrix V_2 = W_solver.solve(G_k.transpose()).transpose();
169 G_k += A_k * V_2 * A_k.transpose();
172 H_k1 = H_k + V_1.transpose() * H_k * A_k;
178 }
while ((H_k1 - H_k).norm() > 1
e-10 * H_k1.norm());
242template <
int States,
int Inputs>
243Eigen::Matrix<double, States, States>
DARE(
244 const Eigen::Matrix<double, States, States>& A,
245 const Eigen::Matrix<double, States, Inputs>& B,
246 const Eigen::Matrix<double, States, States>& Q,
247 const Eigen::LLT<Eigen::Matrix<double, Inputs, Inputs>>& R_llt,
248 const Eigen::Matrix<double, Inputs, Inputs>& N) {
260 return detail::DARE<States, Inputs>(A - B * R_llt.solve(N.transpose()), B,
261 Q - N * R_llt.solve(N.transpose()),
285template <
int States,
int Inputs>
286Eigen::Matrix<double, States, States>
DARE(
287 const Eigen::Matrix<double, States, States>& A,
288 const Eigen::Matrix<double, States, Inputs>& B,
289 const Eigen::Matrix<double, States, States>& Q,
290 const Eigen::Matrix<double, Inputs, Inputs>&
R) {
292 if ((
R -
R.transpose()).norm() > 1
e-10) {
293 std::string msg =
fmt::format(
"R isn't symmetric!\n\nR =\n{}\n",
R);
294 throw std::invalid_argument(msg);
298 auto R_llt =
R.llt();
299 if (R_llt.info() != Eigen::Success) {
300 std::string msg =
fmt::format(
"R isn't positive definite!\n\nR =\n{}\n",
R);
301 throw std::invalid_argument(msg);
304 detail::CheckDARE_ABQ<States, Inputs>(A, B, Q);
306 return detail::DARE<States, Inputs>(A, B, Q, R_llt);
363template <
int States,
int Inputs>
364Eigen::Matrix<double, States, States>
DARE(
365 const Eigen::Matrix<double, States, States>& A,
366 const Eigen::Matrix<double, States, Inputs>& B,
367 const Eigen::Matrix<double, States, States>& Q,
368 const Eigen::Matrix<double, Inputs, Inputs>&
R,
369 const Eigen::Matrix<double, States, Inputs>& N) {
371 if ((
R -
R.transpose()).norm() > 1
e-10) {
372 std::string msg =
fmt::format(
"R isn't symmetric!\n\nR =\n{}\n",
R);
373 throw std::invalid_argument(msg);
377 auto R_llt =
R.llt();
378 if (R_llt.info() != Eigen::Success) {
379 std::string msg =
fmt::format(
"R isn't positive definite!\n\nR =\n{}\n",
R);
380 throw std::invalid_argument(msg);
394 Eigen::Matrix<double, States, States> A_2 =
395 A - B * R_llt.solve(N.transpose());
396 Eigen::Matrix<double, States, States> Q_2 =
397 Q - N * R_llt.solve(N.transpose());
399 detail::CheckDARE_ABQ<States, Inputs>(A_2, B, Q_2);
401 return detail::DARE<States, Inputs>(A_2, B, Q_2, R_llt);
detail namespace with internal helper functions
Definition: xchar.h:20
void CheckDARE_ABQ(const Eigen::Matrix< double, States, States > &A, const Eigen::Matrix< double, States, Inputs > &B, const Eigen::Matrix< double, States, States > &Q)
Checks the preconditions of A, B, and Q for the DARE solver.
Definition: DARE.h:42
Eigen::Matrix< double, States, States > DARE(const Eigen::Matrix< double, States, States > &A, const Eigen::Matrix< double, States, Inputs > &B, const Eigen::Matrix< double, States, States > &Q, const Eigen::LLT< Eigen::Matrix< double, Inputs, Inputs > > &R_llt)
Computes the unique stabilizing solution X to the discrete-time algebraic Riccati equation:
Definition: DARE.h:119
Definition: AprilTagPoseEstimator.h:15
Eigen::Matrix< double, States, States > DARE(const Eigen::Matrix< double, States, States > &A, const Eigen::Matrix< double, States, Inputs > &B, const Eigen::Matrix< double, States, States > &Q, const Eigen::Matrix< double, Inputs, Inputs > &R)
Computes the unique stabilizing solution X to the discrete-time algebraic Riccati equation:
Definition: DARE.h:286
static constexpr const unit_t< compound_unit< energy::joules, inverse< temperature::kelvin >, inverse< substance::moles > > > R(8.3144598)
Gas constant.
static constexpr const charge::coulomb_t e(1.6021766208e-19)
elementary charge.
auto format(wformat_string< T... > fmt, T &&... args) -> std::wstring
Definition: xchar.h:108