WPILibC++ 2024.3.2
DARE.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <stdexcept>
8#include <string>
9
10#include <Eigen/Cholesky>
11#include <Eigen/Core>
12#include <Eigen/LU>
13
14#include "frc/StateSpaceUtil.h"
15#include "frc/fmt/Eigen.h"
16
17// Works cited:
18//
19// [1] E. K.-W. Chu, H.-Y. Fan, W.-W. Lin & C.-S. Wang "Structure-Preserving
20// Algorithms for Periodic Discrete-Time Algebraic Riccati Equations",
21// International Journal of Control, 77:8, 767-788, 2004.
22// DOI: 10.1080/00207170410001714988
23
24namespace frc {
25
26namespace detail {
27
28/**
29 * Checks the preconditions of A, B, and Q for the DARE solver.
30 *
31 * @tparam States Number of states.
32 * @tparam Inputs Number of inputs.
33 * @param A The system matrix.
34 * @param B The input matrix.
35 * @param Q The state cost matrix.
36 * @throws std::invalid_argument if Q isn't symmetric positive semidefinite.
37 * @throws std::invalid_argument if the (A, B) pair isn't stabilizable.
38 * @throws std::invalid_argument if the (A, C) pair where Q = CᵀC isn't
39 * detectable.
40 */
41template <int States, int Inputs>
42void CheckDARE_ABQ(const Eigen::Matrix<double, States, States>& A,
43 const Eigen::Matrix<double, States, Inputs>& B,
44 const Eigen::Matrix<double, States, States>& Q) {
45 // Require Q be symmetric
46 if ((Q - Q.transpose()).norm() > 1e-10) {
47 std::string msg = fmt::format("Q isn't symmetric!\n\nQ =\n{}\n", Q);
48 throw std::invalid_argument(msg);
49 }
50
51 // Require Q be positive semidefinite
52 //
53 // If Q is a symmetric matrix with a decomposition LDLᵀ, the number of
54 // positive, negative, and zero diagonal entries in D equals the number of
55 // positive, negative, and zero eigenvalues respectively in Q (see
56 // https://en.wikipedia.org/wiki/Sylvester's_law_of_inertia).
57 //
58 // Therefore, D having no negative diagonal entries is sufficient to prove Q
59 // is positive semidefinite.
60 auto Q_ldlt = Q.ldlt();
61 if (Q_ldlt.info() != Eigen::Success ||
62 (Q_ldlt.vectorD().array() < 0.0).any()) {
63 std::string msg =
64 fmt::format("Q isn't positive semidefinite!\n\nQ =\n{}\n", Q);
65 throw std::invalid_argument(msg);
66 }
67
68 // Require (A, B) pair be stabilizable
69 if (!IsStabilizable<States, Inputs>(A, B)) {
70 std::string msg = fmt::format(
71 "The (A, B) pair isn't stabilizable!\n\nA =\n{}\nB =\n{}\n", A, B);
72 throw std::invalid_argument(msg);
73 }
74
75 // Require (A, C) pair be detectable where Q = CᵀC
76 //
77 // Q = CᵀC = PᵀLDLᵀP
78 // C = √(D)LᵀP
79 {
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();
84
85 if (!IsDetectable<States, States>(A, C)) {
86 std::string msg = fmt::format(
87 "The (A, C) pair where Q = CᵀC isn't detectable!\n\nA =\n{}\nQ "
88 "=\n{}\n",
89 A, Q);
90 throw std::invalid_argument(msg);
91 }
92 }
93}
94
95/**
96 * Computes the unique stabilizing solution X to the discrete-time algebraic
97 * Riccati equation:
98 *
99 * AᵀXA − X − AᵀXB(BᵀXB + R)⁻¹BᵀXA + Q = 0
100 *
101 * This internal function skips expensive precondition checks for increased
102 * performance. The solver may hang if any of the following occur:
103 * <ul>
104 * <li>Q isn't symmetric positive semidefinite</li>
105 * <li>R isn't symmetric positive definite</li>
106 * <li>The (A, B) pair isn't stabilizable</li>
107 * <li>The (A, C) pair where Q = CᵀC isn't detectable</li>
108 * </ul>
109 * Only use this function if you're sure the preconditions are met.
110 *
111 * @tparam States Number of states.
112 * @tparam Inputs Number of inputs.
113 * @param A The system matrix.
114 * @param B The input matrix.
115 * @param Q The state cost matrix.
116 * @param R_llt The LLT decomposition of the input cost matrix.
117 */
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>;
125
126 // Implements the SDA algorithm on page 5 of [1].
127
128 // A₀ = A
129 StateMatrix A_k = A;
130
131 // G₀ = BR⁻¹Bᵀ
132 //
133 // See equation (4) of [1].
134 StateMatrix G_k = B * R_llt.solve(B.transpose());
135
136 // H₀ = Q
137 //
138 // See equation (4) of [1].
139 StateMatrix H_k;
140 StateMatrix H_k1 = Q;
141
142 do {
143 H_k = H_k1;
144
145 // W = I + GₖHₖ
146 StateMatrix W = StateMatrix::Identity(H_k.rows(), H_k.cols()) + G_k * H_k;
147
148 auto W_solver = W.lu();
149
150 // Solve WV₁ = Aₖ for V₁
151 StateMatrix V_1 = W_solver.solve(A_k);
152
153 // Solve V₂Wᵀ = Gₖ for V₂
154 //
155 // We want to put V₂Wᵀ = Gₖ into Ax = b form so we can solve it more
156 // efficiently.
157 //
158 // V₂Wᵀ = Gₖ
159 // (V₂Wᵀ)ᵀ = Gₖᵀ
160 // WV₂ᵀ = Gₖᵀ
161 //
162 // The solution of Ax = b can be found via x = A.solve(b).
163 //
164 // V₂ᵀ = W.solve(Gₖᵀ)
165 // V₂ = W.solve(Gₖᵀ)ᵀ
166 StateMatrix V_2 = W_solver.solve(G_k.transpose()).transpose();
167
168 // Gₖ₊₁ = Gₖ + AₖV₂Aₖᵀ
169 G_k += A_k * V_2 * A_k.transpose();
170
171 // Hₖ₊₁ = Hₖ + V₁ᵀHₖAₖ
172 H_k1 = H_k + V_1.transpose() * H_k * A_k;
173
174 // Aₖ₊₁ = AₖV₁
175 A_k *= V_1;
176
177 // while |Hₖ₊₁ − Hₖ| > ε |Hₖ₊₁|
178 } while ((H_k1 - H_k).norm() > 1e-10 * H_k1.norm());
179
180 return H_k1;
181}
182
183/**
184Computes the unique stabilizing solution X to the discrete-time algebraic
185Riccati equation:
186
187 AᵀXA − X − (AᵀXB + N)(BᵀXB + R)⁻¹(BᵀXA + Nᵀ) + Q = 0
188
189This is equivalent to solving the original DARE:
190
191 A₂ᵀXA₂ − X − A₂ᵀXB(BᵀXB + R)⁻¹BᵀXA₂ + Q₂ = 0
192
193where A₂ and Q₂ are a change of variables:
194
195 A₂ = A − BR⁻¹Nᵀ and Q₂ = Q − NR⁻¹Nᵀ
196
197This overload of the DARE is useful for finding the control law uₖ that
198minimizes the following cost function subject to xₖ₊₁ = Axₖ + Buₖ.
199
200@verbatim
201 ∞ [xₖ]ᵀ[Q N][xₖ]
202J = Σ [uₖ] [Nᵀ R][uₖ] ΔT
203 k=0
204@endverbatim
205
206This is a more general form of the following. The linear-quadratic regulator
207is the feedback control law uₖ that minimizes the following cost function
208subject to xₖ₊₁ = Axₖ + Buₖ:
209
210@verbatim
211
212J = Σ (xₖᵀQxₖ + uₖᵀRuₖ) ΔT
213 k=0
214@endverbatim
215
216This can be refactored as:
217
218@verbatim
219 ∞ [xₖ]ᵀ[Q 0][xₖ]
220J = Σ [uₖ] [0 R][uₖ] ΔT
221 k=0
222@endverbatim
223
224This internal function skips expensive precondition checks for increased
225performance. The solver may hang if any of the following occur:
226<ul>
227 <li>Q₂ isn't symmetric positive semidefinite</li>
228 <li>R isn't symmetric positive definite</li>
229 <li>The (A₂, B) pair isn't stabilizable</li>
230 <li>The (A₂, C) pair where Q₂ = CᵀC isn't detectable</li>
231</ul>
232Only use this function if you're sure the preconditions are met.
233
234@tparam States Number of states.
235@tparam Inputs Number of inputs.
236@param A The system matrix.
237@param B The input matrix.
238@param Q The state cost matrix.
239@param R_llt The LLT decomposition of the input cost matrix.
240@param N The state-input cross cost matrix.
241*/
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) {
249 // This is a change of variables to make the DARE that includes Q, R, and N
250 // cost matrices fit the form of the DARE that includes only Q and R cost
251 // matrices.
252 //
253 // This is equivalent to solving the original DARE:
254 //
255 // A₂ᵀXA₂ − X − A₂ᵀXB(BᵀXB + R)⁻¹BᵀXA₂ + Q₂ = 0
256 //
257 // where A₂ and Q₂ are a change of variables:
258 //
259 // A₂ = A − BR⁻¹Nᵀ and Q₂ = Q − NR⁻¹Nᵀ
260 return detail::DARE<States, Inputs>(A - B * R_llt.solve(N.transpose()), B,
261 Q - N * R_llt.solve(N.transpose()),
262 R_llt);
263}
264
265} // namespace detail
266
267/**
268 * Computes the unique stabilizing solution X to the discrete-time algebraic
269 * Riccati equation:
270 *
271 * AᵀXA − X − AᵀXB(BᵀXB + R)⁻¹BᵀXA + Q = 0
272 *
273 * @tparam States Number of states.
274 * @tparam Inputs Number of inputs.
275 * @param A The system matrix.
276 * @param B The input matrix.
277 * @param Q The state cost matrix.
278 * @param R The input cost matrix.
279 * @throws std::invalid_argument if Q isn't symmetric positive semidefinite.
280 * @throws std::invalid_argument if R isn't symmetric positive definite.
281 * @throws std::invalid_argument if the (A, B) pair isn't stabilizable.
282 * @throws std::invalid_argument if the (A, C) pair where Q = CᵀC isn't
283 * detectable.
284 */
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) {
291 // Require R be symmetric
292 if ((R - R.transpose()).norm() > 1e-10) {
293 std::string msg = fmt::format("R isn't symmetric!\n\nR =\n{}\n", R);
294 throw std::invalid_argument(msg);
295 }
296
297 // Require R be positive definite
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);
302 }
303
304 detail::CheckDARE_ABQ<States, Inputs>(A, B, Q);
305
306 return detail::DARE<States, Inputs>(A, B, Q, R_llt);
307}
308
309/**
310Computes the unique stabilizing solution X to the discrete-time algebraic
311Riccati equation:
312
313 AᵀXA − X − (AᵀXB + N)(BᵀXB + R)⁻¹(BᵀXA + Nᵀ) + Q = 0
314
315This is equivalent to solving the original DARE:
316
317 A₂ᵀXA₂ − X − A₂ᵀXB(BᵀXB + R)⁻¹BᵀXA₂ + Q₂ = 0
318
319where A₂ and Q₂ are a change of variables:
320
321 A₂ = A − BR⁻¹Nᵀ and Q₂ = Q − NR⁻¹Nᵀ
322
323This overload of the DARE is useful for finding the control law uₖ that
324minimizes the following cost function subject to xₖ₊₁ = Axₖ + Buₖ.
325
326@verbatim
327 ∞ [xₖ]ᵀ[Q N][xₖ]
328J = Σ [uₖ] [Nᵀ R][uₖ] ΔT
329 k=0
330@endverbatim
331
332This is a more general form of the following. The linear-quadratic regulator
333is the feedback control law uₖ that minimizes the following cost function
334subject to xₖ₊₁ = Axₖ + Buₖ:
335
336@verbatim
337
338J = Σ (xₖᵀQxₖ + uₖᵀRuₖ) ΔT
339 k=0
340@endverbatim
341
342This can be refactored as:
343
344@verbatim
345 ∞ [xₖ]ᵀ[Q 0][xₖ]
346J = Σ [uₖ] [0 R][uₖ] ΔT
347 k=0
348@endverbatim
349
350@tparam States Number of states.
351@tparam Inputs Number of inputs.
352@param A The system matrix.
353@param B The input matrix.
354@param Q The state cost matrix.
355@param R The input cost matrix.
356@param N The state-input cross cost matrix.
357@throws std::invalid_argument if Q₂ isn't symmetric positive semidefinite.
358@throws std::invalid_argument if R isn't symmetric positive definite.
359@throws std::invalid_argument if the (A₂, B) pair isn't stabilizable.
360@throws std::invalid_argument if the (A₂, C) pair where Q₂ = CᵀC isn't
361 detectable.
362*/
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) {
370 // Require R be symmetric
371 if ((R - R.transpose()).norm() > 1e-10) {
372 std::string msg = fmt::format("R isn't symmetric!\n\nR =\n{}\n", R);
373 throw std::invalid_argument(msg);
374 }
375
376 // Require R be positive definite
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);
381 }
382
383 // This is a change of variables to make the DARE that includes Q, R, and N
384 // cost matrices fit the form of the DARE that includes only Q and R cost
385 // matrices.
386 //
387 // This is equivalent to solving the original DARE:
388 //
389 // A₂ᵀXA₂ − X − A₂ᵀXB(BᵀXB + R)⁻¹BᵀXA₂ + Q₂ = 0
390 //
391 // where A₂ and Q₂ are a change of variables:
392 //
393 // A₂ = A − BR⁻¹Nᵀ and Q₂ = Q − NR⁻¹Nᵀ
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());
398
399 detail::CheckDARE_ABQ<States, Inputs>(A_2, B, Q_2);
400
401 return detail::DARE<States, Inputs>(A_2, B, Q_2, R_llt);
402}
403
404} // namespace frc
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