WPILibC++ 2025.3.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();
138 }
139
140 /**
141 * Constructs a controller with the given coefficients and plant.
142 *
143 * @param A Continuous system matrix of the plant being controlled.
144 * @param B Continuous input matrix of the plant being controlled.
145 * @param Q The state cost matrix.
146 * @param R The input cost matrix.
147 * @param N The state-input cross-term cost matrix.
148 * @param dt Discretization timestep.
149 * @throws std::invalid_argument If the system is unstabilizable.
150 */
156 units::second_t dt) {
159 DiscretizeAB<States, Inputs>(A, B, dt, &discA, &discB);
160
161 if (auto S = DARE<States, Inputs>(discA, discB, Q, R, N)) {
162 // K = (BᵀSB + R)⁻¹(BᵀSA + Nᵀ)
163 m_K = (discB.transpose() * S.value() * discB + R)
164 .llt()
165 .solve(discB.transpose() * S.value() * discA + N.transpose());
166 } else if (S.error() == DAREError::QNotSymmetric ||
168 std::string msg = fmt::format("{}\n\nQ =\n{}\n", to_string(S.error()), Q);
169
171 throw std::invalid_argument(msg);
172 } else if (S.error() == DAREError::RNotSymmetric ||
174 std::string msg = fmt::format("{}\n\nR =\n{}\n", to_string(S.error()), R);
175
177 throw std::invalid_argument(msg);
178 } else if (S.error() == DAREError::ABNotStabilizable) {
179 std::string msg =
180 fmt::format("{}\n\nA =\n{}\nB =\n{}\n", to_string(S.error()),
181 discA - discB * R.llt().solve(N.transpose()), discB);
182
184 throw std::invalid_argument(msg);
185 } else if (S.error() == DAREError::ACNotDetectable) {
186 auto R_llt = R.llt();
187 std::string msg =
188 fmt::format("{}\n\nA =\n{}\nQ =\n{}\n", to_string(S.error()),
189 discA - discB * R_llt.solve(N.transpose()),
190 Q - N * R_llt.solve(N.transpose()));
191
193 throw std::invalid_argument(msg);
194 }
195
196 Reset();
197 }
198
201
202 /**
203 * Returns the controller matrix K.
204 */
205 const Matrixd<Inputs, States>& K() const { return m_K; }
206
207 /**
208 * Returns an element of the controller matrix K.
209 *
210 * @param i Row of K.
211 * @param j Column of K.
212 */
213 double K(int i, int j) const { return m_K(i, j); }
214
215 /**
216 * Returns the reference vector r.
217 *
218 * @return The reference vector.
219 */
220 const StateVector& R() const { return m_r; }
221
222 /**
223 * Returns an element of the reference vector r.
224 *
225 * @param i Row of r.
226 *
227 * @return The row of the reference vector.
228 */
229 double R(int i) const { return m_r(i); }
230
231 /**
232 * Returns the control input vector u.
233 *
234 * @return The control input.
235 */
236 const InputVector& U() const { return m_u; }
237
238 /**
239 * Returns an element of the control input vector u.
240 *
241 * @param i Row of u.
242 *
243 * @return The row of the control input vector.
244 */
245 double U(int i) const { return m_u(i); }
246
247 /**
248 * Resets the controller.
249 */
250 void Reset() {
251 m_r.setZero();
252 m_u.setZero();
253 }
254
255 /**
256 * Returns the next output of the controller.
257 *
258 * @param x The current state x.
259 */
261 m_u = m_K * (m_r - x);
262 return m_u;
263 }
264
265 /**
266 * Returns the next output of the controller.
267 *
268 * @param x The current state x.
269 * @param nextR The next reference vector r.
270 */
272 m_r = nextR;
273 return Calculate(x);
274 }
275
276 /**
277 * Adjusts LQR controller gain to compensate for a pure time delay in the
278 * input.
279 *
280 * Linear-Quadratic regulator controller gains tend to be aggressive. If
281 * sensor measurements are time-delayed too long, the LQR may be unstable.
282 * However, if we know the amount of delay, we can compute the control based
283 * on where the system will be after the time delay.
284 *
285 * See https://file.tavsys.net/control/controls-engineering-in-frc.pdf
286 * appendix C.4 for a derivation.
287 *
288 * @param plant The plant being controlled.
289 * @param dt Discretization timestep.
290 * @param inputDelay Input time delay.
291 */
292 template <int Outputs>
294 units::second_t dt, units::second_t inputDelay) {
297 DiscretizeAB<States, Inputs>(plant.A(), plant.B(), dt, &discA, &discB);
298
299 m_K = m_K * (discA - discB * m_K).pow(inputDelay / dt);
300 }
301
302 private:
303 // Current reference
304 StateVector m_r;
305
306 // Computed controller output
307 InputVector m_u;
308
309 // Controller gain
311};
312
313extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
314 LinearQuadraticRegulator<1, 1>;
315extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
316 LinearQuadraticRegulator<2, 1>;
317extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
318 LinearQuadraticRegulator<2, 2>;
319
320} // namespace frc
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
#define EXPORT_TEMPLATE_DECLARE(export)
Definition SymbolExports.hpp:92
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:250
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:293
InputVector Calculate(const StateVector &x, const StateVector &nextR)
Returns the next output of the controller.
Definition LinearQuadraticRegulator.h:271
const InputVector & U() const
Returns the control input vector u.
Definition LinearQuadraticRegulator.h:236
const Matrixd< Inputs, States > & K() const
Returns the controller matrix K.
Definition LinearQuadraticRegulator.h:205
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:213
double U(int i) const
Returns an element of the control input vector u.
Definition LinearQuadraticRegulator.h:245
InputVector Calculate(const StateVector &x)
Returns the next output of the controller.
Definition LinearQuadraticRegulator.h:260
const StateVector & R() const
Returns the reference vector r.
Definition LinearQuadraticRegulator.h:220
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:151
double R(int i) const
Returns an element of the reference vector r.
Definition LinearQuadraticRegulator.h:229
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:62
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:165
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