WPILibC++ 2023.4.3-108-ge5452e3
frc::LinearQuadraticRegulator< States, Inputs > Class Template Reference

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
 
LinearQuadraticRegulatoroperator= (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 StateVectorR () const
 Returns the reference vector r. More...
 
double R (int i) const
 Returns an element of the reference vector r. More...
 
const InputVectorU () 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...
 

Detailed Description

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
StatesNumber of states.
InputsNumber of inputs.

Member Typedef Documentation

◆ InputArray

template<int States, int Inputs>
using frc::LinearQuadraticRegulator< States, Inputs >::InputArray = wpi::array<double, Inputs>

◆ InputVector

template<int States, int Inputs>
using frc::LinearQuadraticRegulator< States, Inputs >::InputVector = Vectord<Inputs>

◆ StateArray

template<int States, int Inputs>
using frc::LinearQuadraticRegulator< States, Inputs >::StateArray = wpi::array<double, States>

◆ StateVector

template<int States, int Inputs>
using frc::LinearQuadraticRegulator< States, Inputs >::StateVector = Vectord<States>

Constructor & Destructor Documentation

◆ LinearQuadraticRegulator() [1/5]

template<int States, int Inputs>
template<int Outputs>
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.

Parameters
plantThe plant being controlled.
QelemsThe maximum desired error tolerance for each state.
RelemsThe maximum desired control effort for each input.
dtDiscretization timestep.
Exceptions
std::invalid_argumentIf the system is uncontrollable.

◆ LinearQuadraticRegulator() [2/5]

template<int States, int Inputs>
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.

Parameters
AContinuous system matrix of the plant being controlled.
BContinuous input matrix of the plant being controlled.
QelemsThe maximum desired error tolerance for each state.
RelemsThe maximum desired control effort for each input.
dtDiscretization timestep.
Exceptions
std::invalid_argumentIf the system is uncontrollable.

◆ LinearQuadraticRegulator() [3/5]

template<int States, int Inputs>
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.

Parameters
AContinuous system matrix of the plant being controlled.
BContinuous input matrix of the plant being controlled.
QThe state cost matrix.
RThe input cost matrix.
dtDiscretization timestep.
Exceptions
std::invalid_argumentIf the system is uncontrollable.

◆ LinearQuadraticRegulator() [4/5]

template<int States, int Inputs>
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.

Parameters
AContinuous system matrix of the plant being controlled.
BContinuous input matrix of the plant being controlled.
QThe state cost matrix.
RThe input cost matrix.
NThe state-input cross-term cost matrix.
dtDiscretization timestep.
Exceptions
std::invalid_argumentIf the system is uncontrollable.

◆ LinearQuadraticRegulator() [5/5]

template<int States, int Inputs>
frc::LinearQuadraticRegulator< States, Inputs >::LinearQuadraticRegulator ( LinearQuadraticRegulator< States, Inputs > &&  )
default

Member Function Documentation

◆ Calculate() [1/2]

template<int States, int Inputs>
LinearQuadraticRegulator< States, Inputs >::InputVector frc::LinearQuadraticRegulator< States, Inputs >::Calculate ( const StateVector x)

Returns the next output of the controller.

Parameters
xThe current state x.

◆ Calculate() [2/2]

template<int States, int Inputs>
LinearQuadraticRegulator< States, Inputs >::InputVector frc::LinearQuadraticRegulator< States, Inputs >::Calculate ( const StateVector x,
const StateVector nextR 
)

Returns the next output of the controller.

Parameters
xThe current state x.
nextRThe next reference vector r.

◆ K() [1/2]

template<int States, int Inputs>
const Matrixd< Inputs, States > & frc::LinearQuadraticRegulator< States, Inputs >::K ( ) const
inline

Returns the controller matrix K.

◆ K() [2/2]

template<int States, int Inputs>
double frc::LinearQuadraticRegulator< States, Inputs >::K ( int  i,
int  j 
) const
inline

Returns an element of the controller matrix K.

Parameters
iRow of K.
jColumn of K.

◆ LatencyCompensate()

template<int States, int Inputs>
template<int Outputs>
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.

Parameters
plantThe plant being controlled.
dtDiscretization timestep.
inputDelayInput time delay.

◆ operator=()

template<int States, int Inputs>
LinearQuadraticRegulator & frc::LinearQuadraticRegulator< States, Inputs >::operator= ( LinearQuadraticRegulator< States, Inputs > &&  )
default

◆ R() [1/2]

template<int States, int Inputs>
const StateVector & frc::LinearQuadraticRegulator< States, Inputs >::R ( ) const
inline

Returns the reference vector r.

Returns
The reference vector.

◆ R() [2/2]

template<int States, int Inputs>
double frc::LinearQuadraticRegulator< States, Inputs >::R ( int  i) const
inline

Returns an element of the reference vector r.

Parameters
iRow of r.
Returns
The row of the reference vector.

◆ Reset()

template<int States, int Inputs>
void frc::LinearQuadraticRegulator< States, Inputs >::Reset ( )
inline

Resets the controller.

◆ U() [1/2]

template<int States, int Inputs>
const InputVector & frc::LinearQuadraticRegulator< States, Inputs >::U ( ) const
inline

Returns the control input vector u.

Returns
The control input.

◆ U() [2/2]

template<int States, int Inputs>
double frc::LinearQuadraticRegulator< States, Inputs >::U ( int  i) const
inline

Returns an element of the control input vector u.

Parameters
iRow of u.
Returns
The row of the control input vector.

The documentation for this class was generated from the following files: