WPILibC++ 2023.4.3
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 * @param plant The plant being controlled.
40 * @param Qelems The maximum desired error tolerance for each state.
41 * @param Relems The maximum desired control effort for each input.
42 * @param dt Discretization timestep.
43 * @throws std::invalid_argument If the system is uncontrollable.
44 */
45 template <int Outputs>
47 const StateArray& Qelems, const InputArray& Relems,
48 units::second_t dt);
49
50 /**
51 * Constructs a controller with the given coefficients and plant.
52 *
53 * @param A Continuous system matrix of the plant being controlled.
54 * @param B Continuous input matrix of 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 uncontrollable.
59 */
62 const StateArray& Qelems, const InputArray& Relems,
63 units::second_t dt);
64
65 /**
66 * Constructs a controller with the given coefficients and plant.
67 *
68 * @param A Continuous system matrix of the plant being controlled.
69 * @param B Continuous input matrix of the plant being controlled.
70 * @param Q The state cost matrix.
71 * @param R The input cost matrix.
72 * @param dt Discretization timestep.
73 * @throws std::invalid_argument If the system is uncontrollable.
74 */
79 units::second_t dt);
80
81 /**
82 * Constructs a controller with the given coefficients and plant.
83 *
84 * @param A Continuous system matrix of the plant being controlled.
85 * @param B Continuous input matrix of the plant being controlled.
86 * @param Q The state cost matrix.
87 * @param R The input cost matrix.
88 * @param N The state-input cross-term cost matrix.
89 * @param dt Discretization timestep.
90 * @throws std::invalid_argument If the system is uncontrollable.
91 */
97 units::second_t dt);
98
101
102 /**
103 * Returns the controller matrix K.
104 */
105 const Matrixd<Inputs, States>& K() const { return m_K; }
106
107 /**
108 * Returns an element of the controller matrix K.
109 *
110 * @param i Row of K.
111 * @param j Column of K.
112 */
113 double K(int i, int j) const { return m_K(i, j); }
114
115 /**
116 * Returns the reference vector r.
117 *
118 * @return The reference vector.
119 */
120 const StateVector& R() const { return m_r; }
121
122 /**
123 * Returns an element of the reference vector r.
124 *
125 * @param i Row of r.
126 *
127 * @return The row of the reference vector.
128 */
129 double R(int i) const { return m_r(i); }
130
131 /**
132 * Returns the control input vector u.
133 *
134 * @return The control input.
135 */
136 const InputVector& U() const { return m_u; }
137
138 /**
139 * Returns an element of the control input vector u.
140 *
141 * @param i Row of u.
142 *
143 * @return The row of the control input vector.
144 */
145 double U(int i) const { return m_u(i); }
146
147 /**
148 * Resets the controller.
149 */
150 void Reset() {
151 m_r.setZero();
152 m_u.setZero();
153 }
154
155 /**
156 * Returns the next output of the controller.
157 *
158 * @param x The current state x.
159 */
161
162 /**
163 * Returns the next output of the controller.
164 *
165 * @param x The current state x.
166 * @param nextR The next reference vector r.
167 */
168 InputVector Calculate(const StateVector& x, const StateVector& nextR);
169
170 /**
171 * Adjusts LQR controller gain to compensate for a pure time delay in the
172 * input.
173 *
174 * Linear-Quadratic regulator controller gains tend to be aggressive. If
175 * sensor measurements are time-delayed too long, the LQR may be unstable.
176 * However, if we know the amount of delay, we can compute the control based
177 * on where the system will be after the time delay.
178 *
179 * See https://file.tavsys.net/control/controls-engineering-in-frc.pdf
180 * appendix C.4 for a derivation.
181 *
182 * @param plant The plant being controlled.
183 * @param dt Discretization timestep.
184 * @param inputDelay Input time delay.
185 */
186 template <int Outputs>
188 units::second_t dt, units::second_t inputDelay);
189
190 private:
191 // Current reference
192 StateVector m_r;
193
194 // Computed controller output
195 InputVector m_u;
196
197 // Controller gain
199};
200
203extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
205extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
207
208} // namespace frc
209
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
The matrix class, also used for vectors and row-vectors.
Definition: Matrix.h:180
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:150
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:103
const InputVector & U() const
Returns the control input vector u.
Definition: LinearQuadraticRegulator.h:136
const Matrixd< Inputs, States > & K() const
Returns the controller matrix K.
Definition: LinearQuadraticRegulator.h:105
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:88
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:113
double U(int i) const
Returns an element of the control input vector u.
Definition: LinearQuadraticRegulator.h:145
const StateVector & R() const
Returns the reference vector r.
Definition: LinearQuadraticRegulator.h:120
double R(int i) const
Returns an element of the reference vector r.
Definition: LinearQuadraticRegulator.h:129
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:25
Definition: AprilTagFieldLayout.h:22
template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT) LinearQuadraticRegulator< 1
Eigen::Vector< double, Size > Vectord
Definition: EigenCore.h:12