WPILibC++ 2026.2.1
Loading...
Searching...
No Matches
LinearQuadraticRegulator.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 <unsupported/Eigen/MatrixFunctions>
12#include <wpi/SymbolExports.h>
13#include <wpi/array.h>
14
15#include "frc/DARE.h"
16#include "frc/EigenCore.h"
17#include "frc/StateSpaceUtil.h"
18#include "frc/fmt/Eigen.h"
21#include "units/time.h"
22#include "wpimath/MathShared.h"
23
24namespace frc {
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 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 units::second_t dt)
85 MakeCostMatrix(Relems), 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 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();
140 }
141
142 /**
143 * Constructs a controller with the given coefficients and plant.
144 *
145 * @param A Continuous system matrix of the plant being controlled.
146 * @param B Continuous input matrix of the plant being controlled.
147 * @param Q The state cost matrix.
148 * @param R The input cost matrix.
149 * @param N The state-input cross-term cost matrix.
150 * @param dt Discretization timestep.
151 * @throws std::invalid_argument If the system is unstabilizable.
152 */
158 units::second_t dt) {
161 DiscretizeAB<States, Inputs>(A, B, dt, &discA, &discB);
162
163 if (auto S = DARE<States, Inputs>(discA, discB, Q, R, N)) {
164 // K = (BᵀSB + R)⁻¹(BᵀSA + Nᵀ)
165 m_K = (discB.transpose() * S.value() * discB + R)
166 .llt()
167 .solve(discB.transpose() * S.value() * discA + N.transpose());
168 } else if (S.error() == DAREError::QNotSymmetric ||
170 std::string msg = fmt::format("{}\n\nQ =\n{}\n", to_string(S.error()), Q);
171
173 throw std::invalid_argument(msg);
174 } else if (S.error() == DAREError::RNotSymmetric ||
176 std::string msg = fmt::format("{}\n\nR =\n{}\n", to_string(S.error()), R);
177
179 throw std::invalid_argument(msg);
180 } else if (S.error() == DAREError::ABNotStabilizable) {
181 std::string msg =
182 fmt::format("{}\n\nA =\n{}\nB =\n{}\n", to_string(S.error()),
183 discA - discB * R.llt().solve(N.transpose()), discB);
184
186 throw std::invalid_argument(msg);
187 } else if (S.error() == DAREError::ACNotDetectable) {
188 auto R_llt = R.llt();
189 std::string msg =
190 fmt::format("{}\n\nA =\n{}\nQ =\n{}\n", to_string(S.error()),
191 discA - discB * R_llt.solve(N.transpose()),
192 Q - N * R_llt.solve(N.transpose()));
193
195 throw std::invalid_argument(msg);
196 }
197
198 Reset();
201 }
202
205
206 /**
207 * Returns the controller matrix K.
208 */
209 const Matrixd<Inputs, States>& K() const { return m_K; }
210
211 /**
212 * Returns an element of the controller matrix K.
213 *
214 * @param i Row of K.
215 * @param j Column of K.
216 */
217 double K(int i, int j) const { return m_K(i, j); }
218
219 /**
220 * Returns the reference vector r.
221 *
222 * @return The reference vector.
223 */
224 const StateVector& R() const { return m_r; }
225
226 /**
227 * Returns an element of the reference vector r.
228 *
229 * @param i Row of r.
230 *
231 * @return The row of the reference vector.
232 */
233 double R(int i) const { return m_r(i); }
234
235 /**
236 * Returns the control input vector u.
237 *
238 * @return The control input.
239 */
240 const InputVector& U() const { return m_u; }
241
242 /**
243 * Returns an element of the control input vector u.
244 *
245 * @param i Row of u.
246 *
247 * @return The row of the control input vector.
248 */
249 double U(int i) const { return m_u(i); }
250
251 /**
252 * Resets the controller.
253 */
254 void Reset() {
255 m_r.setZero();
256 m_u.setZero();
257 }
258
259 /**
260 * Returns the next output of the controller.
261 *
262 * @param x The current state x.
263 */
265 m_u = m_K * (m_r - x);
266 return m_u;
267 }
268
269 /**
270 * Returns the next output of the controller.
271 *
272 * @param x The current state x.
273 * @param nextR The next reference vector r.
274 */
276 m_r = nextR;
277 return Calculate(x);
278 }
279
280 /**
281 * Adjusts LQR controller gain to compensate for a pure time delay in the
282 * input.
283 *
284 * Linear-Quadratic regulator controller gains tend to be aggressive. If
285 * sensor measurements are time-delayed too long, the LQR may be unstable.
286 * However, if we know the amount of delay, we can compute the control based
287 * on where the system will be after the time delay.
288 *
289 * See https://file.tavsys.net/control/controls-engineering-in-frc.pdf
290 * appendix C.4 for a derivation.
291 *
292 * @param plant The plant being controlled.
293 * @param dt Discretization timestep.
294 * @param inputDelay Input time delay.
295 */
296 template <int Outputs>
298 units::second_t dt, units::second_t inputDelay) {
301 DiscretizeAB<States, Inputs>(plant.A(), plant.B(), dt, &discA, &discB);
302
303 m_K = m_K * (discA - discB * m_K).pow(inputDelay / dt);
304 }
305
306 private:
307 // Current reference
308 StateVector m_r;
309
310 // Computed controller output
311 InputVector m_u;
312
313 // Controller gain
315};
316
317extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
318 LinearQuadraticRegulator<1, 1>;
319extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
320 LinearQuadraticRegulator<2, 1>;
321extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
322 LinearQuadraticRegulator<2, 2>;
323
324} // namespace frc
#define EXPORT_TEMPLATE_DECLARE(export)
Definition SymbolExports.h:94
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
Contains the controller coefficients and logic for a linear-quadratic regulator (LQR).
Definition LinearQuadraticRegulator.h:38
Vectord< States > StateVector
Definition LinearQuadraticRegulator.h:40
void Reset()
Resets the controller.
Definition LinearQuadraticRegulator.h:254
LinearQuadraticRegulator & operator=(LinearQuadraticRegulator &&)=default
LinearQuadraticRegulator(const Matrixd< States, States > &A, const Matrixd< States, Inputs > &B, const StateArray &Qelems, const InputArray &Relems, units::second_t dt)
Constructs a controller with the given coefficients and plant.
Definition LinearQuadraticRegulator.h:80
LinearQuadraticRegulator(LinearQuadraticRegulator &&)=default
void LatencyCompensate(const LinearSystem< States, Inputs, Outputs > &plant, units::second_t dt, units::second_t inputDelay)
Adjusts LQR controller gain to compensate for a pure time delay in the input.
Definition LinearQuadraticRegulator.h:297
InputVector Calculate(const StateVector &x, const StateVector &nextR)
Returns the next output of the controller.
Definition LinearQuadraticRegulator.h:275
const InputVector & U() const
Returns the control input vector u.
Definition LinearQuadraticRegulator.h:240
const Matrixd< Inputs, States > & K() const
Returns the controller matrix K.
Definition LinearQuadraticRegulator.h:209
LinearQuadraticRegulator(const LinearSystem< States, Inputs, Outputs > &plant, const StateArray &Qelems, const InputArray &Relems, units::second_t dt)
Constructs a controller with the given coefficients and plant.
Definition LinearQuadraticRegulator.h:61
Vectord< Inputs > InputVector
Definition LinearQuadraticRegulator.h:41
LinearQuadraticRegulator(const Matrixd< States, States > &A, const Matrixd< States, Inputs > &B, const Matrixd< States, States > &Q, const Matrixd< Inputs, Inputs > &R, units::second_t dt)
Constructs a controller with the given coefficients and plant.
Definition LinearQuadraticRegulator.h:97
double K(int i, int j) const
Returns an element of the controller matrix K.
Definition LinearQuadraticRegulator.h:217
double U(int i) const
Returns an element of the control input vector u.
Definition LinearQuadraticRegulator.h:249
InputVector Calculate(const StateVector &x)
Returns the next output of the controller.
Definition LinearQuadraticRegulator.h:264
const StateVector & R() const
Returns the reference vector r.
Definition LinearQuadraticRegulator.h:224
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, units::second_t dt)
Constructs a controller with the given coefficients and plant.
Definition LinearQuadraticRegulator.h:153
double R(int i) const
Returns an element of the reference vector r.
Definition LinearQuadraticRegulator.h:233
A plant defined using state-space notation.
Definition LinearSystem.h:35
constexpr const Matrixd< States, States > & A() const
Returns the system matrix A.
Definition LinearSystem.h:104
constexpr const Matrixd< States, Inputs > & B() const
Returns the input matrix B.
Definition LinearSystem.h:117
This class is a wrapper around std::array that does compile time size checking.
Definition array.h:26
static void ReportError(const S &format, Args &&... args)
Definition MathShared.h:67
static void ReportUsage(MathUsageId id, int count)
Definition MathShared.h:80
Definition CAN.h:11
void DiscretizeAB(const Matrixd< States, States > &contA, const Matrixd< States, Inputs > &contB, units::second_t dt, Matrixd< States, States > *discA, Matrixd< States, Inputs > *discB)
Discretizes the given continuous A and B matrices.
Definition Discretization.h:41
Eigen::Matrix< double, Rows, Cols, Options, MaxRows, MaxCols > Matrixd
Definition EigenCore.h:21
Eigen::Vector< double, Size > Vectord
Definition EigenCore.h:12
wpi::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.h:169
constexpr std::string_view to_string(const DAREError &error)
Converts the given DAREError enum to a string.
Definition DARE.h:39
@ QNotPositiveSemidefinite
Q was not positive semidefinite.
@ RNotSymmetric
R was not symmetric.
@ QNotSymmetric
Q was not symmetric.
@ ACNotDetectable
(A, C) pair where Q = CᵀC was not detectable.
@ RNotPositiveDefinite
R was not positive definite.
@ ABNotStabilizable
(A, B) pair was not stabilizable.
constexpr Matrixd< sizeof...(Ts), sizeof...(Ts)> MakeCostMatrix(Ts... tolerances)
Creates a cost matrix from the given vector for use with LQR.
Definition StateSpaceUtil.h:37
#define S(label, offset, message)
Definition Errors.h:113