35template <
int States,
int Inputs,
int Outputs>
62 const OutputArray& measurementStdDevs, units::second_t dt);
75 double P(
int i,
int j)
const {
return m_P(i, j); }
94 double Xhat(
int i)
const {
return m_xHat(i); }
109 void SetXhat(
int i,
double value) { m_xHat(i) = value; }
155 units::second_t m_dt;
161 KalmanFilter<1, 1, 1>;
163 KalmanFilter<2, 1, 1>;
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
A Kalman filter combines predictions from a model and measurements to give an estimate of the true sy...
Definition: KalmanFilter.h:36
void SetXhat(int i, double value)
Set an element of the initial state estimate x-hat.
Definition: KalmanFilter.h:109
Vectord< States > StateVector
Definition: KalmanFilter.h:38
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.inc:23
const StateVector & Xhat() const
Returns the state estimate x-hat.
Definition: KalmanFilter.h:87
void Predict(const InputVector &u, units::second_t dt)
Project the model into the future with a new control input u.
Definition: KalmanFilter.inc:59
Vectord< Outputs > OutputVector
Definition: KalmanFilter.h:40
double Xhat(int i) const
Returns an element of the state estimate x-hat.
Definition: KalmanFilter.h:94
void SetP(const StateMatrix &P)
Set the current error covariance matrix P.
Definition: KalmanFilter.h:82
void Correct(const InputVector &u, const OutputVector &y)
Correct the state estimate x-hat using the measurements in y.
Definition: KalmanFilter.h:133
const StateMatrix & P() const
Returns the error covariance matrix P.
Definition: KalmanFilter.h:67
double P(int i, int j) const
Returns an element of the error covariance matrix P.
Definition: KalmanFilter.h:75
void Reset()
Resets the observer.
Definition: KalmanFilter.h:114
Vectord< Inputs > InputVector
Definition: KalmanFilter.h:39
Matrixd< States, States > StateMatrix
Definition: KalmanFilter.h:45
void SetXhat(const StateVector &xHat)
Set initial state estimate x-hat.
Definition: KalmanFilter.h:101
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
static constexpr const unit_t< compound_unit< energy::joules, inverse< temperature::kelvin >, inverse< substance::moles > > > R(8.3144598)
Gas constant.