11#include <Eigen/Cholesky>
45template <
int States,
int Inputs,
int Outputs>
72 const OutputArray& measurementStdDevs, units::second_t dt) {
86 const auto& C = plant.
C();
94 fmt::format(
"{}\n\nQ =\n{}\n",
to_string(P.error()), discQ);
97 throw std::invalid_argument(msg);
101 fmt::format(
"{}\n\nR =\n{}\n",
to_string(P.error()), discR);
104 throw std::invalid_argument(msg);
106 std::string msg = fmt::format(
107 "The (A, C) pair is not detectable.\n\nA =\n{}\nC =\n{}\n",
111 throw std::invalid_argument(msg);
113 std::string msg = fmt::format(
"{}\n\nA =\n{}\nQ =\n{}\n",
117 throw std::invalid_argument(msg);
134 double P(
int i,
int j)
const {
return m_P(i, j); }
153 double Xhat(
int i)
const {
return m_xHat(i); }
168 void SetXhat(
int i,
double value) { m_xHat(i) = value; }
190 m_xHat = m_plant->CalculateX(m_xHat, u, dt);
193 m_P = discA * m_P * discA.transpose() + discQ;
219 const auto& C = m_plant->C();
220 const auto& D = m_plant->D();
239 S.transpose().ldlt().solve(C * m_P.transpose()).transpose();
242 m_xHat += K * (y - (C * m_xHat + D * u));
246 m_P = (StateMatrix::Identity() - K * C) * m_P *
247 (StateMatrix::Identity() - K * C).transpose() +
248 K * discR * K.transpose();
257 units::second_t m_dt;
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
#define EXPORT_TEMPLATE_DECLARE(export)
Definition SymbolExports.hpp:92
A Kalman filter combines predictions from a model and measurements to give an estimate of the true sy...
Definition KalmanFilter.h:46
void SetXhat(int i, double value)
Set an element of the initial state estimate x-hat.
Definition KalmanFilter.h:168
Vectord< States > StateVector
Definition KalmanFilter.h:48
KalmanFilter(LinearSystem< States, Inputs, Outputs > &plant, const StateArray &stateStdDevs, const OutputArray &measurementStdDevs, units::second_t dt)
Constructs a Kalman filter with the given plant.
Definition KalmanFilter.h:70
const StateVector & Xhat() const
Returns the state estimate x-hat.
Definition KalmanFilter.h:146
void Correct(const InputVector &u, const OutputVector &y, const Matrixd< Outputs, Outputs > &R)
Correct the state estimate x-hat using the measurements in y.
Definition KalmanFilter.h:217
void Predict(const InputVector &u, units::second_t dt)
Project the model into the future with a new control input u.
Definition KalmanFilter.h:184
Vectord< Outputs > OutputVector
Definition KalmanFilter.h:50
double Xhat(int i) const
Returns an element of the state estimate x-hat.
Definition KalmanFilter.h:153
void SetP(const StateMatrix &P)
Set the current error covariance matrix P.
Definition KalmanFilter.h:141
void Correct(const InputVector &u, const OutputVector &y)
Correct the state estimate x-hat using the measurements in y.
Definition KalmanFilter.h:204
const StateMatrix & P() const
Returns the error covariance matrix P.
Definition KalmanFilter.h:126
double P(int i, int j) const
Returns an element of the error covariance matrix P.
Definition KalmanFilter.h:134
void Reset()
Resets the observer.
Definition KalmanFilter.h:173
Vectord< Inputs > InputVector
Definition KalmanFilter.h:49
Matrixd< States, States > StateMatrix
Definition KalmanFilter.h:55
void SetXhat(const StateVector &xHat)
Set initial state estimate x-hat.
Definition KalmanFilter.h:160
A plant defined using state-space notation.
Definition LinearSystem.h:35
constexpr const Matrixd< Outputs, States > & C() const
Returns the output matrix C.
Definition LinearSystem.h:130
constexpr const Matrixd< States, States > & A() const
Returns the system matrix A.
Definition LinearSystem.h:104
This class is a wrapper around std::array that does compile time size checking.
Definition array.h:26
static void ReportError(const S &format, Args &&... args)
Definition MathShared.h:62
void DiscretizeAQ(const Matrixd< States, States > &contA, const Matrixd< States, States > &contQ, units::second_t dt, Matrixd< States, States > *discA, Matrixd< States, States > *discQ)
Discretizes the given continuous A and Q matrices.
Definition Discretization.h:71
Eigen::Matrix< double, Rows, Cols, Options, MaxRows, MaxCols > Matrixd
Definition EigenCore.h:21
Eigen::Vector< double, Size > Vectord
Definition EigenCore.h:12
Matrixd< Outputs, Outputs > DiscretizeR(const Matrixd< Outputs, Outputs > &R, units::second_t dt)
Returns a discretized version of the provided continuous measurement noise covariance matrix.
Definition Discretization.h:113
constexpr Matrixd< sizeof...(Ts), sizeof...(Ts)> MakeCovMatrix(Ts... stdDevs)
Creates a covariance matrix from the given vector for use with Kalman filters.
Definition StateSpaceUtil.h:75
wpi::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.h:165
constexpr std::string_view to_string(const DAREError &error)
Converts the given DAREError enum to a string.
Definition DARE.h:39
@ QNotPositiveSemidefinite
Q was not positive semidefinite.
@ RNotSymmetric
R was not symmetric.
@ QNotSymmetric
Q was not symmetric.
@ ACNotDetectable
(A, C) pair where Q = CᵀC was not detectable.
@ RNotPositiveDefinite
R was not positive definite.
@ ABNotStabilizable
(A, B) pair was not stabilizable.
#define S(label, offset, message)
Definition Errors.h:113