WPILibC++ 2024.3.2
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 <wpi/SymbolExports.h>
8#include <wpi/array.h>
9
10#include "frc/EigenCore.h"
12#include "units/time.h"
13
14namespace frc {
15
16/**
17 * Contains the controller coefficients and logic for a linear-quadratic
18 * regulator (LQR).
19 * LQRs use the control law u = K(r - x).
20 *
21 * For more on the underlying math, read
22 * https://file.tavsys.net/control/controls-engineering-in-frc.pdf.
23 *
24 * @tparam States Number of states.
25 * @tparam Inputs Number of inputs.
26 */
27template <int States, int Inputs>
29 public:
32
35
36 /**
37 * Constructs a controller with the given coefficients and plant.
38 *
39 * See
40 * https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning
41 * for how to select the tolerances.
42 *
43 * @tparam Outputs Number of outputs.
44 * @param plant The plant being controlled.
45 * @param Qelems The maximum desired error tolerance for each state.
46 * @param Relems The maximum desired control effort for each input.
47 * @param dt Discretization timestep.
48 * @throws std::invalid_argument If the system is uncontrollable.
49 */
50 template <int Outputs>
52 const StateArray& Qelems, const InputArray& Relems,
53 units::second_t dt);
54
55 /**
56 * Constructs a controller with the given coefficients and plant.
57 *
58 * See
59 * https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning
60 * for how to select the tolerances.
61 *
62 * @param A Continuous system matrix of the plant being controlled.
63 * @param B Continuous input matrix of the plant being controlled.
64 * @param Qelems The maximum desired error tolerance for each state.
65 * @param Relems The maximum desired control effort for each input.
66 * @param dt Discretization timestep.
67 * @throws std::invalid_argument If the system is uncontrollable.
68 */
71 const StateArray& Qelems, const InputArray& Relems,
72 units::second_t dt);
73
74 /**
75 * Constructs a controller with the given coefficients and plant.
76 *
77 * @param A Continuous system matrix of the plant being controlled.
78 * @param B Continuous input matrix of the plant being controlled.
79 * @param Q The state cost matrix.
80 * @param R The input cost matrix.
81 * @param dt Discretization timestep.
82 * @throws std::invalid_argument If the system is uncontrollable.
83 */
88 units::second_t dt);
89
90 /**
91 * Constructs a controller with the given coefficients and plant.
92 *
93 * @param A Continuous system matrix of the plant being controlled.
94 * @param B Continuous input matrix of the plant being controlled.
95 * @param Q The state cost matrix.
96 * @param R The input cost matrix.
97 * @param N The state-input cross-term cost matrix.
98 * @param dt Discretization timestep.
99 * @throws std::invalid_argument If the system is uncontrollable.
100 */
106 units::second_t dt);
107
110
111 /**
112 * Returns the controller matrix K.
113 */
114 const Matrixd<Inputs, States>& K() const { return m_K; }
115
116 /**
117 * Returns an element of the controller matrix K.
118 *
119 * @param i Row of K.
120 * @param j Column of K.
121 */
122 double K(int i, int j) const { return m_K(i, j); }
123
124 /**
125 * Returns the reference vector r.
126 *
127 * @return The reference vector.
128 */
129 const StateVector& R() const { return m_r; }
130
131 /**
132 * Returns an element of the reference vector r.
133 *
134 * @param i Row of r.
135 *
136 * @return The row of the reference vector.
137 */
138 double R(int i) const { return m_r(i); }
139
140 /**
141 * Returns the control input vector u.
142 *
143 * @return The control input.
144 */
145 const InputVector& U() const { return m_u; }
146
147 /**
148 * Returns an element of the control input vector u.
149 *
150 * @param i Row of u.
151 *
152 * @return The row of the control input vector.
153 */
154 double U(int i) const { return m_u(i); }
155
156 /**
157 * Resets the controller.
158 */
159 void Reset() {
160 m_r.setZero();
161 m_u.setZero();
162 }
163
164 /**
165 * Returns the next output of the controller.
166 *
167 * @param x The current state x.
168 */
170
171 /**
172 * Returns the next output of the controller.
173 *
174 * @param x The current state x.
175 * @param nextR The next reference vector r.
176 */
177 InputVector Calculate(const StateVector& x, const StateVector& nextR);
178
179 /**
180 * Adjusts LQR controller gain to compensate for a pure time delay in the
181 * input.
182 *
183 * Linear-Quadratic regulator controller gains tend to be aggressive. If
184 * sensor measurements are time-delayed too long, the LQR may be unstable.
185 * However, if we know the amount of delay, we can compute the control based
186 * on where the system will be after the time delay.
187 *
188 * See https://file.tavsys.net/control/controls-engineering-in-frc.pdf
189 * appendix C.4 for a derivation.
190 *
191 * @param plant The plant being controlled.
192 * @param dt Discretization timestep.
193 * @param inputDelay Input time delay.
194 */
195 template <int Outputs>
197 units::second_t dt, units::second_t inputDelay);
198
199 private:
200 // Current reference
201 StateVector m_r;
202
203 // Computed controller output
204 InputVector m_u;
205
206 // Controller gain
208};
209
212extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
214extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
216
217} // namespace frc
218
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Contains the controller coefficients and logic for a linear-quadratic regulator (LQR).
Definition: LinearQuadraticRegulator.h:28
Vectord< States > StateVector
Definition: LinearQuadraticRegulator.h:30
void Reset()
Resets the controller.
Definition: LinearQuadraticRegulator.h:159
LinearQuadraticRegulator & operator=(LinearQuadraticRegulator &&)=default
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.inc:101
const InputVector & U() const
Returns the control input vector u.
Definition: LinearQuadraticRegulator.h:145
const Matrixd< Inputs, States > & K() const
Returns the controller matrix K.
Definition: LinearQuadraticRegulator.h:114
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.inc:24
InputVector Calculate(const StateVector &x)
Returns the next output of the controller.
Definition: LinearQuadraticRegulator.inc:86
Vectord< Inputs > InputVector
Definition: LinearQuadraticRegulator.h:31
double K(int i, int j) const
Returns an element of the controller matrix K.
Definition: LinearQuadraticRegulator.h:122
double U(int i) const
Returns an element of the control input vector u.
Definition: LinearQuadraticRegulator.h:154
const StateVector & R() const
Returns the reference vector r.
Definition: LinearQuadraticRegulator.h:129
double R(int i) const
Returns an element of the reference vector r.
Definition: LinearQuadraticRegulator.h:138
A plant defined using state-space notation.
Definition: LinearSystem.h:31
This class is a wrapper around std::array that does compile time size checking.
Definition: array.h:26
Definition: AprilTagPoseEstimator.h:15
Eigen::Matrix< double, Rows, Cols, Options, MaxRows, MaxCols > Matrixd
Definition: EigenCore.h:21
Eigen::Vector< double, Size > Vectord
Definition: EigenCore.h:12
template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT) LinearQuadraticRegulator< 1