Contains the controller coefficients and logic for a linear-quadratic regulator (LQR).
More...
|
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.
|
|
| 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.
|
|
| 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.
|
|
| 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.
|
|
| LinearQuadraticRegulator (LinearQuadraticRegulator &&)=default |
|
LinearQuadraticRegulator & | operator= (LinearQuadraticRegulator &&)=default |
|
const Matrixd< Inputs, States > & | K () const |
| Returns the controller matrix K.
|
|
double | K (int i, int j) const |
| Returns an element of the controller matrix K.
|
|
const StateVector & | R () const |
| Returns the reference vector r.
|
|
double | R (int i) const |
| Returns an element of the reference vector r.
|
|
const InputVector & | U () const |
| Returns the control input vector u.
|
|
double | U (int i) const |
| Returns an element of the control input vector u.
|
|
void | Reset () |
| Resets the controller.
|
|
InputVector | Calculate (const StateVector &x) |
| Returns the next output of the controller.
|
|
InputVector | Calculate (const StateVector &x, const StateVector &nextR) |
| Returns the next output of the controller.
|
|
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.
|
|
template<int States, int Inputs>
class frc::LinearQuadraticRegulator< States, Inputs >
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.
- Template Parameters
-
States | Number of states. |
Inputs | Number of inputs. |
template<int States, int Inputs>
template<int Outputs>
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.
- Parameters
-
plant | The plant being controlled. |
dt | Discretization timestep. |
inputDelay | Input time delay. |