10#include <Eigen/Cholesky>
11#include <unsupported/Eigen/MatrixFunctions>
20#include "wpi/units/time.hpp"
37template <
int States,
int Inputs>
60 template <
int Outputs>
63 wpi::units::second_t dt)
83 wpi::units::second_t dt)
101 wpi::units::second_t dt) {
108 m_K = (discB.transpose() *
S.value() * discB +
R)
110 .solve(discB.transpose() *
S.value() * discA);
113 std::string msg = fmt::format(
"{}\n\nQ =\n{}\n",
to_string(
S.error()), Q);
116 throw std::invalid_argument(msg);
119 std::string msg = fmt::format(
"{}\n\nR =\n{}\n",
to_string(
S.error()),
R);
122 throw std::invalid_argument(msg);
124 std::string msg = fmt::format(
"{}\n\nA =\n{}\nB =\n{}\n",
128 throw std::invalid_argument(msg);
130 std::string msg = fmt::format(
"{}\n\nA =\n{}\nQ =\n{}\n",
134 throw std::invalid_argument(msg);
157 wpi::units::second_t dt) {
164 m_K = (discB.transpose() *
S.value() * discB +
R)
166 .solve(discB.transpose() *
S.value() * discA + N.transpose());
169 std::string msg = fmt::format(
"{}\n\nQ =\n{}\n",
to_string(
S.error()), Q);
172 throw std::invalid_argument(msg);
175 std::string msg = fmt::format(
"{}\n\nR =\n{}\n",
to_string(
S.error()),
R);
178 throw std::invalid_argument(msg);
181 fmt::format(
"{}\n\nA =\n{}\nB =\n{}\n",
to_string(
S.error()),
182 discA - discB *
R.llt().solve(N.transpose()), discB);
185 throw std::invalid_argument(msg);
187 auto R_llt =
R.llt();
189 fmt::format(
"{}\n\nA =\n{}\nQ =\n{}\n",
to_string(
S.error()),
190 discA - discB * R_llt.solve(N.transpose()),
191 Q - N * R_llt.solve(N.transpose()));
194 throw std::invalid_argument(msg);
215 double K(
int i,
int j)
const {
return m_K(i, j); }
231 double R(
int i)
const {
return m_r(i); }
247 double U(
int i)
const {
return m_u(i); }
263 m_u = m_K * (m_r - x);
294 template <
int Outputs>
296 wpi::units::second_t dt,
297 wpi::units::second_t inputDelay) {
302 m_K = m_K * (discA - discB * m_K).pow(inputDelay / dt);
316template <
int States,
int Inputs>
#define S(label, offset, message)
Definition Errors.hpp:113
#define EXPORT_TEMPLATE_DECLARE(export)
Definition SymbolExports.hpp:94
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
Contains the controller coefficients and logic for a linear-quadratic regulator (LQR).
Definition LinearQuadraticRegulator.hpp:38
double U(int i) const
Returns an element of the control input vector u.
Definition LinearQuadraticRegulator.hpp:247
void Reset()
Resets the controller.
Definition LinearQuadraticRegulator.hpp:252
double K(int i, int j) const
Returns an element of the controller matrix K.
Definition LinearQuadraticRegulator.hpp:215
void LatencyCompensate(const LinearSystem< States, Inputs, Outputs > &plant, wpi::units::second_t dt, wpi::units::second_t inputDelay)
Adjusts LQR controller gain to compensate for a pure time delay in the input.
Definition LinearQuadraticRegulator.hpp:295
LinearQuadraticRegulator(const Matrixd< States, States > &A, const Matrixd< States, Inputs > &B, const StateArray &Qelems, const InputArray &Relems, wpi::units::second_t dt)
Constructs a controller with the given coefficients and plant.
Definition LinearQuadraticRegulator.hpp:80
LinearQuadraticRegulator(const Matrixd< States, States > &A, const Matrixd< States, Inputs > &B, const Matrixd< States, States > &Q, const Matrixd< Inputs, Inputs > &R, wpi::units::second_t dt)
Constructs a controller with the given coefficients and plant.
Definition LinearQuadraticRegulator.hpp:97
const StateVector & R() const
Returns the reference vector r.
Definition LinearQuadraticRegulator.hpp:222
Vectord< Inputs > InputVector
Definition LinearQuadraticRegulator.hpp:41
wpi::util::array< double, Inputs > InputArray
Definition LinearQuadraticRegulator.hpp:44
Vectord< States > StateVector
Definition LinearQuadraticRegulator.hpp:40
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, wpi::units::second_t dt)
Constructs a controller with the given coefficients and plant.
Definition LinearQuadraticRegulator.hpp:152
LinearQuadraticRegulator(const LinearSystem< States, Inputs, Outputs > &plant, const StateArray &Qelems, const InputArray &Relems, wpi::units::second_t dt)
Constructs a controller with the given coefficients and plant.
Definition LinearQuadraticRegulator.hpp:61
wpi::util::array< double, States > StateArray
Definition LinearQuadraticRegulator.hpp:43
LinearQuadraticRegulator & operator=(LinearQuadraticRegulator &&)=default
const InputVector & U() const
Returns the control input vector u.
Definition LinearQuadraticRegulator.hpp:238
InputVector Calculate(const StateVector &x)
Returns the next output of the controller.
Definition LinearQuadraticRegulator.hpp:262
const Matrixd< Inputs, States > & K() const
Returns the controller matrix K.
Definition LinearQuadraticRegulator.hpp:207
InputVector Calculate(const StateVector &x, const StateVector &nextR)
Returns the next output of the controller.
Definition LinearQuadraticRegulator.hpp:273
double R(int i) const
Returns an element of the reference vector r.
Definition LinearQuadraticRegulator.hpp:231
LinearQuadraticRegulator(LinearQuadraticRegulator &&)=default
A plant defined using state-space notation.
Definition LinearSystem.hpp:35
constexpr const Matrixd< States, States > & A() const
Returns the system matrix A.
Definition LinearSystem.hpp:104
constexpr const Matrixd< States, Inputs > & B() const
Returns the input matrix B.
Definition LinearSystem.hpp:117
static void ReportUsage(std::string_view resource, std::string_view data)
Definition MathShared.hpp:61
static void ReportError(const S &format, Args &&... args)
Definition MathShared.hpp:48
This class is a wrapper around std::array that does compile time size checking.
Definition array.hpp:26
Definition LinearSystem.hpp:20
wpi::util::expected< Eigen::Matrix< double, States, States >, DAREError > DARE(const Eigen::Matrix< double, States, States > &A, const Eigen::Matrix< double, States, Inputs > &B, const Eigen::Matrix< double, States, States > &Q, const Eigen::Matrix< double, Inputs, Inputs > &R, bool checkPreconditions=true)
Computes the unique stabilizing solution X to the discrete-time algebraic Riccati equation:
Definition DARE.hpp:169
LinearQuadraticRegulator< States, Inputs > LQR
Definition LinearQuadraticRegulator.hpp:317
@ QNotPositiveSemidefinite
Q was not positive semidefinite.
Definition DARE.hpp:25
@ RNotSymmetric
R was not symmetric.
Definition DARE.hpp:27
@ QNotSymmetric
Q was not symmetric.
Definition DARE.hpp:23
@ ACNotDetectable
(A, C) pair where Q = CᵀC was not detectable.
Definition DARE.hpp:33
@ RNotPositiveDefinite
R was not positive definite.
Definition DARE.hpp:29
@ ABNotStabilizable
(A, B) pair was not stabilizable.
Definition DARE.hpp:31
constexpr std::string_view to_string(const DAREError &error)
Converts the given DAREError enum to a string.
Definition DARE.hpp:39
constexpr Eigen::Matrix< double, sizeof...(Ts), sizeof...(Ts)> CostMatrix(Ts... tolerances)
Creates a cost matrix from the given vector for use with LQR.
Definition StateSpaceUtil.hpp:34
Eigen::Matrix< double, Rows, Cols, Options, MaxRows, MaxCols > Matrixd
Definition EigenCore.hpp:21
void DiscretizeAB(const Matrixd< States, States > &contA, const Matrixd< States, Inputs > &contB, wpi::units::second_t dt, Matrixd< States, States > *discA, Matrixd< States, Inputs > *discB)
Discretizes the given continuous A and B matrices.
Definition Discretization.hpp:41
Eigen::Vector< double, Size > Vectord
Definition EigenCore.hpp:12