WPILibC++ 2023.4.3-108-ge5452e3
|
Contains the controller coefficients and logic for a linear-quadratic regulator (LQR). More...
#include <frc/controller/LinearQuadraticRegulator.h>
Public Types | |
using | StateVector = Vectord< States > |
using | InputVector = Vectord< Inputs > |
using | StateArray = wpi::array< double, States > |
using | InputArray = wpi::array< double, Inputs > |
Public Member Functions | |
template<int Outputs> | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
LinearQuadraticRegulator (LinearQuadraticRegulator &&)=default | |
LinearQuadraticRegulator & | operator= (LinearQuadraticRegulator &&)=default |
const Matrixd< Inputs, States > & | K () const |
Returns the controller matrix K. More... | |
double | K (int i, int j) const |
Returns an element of the controller matrix K. More... | |
const StateVector & | R () const |
Returns the reference vector r. More... | |
double | R (int i) const |
Returns an element of the reference vector r. More... | |
const InputVector & | U () const |
Returns the control input vector u. More... | |
double | U (int i) const |
Returns an element of the control input vector u. More... | |
void | Reset () |
Resets the controller. More... | |
InputVector | Calculate (const StateVector &x) |
Returns the next output of the controller. More... | |
InputVector | Calculate (const StateVector &x, const StateVector &nextR) |
Returns the next output of the controller. More... | |
template<int Outputs> | |
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. More... | |
Contains the controller coefficients and logic for a linear-quadratic regulator (LQR).
LQRs use the control law u = K(r - x).
For more on the underlying math, read https://file.tavsys.net/control/controls-engineering-in-frc.pdf.
States | Number of states. |
Inputs | Number of inputs. |
using frc::LinearQuadraticRegulator< States, Inputs >::InputArray = wpi::array<double, Inputs> |
using frc::LinearQuadraticRegulator< States, Inputs >::InputVector = Vectord<Inputs> |
using frc::LinearQuadraticRegulator< States, Inputs >::StateArray = wpi::array<double, States> |
using frc::LinearQuadraticRegulator< States, Inputs >::StateVector = Vectord<States> |
frc::LinearQuadraticRegulator< States, Inputs >::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.
plant | The plant being controlled. |
Qelems | The maximum desired error tolerance for each state. |
Relems | The maximum desired control effort for each input. |
dt | Discretization timestep. |
std::invalid_argument | If the system is uncontrollable. |
frc::LinearQuadraticRegulator< States, Inputs >::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.
A | Continuous system matrix of the plant being controlled. |
B | Continuous input matrix of the plant being controlled. |
Qelems | The maximum desired error tolerance for each state. |
Relems | The maximum desired control effort for each input. |
dt | Discretization timestep. |
std::invalid_argument | If the system is uncontrollable. |
frc::LinearQuadraticRegulator< States, Inputs >::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.
A | Continuous system matrix of the plant being controlled. |
B | Continuous input matrix of the plant being controlled. |
Q | The state cost matrix. |
R | The input cost matrix. |
dt | Discretization timestep. |
std::invalid_argument | If the system is uncontrollable. |
frc::LinearQuadraticRegulator< States, Inputs >::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.
A | Continuous system matrix of the plant being controlled. |
B | Continuous input matrix of the plant being controlled. |
Q | The state cost matrix. |
R | The input cost matrix. |
N | The state-input cross-term cost matrix. |
dt | Discretization timestep. |
std::invalid_argument | If the system is uncontrollable. |
|
default |
LinearQuadraticRegulator< States, Inputs >::InputVector frc::LinearQuadraticRegulator< States, Inputs >::Calculate | ( | const StateVector & | x | ) |
Returns the next output of the controller.
x | The current state x. |
LinearQuadraticRegulator< States, Inputs >::InputVector frc::LinearQuadraticRegulator< States, Inputs >::Calculate | ( | const StateVector & | x, |
const StateVector & | nextR | ||
) |
Returns the next output of the controller.
x | The current state x. |
nextR | The next reference vector r. |
|
inline |
Returns the controller matrix K.
|
inline |
Returns an element of the controller matrix K.
i | Row of K. |
j | Column of K. |
void frc::LinearQuadraticRegulator< States, Inputs >::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.
Linear-Quadratic regulator controller gains tend to be aggressive. If sensor measurements are time-delayed too long, the LQR may be unstable. However, if we know the amount of delay, we can compute the control based on where the system will be after the time delay.
See https://file.tavsys.net/control/controls-engineering-in-frc.pdf appendix C.4 for a derivation.
plant | The plant being controlled. |
dt | Discretization timestep. |
inputDelay | Input time delay. |
|
default |
|
inline |
Returns the reference vector r.
|
inline |
Returns an element of the reference vector r.
i | Row of r. |
|
inline |
Resets the controller.
|
inline |
Returns the control input vector u.
|
inline |
Returns an element of the control input vector u.
i | Row of u. |