WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
LinearQuadraticRegulator.hpp
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 <unsupported/Eigen/MatrixFunctions>
12
20#include "wpi/units/time.hpp"
22#include "wpi/util/array.hpp"
23
24namespace wpi::math {
25
26/**
27 * Contains the controller coefficients and logic for a linear-quadratic
28 * regulator (LQR).
29 * LQRs use the control law u = K(r - x).
30 *
31 * For more on the underlying math, read
32 * https://file.tavsys.net/control/controls-engineering-in-frc.pdf.
33 *
34 * @tparam States Number of states.
35 * @tparam Inputs Number of inputs.
36 */
37template <int States, int Inputs>
39 public:
42
45
46 /**
47 * Constructs a controller with the given coefficients and plant.
48 *
49 * See
50 * https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning
51 * for how to select the tolerances.
52 *
53 * @tparam Outputs Number of outputs.
54 * @param plant The plant being controlled.
55 * @param Qelems The maximum desired error tolerance for each state.
56 * @param Relems The maximum desired control effort for each input.
57 * @param dt Discretization timestep.
58 * @throws std::invalid_argument If the system is unstabilizable.
59 */
60 template <int Outputs>
62 const StateArray& Qelems, const InputArray& Relems,
63 wpi::units::second_t dt)
64 : LinearQuadraticRegulator(plant.A(), plant.B(), Qelems, Relems, dt) {}
65
66 /**
67 * Constructs a controller with the given coefficients and plant.
68 *
69 * See
70 * https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning
71 * for how to select the tolerances.
72 *
73 * @param A Continuous system matrix of the plant being controlled.
74 * @param B Continuous input matrix of the plant being controlled.
75 * @param Qelems The maximum desired error tolerance for each state.
76 * @param Relems The maximum desired control effort for each input.
77 * @param dt Discretization timestep.
78 * @throws std::invalid_argument If the system is unstabilizable.
79 */
82 const StateArray& Qelems, const InputArray& Relems,
83 wpi::units::second_t dt)
84 : LinearQuadraticRegulator(A, B, CostMatrix(Qelems), CostMatrix(Relems),
85 dt) {}
86
87 /**
88 * Constructs a controller with the given coefficients and plant.
89 *
90 * @param A Continuous system matrix of the plant being controlled.
91 * @param B Continuous input matrix of the plant being controlled.
92 * @param Q The state cost matrix.
93 * @param R The input cost matrix.
94 * @param dt Discretization timestep.
95 * @throws std::invalid_argument If the system is unstabilizable.
96 */
101 wpi::units::second_t dt) {
104 DiscretizeAB<States, Inputs>(A, B, dt, &discA, &discB);
105
106 if (auto S = DARE<States, Inputs>(discA, discB, Q, R)) {
107 // K = (BᵀSB + R)⁻¹BᵀSA
108 m_K = (discB.transpose() * S.value() * discB + R)
109 .llt()
110 .solve(discB.transpose() * S.value() * discA);
111 } else if (S.error() == DAREError::QNotSymmetric ||
113 std::string msg = fmt::format("{}\n\nQ =\n{}\n", to_string(S.error()), Q);
114
116 throw std::invalid_argument(msg);
117 } else if (S.error() == DAREError::RNotSymmetric ||
119 std::string msg = fmt::format("{}\n\nR =\n{}\n", to_string(S.error()), R);
120
122 throw std::invalid_argument(msg);
123 } else if (S.error() == DAREError::ABNotStabilizable) {
124 std::string msg = fmt::format("{}\n\nA =\n{}\nB =\n{}\n",
125 to_string(S.error()), discA, discB);
126
128 throw std::invalid_argument(msg);
129 } else if (S.error() == DAREError::ACNotDetectable) {
130 std::string msg = fmt::format("{}\n\nA =\n{}\nQ =\n{}\n",
131 to_string(S.error()), discA, Q);
132
134 throw std::invalid_argument(msg);
135 }
136
137 Reset();
138 wpi::math::MathSharedStore::ReportUsage("LinearQuadraticRegulator", "");
139 }
140
141 /**
142 * Constructs a controller with the given coefficients and plant.
143 *
144 * @param A Continuous system matrix of the plant being controlled.
145 * @param B Continuous input matrix of the plant being controlled.
146 * @param Q The state cost matrix.
147 * @param R The input cost matrix.
148 * @param N The state-input cross-term cost matrix.
149 * @param dt Discretization timestep.
150 * @throws std::invalid_argument If the system is unstabilizable.
151 */
157 wpi::units::second_t dt) {
160 DiscretizeAB<States, Inputs>(A, B, dt, &discA, &discB);
161
162 if (auto S = DARE<States, Inputs>(discA, discB, Q, R, N)) {
163 // K = (BᵀSB + R)⁻¹(BᵀSA + Nᵀ)
164 m_K = (discB.transpose() * S.value() * discB + R)
165 .llt()
166 .solve(discB.transpose() * S.value() * discA + N.transpose());
167 } else if (S.error() == DAREError::QNotSymmetric ||
169 std::string msg = fmt::format("{}\n\nQ =\n{}\n", to_string(S.error()), Q);
170
172 throw std::invalid_argument(msg);
173 } else if (S.error() == DAREError::RNotSymmetric ||
175 std::string msg = fmt::format("{}\n\nR =\n{}\n", to_string(S.error()), R);
176
178 throw std::invalid_argument(msg);
179 } else if (S.error() == DAREError::ABNotStabilizable) {
180 std::string msg =
181 fmt::format("{}\n\nA =\n{}\nB =\n{}\n", to_string(S.error()),
182 discA - discB * R.llt().solve(N.transpose()), discB);
183
185 throw std::invalid_argument(msg);
186 } else if (S.error() == DAREError::ACNotDetectable) {
187 auto R_llt = R.llt();
188 std::string msg =
189 fmt::format("{}\n\nA =\n{}\nQ =\n{}\n", to_string(S.error()),
190 discA - discB * R_llt.solve(N.transpose()),
191 Q - N * R_llt.solve(N.transpose()));
192
194 throw std::invalid_argument(msg);
195 }
196
197 Reset();
198 wpi::math::MathSharedStore::ReportUsage("LinearQuadraticRegulator", "");
199 }
200
203
204 /**
205 * Returns the controller matrix K.
206 */
207 const Matrixd<Inputs, States>& K() const { return m_K; }
208
209 /**
210 * Returns an element of the controller matrix K.
211 *
212 * @param i Row of K.
213 * @param j Column of K.
214 */
215 double K(int i, int j) const { return m_K(i, j); }
216
217 /**
218 * Returns the reference vector r.
219 *
220 * @return The reference vector.
221 */
222 const StateVector& R() const { return m_r; }
223
224 /**
225 * Returns an element of the reference vector r.
226 *
227 * @param i Row of r.
228 *
229 * @return The row of the reference vector.
230 */
231 double R(int i) const { return m_r(i); }
232
233 /**
234 * Returns the control input vector u.
235 *
236 * @return The control input.
237 */
238 const InputVector& U() const { return m_u; }
239
240 /**
241 * Returns an element of the control input vector u.
242 *
243 * @param i Row of u.
244 *
245 * @return The row of the control input vector.
246 */
247 double U(int i) const { return m_u(i); }
248
249 /**
250 * Resets the controller.
251 */
252 void Reset() {
253 m_r.setZero();
254 m_u.setZero();
255 }
256
257 /**
258 * Returns the next output of the controller.
259 *
260 * @param x The current state x.
261 */
263 m_u = m_K * (m_r - x);
264 return m_u;
265 }
266
267 /**
268 * Returns the next output of the controller.
269 *
270 * @param x The current state x.
271 * @param nextR The next reference vector r.
272 */
274 m_r = nextR;
275 return Calculate(x);
276 }
277
278 /**
279 * Adjusts LQR controller gain to compensate for a pure time delay in the
280 * input.
281 *
282 * Linear-Quadratic regulator controller gains tend to be aggressive. If
283 * sensor measurements are time-delayed too long, the LQR may be unstable.
284 * However, if we know the amount of delay, we can compute the control based
285 * on where the system will be after the time delay.
286 *
287 * See https://file.tavsys.net/control/controls-engineering-in-frc.pdf
288 * appendix C.4 for a derivation.
289 *
290 * @param plant The plant being controlled.
291 * @param dt Discretization timestep.
292 * @param inputDelay Input time delay.
293 */
294 template <int Outputs>
296 wpi::units::second_t dt,
297 wpi::units::second_t inputDelay) {
300 DiscretizeAB<States, Inputs>(plant.A(), plant.B(), dt, &discA, &discB);
301
302 m_K = m_K * (discA - discB * m_K).pow(inputDelay / dt);
303 }
304
305 private:
306 // Current reference
307 StateVector m_r;
308
309 // Computed controller output
310 InputVector m_u;
311
312 // Controller gain
314};
315
316template <int States, int Inputs>
318
321extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
323extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
325
326} // namespace wpi::math
#define S(label, offset, message)
Definition Errors.hpp:113
#define EXPORT_TEMPLATE_DECLARE(export)
Definition SymbolExports.hpp:94
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
Contains the controller coefficients and logic for a linear-quadratic regulator (LQR).
Definition LinearQuadraticRegulator.hpp:38
double U(int i) const
Returns an element of the control input vector u.
Definition LinearQuadraticRegulator.hpp:247
void Reset()
Resets the controller.
Definition LinearQuadraticRegulator.hpp:252
double K(int i, int j) const
Returns an element of the controller matrix K.
Definition LinearQuadraticRegulator.hpp:215
void LatencyCompensate(const LinearSystem< States, Inputs, Outputs > &plant, wpi::units::second_t dt, wpi::units::second_t inputDelay)
Adjusts LQR controller gain to compensate for a pure time delay in the input.
Definition LinearQuadraticRegulator.hpp:295
LinearQuadraticRegulator(const Matrixd< States, States > &A, const Matrixd< States, Inputs > &B, const StateArray &Qelems, const InputArray &Relems, wpi::units::second_t dt)
Constructs a controller with the given coefficients and plant.
Definition LinearQuadraticRegulator.hpp:80
LinearQuadraticRegulator(const Matrixd< States, States > &A, const Matrixd< States, Inputs > &B, const Matrixd< States, States > &Q, const Matrixd< Inputs, Inputs > &R, wpi::units::second_t dt)
Constructs a controller with the given coefficients and plant.
Definition LinearQuadraticRegulator.hpp:97
const StateVector & R() const
Returns the reference vector r.
Definition LinearQuadraticRegulator.hpp:222
Vectord< Inputs > InputVector
Definition LinearQuadraticRegulator.hpp:41
wpi::util::array< double, Inputs > InputArray
Definition LinearQuadraticRegulator.hpp:44
Vectord< States > StateVector
Definition LinearQuadraticRegulator.hpp:40
LinearQuadraticRegulator(const Matrixd< States, States > &A, const Matrixd< States, Inputs > &B, const Matrixd< States, States > &Q, const Matrixd< Inputs, Inputs > &R, const Matrixd< States, Inputs > &N, wpi::units::second_t dt)
Constructs a controller with the given coefficients and plant.
Definition LinearQuadraticRegulator.hpp:152
LinearQuadraticRegulator(const LinearSystem< States, Inputs, Outputs > &plant, const StateArray &Qelems, const InputArray &Relems, wpi::units::second_t dt)
Constructs a controller with the given coefficients and plant.
Definition LinearQuadraticRegulator.hpp:61
wpi::util::array< double, States > StateArray
Definition LinearQuadraticRegulator.hpp:43
LinearQuadraticRegulator & operator=(LinearQuadraticRegulator &&)=default
const InputVector & U() const
Returns the control input vector u.
Definition LinearQuadraticRegulator.hpp:238
InputVector Calculate(const StateVector &x)
Returns the next output of the controller.
Definition LinearQuadraticRegulator.hpp:262
const Matrixd< Inputs, States > & K() const
Returns the controller matrix K.
Definition LinearQuadraticRegulator.hpp:207
InputVector Calculate(const StateVector &x, const StateVector &nextR)
Returns the next output of the controller.
Definition LinearQuadraticRegulator.hpp:273
double R(int i) const
Returns an element of the reference vector r.
Definition LinearQuadraticRegulator.hpp:231
LinearQuadraticRegulator(LinearQuadraticRegulator &&)=default
A plant defined using state-space notation.
Definition LinearSystem.hpp:35
constexpr const Matrixd< States, States > & A() const
Returns the system matrix A.
Definition LinearSystem.hpp:104
constexpr const Matrixd< States, Inputs > & B() const
Returns the input matrix B.
Definition LinearSystem.hpp:117
static void ReportUsage(std::string_view resource, std::string_view data)
Definition MathShared.hpp:61
static void ReportError(const S &format, Args &&... args)
Definition MathShared.hpp:48
This class is a wrapper around std::array that does compile time size checking.
Definition array.hpp:26
Definition LinearSystem.hpp:20
wpi::util::expected< Eigen::Matrix< double, States, States >, DAREError > 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, bool checkPreconditions=true)
Computes the unique stabilizing solution X to the discrete-time algebraic Riccati equation:
Definition DARE.hpp:169
LinearQuadraticRegulator< States, Inputs > LQR
Definition LinearQuadraticRegulator.hpp:317
@ QNotPositiveSemidefinite
Q was not positive semidefinite.
Definition DARE.hpp:25
@ RNotSymmetric
R was not symmetric.
Definition DARE.hpp:27
@ QNotSymmetric
Q was not symmetric.
Definition DARE.hpp:23
@ ACNotDetectable
(A, C) pair where Q = CᵀC was not detectable.
Definition DARE.hpp:33
@ RNotPositiveDefinite
R was not positive definite.
Definition DARE.hpp:29
@ ABNotStabilizable
(A, B) pair was not stabilizable.
Definition DARE.hpp:31
constexpr std::string_view to_string(const DAREError &error)
Converts the given DAREError enum to a string.
Definition DARE.hpp:39
constexpr Eigen::Matrix< double, sizeof...(Ts), sizeof...(Ts)> CostMatrix(Ts... tolerances)
Creates a cost matrix from the given vector for use with LQR.
Definition StateSpaceUtil.hpp:34
Eigen::Matrix< double, Rows, Cols, Options, MaxRows, MaxCols > Matrixd
Definition EigenCore.hpp:21
void DiscretizeAB(const Matrixd< States, States > &contA, const Matrixd< States, Inputs > &contB, wpi::units::second_t dt, Matrixd< States, States > *discA, Matrixd< States, Inputs > *discB)
Discretizes the given continuous A and B matrices.
Definition Discretization.hpp:41
Eigen::Vector< double, Size > Vectord
Definition EigenCore.hpp:12