WPILibC++ 2024.1.1-beta-4
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 * @param plant The plant being controlled.
44 * @param Qelems The maximum desired error tolerance for each state.
45 * @param Relems The maximum desired control effort for each input.
46 * @param dt Discretization timestep.
47 * @throws std::invalid_argument If the system is uncontrollable.
48 */
49 template <int Outputs>
51 const StateArray& Qelems, const InputArray& Relems,
52 units::second_t dt);
53
54 /**
55 * Constructs a controller with the given coefficients and plant.
56 *
57 * See
58 * https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning
59 * for how to select the tolerances.
60 *
61 * @param A Continuous system matrix of the plant being controlled.
62 * @param B Continuous input matrix of the plant being controlled.
63 * @param Qelems The maximum desired error tolerance for each state.
64 * @param Relems The maximum desired control effort for each input.
65 * @param dt Discretization timestep.
66 * @throws std::invalid_argument If the system is uncontrollable.
67 */
70 const StateArray& Qelems, const InputArray& Relems,
71 units::second_t dt);
72
73 /**
74 * Constructs a controller with the given coefficients and plant.
75 *
76 * @param A Continuous system matrix of the plant being controlled.
77 * @param B Continuous input matrix of the plant being controlled.
78 * @param Q The state cost matrix.
79 * @param R The input cost matrix.
80 * @param dt Discretization timestep.
81 * @throws std::invalid_argument If the system is uncontrollable.
82 */
87 units::second_t dt);
88
89 /**
90 * Constructs a controller with the given coefficients and plant.
91 *
92 * @param A Continuous system matrix of the plant being controlled.
93 * @param B Continuous input matrix of the plant being controlled.
94 * @param Q The state cost matrix.
95 * @param R The input cost matrix.
96 * @param N The state-input cross-term cost matrix.
97 * @param dt Discretization timestep.
98 * @throws std::invalid_argument If the system is uncontrollable.
99 */
105 units::second_t dt);
106
109
110 /**
111 * Returns the controller matrix K.
112 */
113 const Matrixd<Inputs, States>& K() const { return m_K; }
114
115 /**
116 * Returns an element of the controller matrix K.
117 *
118 * @param i Row of K.
119 * @param j Column of K.
120 */
121 double K(int i, int j) const { return m_K(i, j); }
122
123 /**
124 * Returns the reference vector r.
125 *
126 * @return The reference vector.
127 */
128 const StateVector& R() const { return m_r; }
129
130 /**
131 * Returns an element of the reference vector r.
132 *
133 * @param i Row of r.
134 *
135 * @return The row of the reference vector.
136 */
137 double R(int i) const { return m_r(i); }
138
139 /**
140 * Returns the control input vector u.
141 *
142 * @return The control input.
143 */
144 const InputVector& U() const { return m_u; }
145
146 /**
147 * Returns an element of the control input vector u.
148 *
149 * @param i Row of u.
150 *
151 * @return The row of the control input vector.
152 */
153 double U(int i) const { return m_u(i); }
154
155 /**
156 * Resets the controller.
157 */
158 void Reset() {
159 m_r.setZero();
160 m_u.setZero();
161 }
162
163 /**
164 * Returns the next output of the controller.
165 *
166 * @param x The current state x.
167 */
169
170 /**
171 * Returns the next output of the controller.
172 *
173 * @param x The current state x.
174 * @param nextR The next reference vector r.
175 */
176 InputVector Calculate(const StateVector& x, const StateVector& nextR);
177
178 /**
179 * Adjusts LQR controller gain to compensate for a pure time delay in the
180 * input.
181 *
182 * Linear-Quadratic regulator controller gains tend to be aggressive. If
183 * sensor measurements are time-delayed too long, the LQR may be unstable.
184 * However, if we know the amount of delay, we can compute the control based
185 * on where the system will be after the time delay.
186 *
187 * See https://file.tavsys.net/control/controls-engineering-in-frc.pdf
188 * appendix C.4 for a derivation.
189 *
190 * @param plant The plant being controlled.
191 * @param dt Discretization timestep.
192 * @param inputDelay Input time delay.
193 */
194 template <int Outputs>
196 units::second_t dt, units::second_t inputDelay);
197
198 private:
199 // Current reference
200 StateVector m_r;
201
202 // Computed controller output
203 InputVector m_u;
204
205 // Controller gain
207};
208
209extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
210 LinearQuadraticRegulator<1, 1>;
211extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
212 LinearQuadraticRegulator<2, 1>;
213extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
214 LinearQuadraticRegulator<2, 2>;
215
216} // namespace frc
217
#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:158
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:144
const Matrixd< Inputs, States > & K() const
Returns the controller matrix K.
Definition: LinearQuadraticRegulator.h:113
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:121
double U(int i) const
Returns an element of the control input vector u.
Definition: LinearQuadraticRegulator.h:153
const StateVector & R() const
Returns the reference vector r.
Definition: LinearQuadraticRegulator.h:128
double R(int i) const
Returns an element of the reference vector r.
Definition: LinearQuadraticRegulator.h:137
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) LinearSystemLoop< 1