27template <
int States,
int Inputs>
50 template <
int Outputs>
122 double K(
int i,
int j)
const {
return m_K(i, j); }
138 double R(
int i)
const {
return m_r(i); }
154 double U(
int i)
const {
return m_u(i); }
195 template <
int Outputs>
197 units::second_t dt, units::second_t inputDelay);
#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:159
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:145
const Matrixd< Inputs, States > & K() const
Returns the controller matrix K.
Definition: LinearQuadraticRegulator.h:114
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:122
double U(int i) const
Returns an element of the control input vector u.
Definition: LinearQuadraticRegulator.h:154
const StateVector & R() const
Returns the reference vector r.
Definition: LinearQuadraticRegulator.h:129
double R(int i) const
Returns an element of the reference vector r.
Definition: LinearQuadraticRegulator.h:138
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) LinearQuadraticRegulator< 1