46template <
int States,
int Inputs,
int Outputs>
136 double S(
int i,
int j)
const {
return m_S(i, j); }
168 double Xhat(
int i)
const {
return m_xHat(i); }
183 void SetXhat(
int i,
double value) { m_xHat(i) = value; }
209 Correct<Outputs>(u, y, m_h, m_contR, m_meanFuncY, m_residualFuncY,
210 m_residualFuncX, m_addFuncX);
224 Correct<Outputs>(u, y, m_h,
R, m_meanFuncY, m_residualFuncY,
225 m_residualFuncX, m_addFuncX);
301 units::second_t m_dt;
307 UnscentedKalmanFilter<3, 3, 1>;
309 UnscentedKalmanFilter<5, 3, 3>;
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Generates sigma points and weights according to Van der Merwe's 2004 dissertation[1] for the Unscente...
Definition: MerweScaledSigmaPoints.h:28
A Kalman filter combines predictions from a model and measurements to give an estimate of the true sy...
Definition: UnscentedKalmanFilter.h:47
const StateVector & Xhat() const
Returns the state estimate x-hat.
Definition: UnscentedKalmanFilter.h:161
Matrixd< States, States > StateMatrix
Definition: UnscentedKalmanFilter.h:56
const StateMatrix & S() const
Returns the square-root error covariance matrix S.
Definition: UnscentedKalmanFilter.h:128
Vectord< Outputs > OutputVector
Definition: UnscentedKalmanFilter.h:51
double Xhat(int i) const
Returns an element of the state estimate x-hat.
Definition: UnscentedKalmanFilter.h:168
void Predict(const InputVector &u, units::second_t dt)
Project the model into the future with a new control input u.
Definition: UnscentedKalmanFilter.inc:73
double S(int i, int j) const
Returns an element of the square-root error covariance matrix S.
Definition: UnscentedKalmanFilter.h:136
Vectord< States > StateVector
Definition: UnscentedKalmanFilter.h:49
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: UnscentedKalmanFilter.h:222
void SetS(const StateMatrix &S)
Set the current square-root error covariance matrix S.
Definition: UnscentedKalmanFilter.h:143
StateMatrix P() const
Returns the reconstructed error covariance matrix P.
Definition: UnscentedKalmanFilter.h:148
void SetXhat(const StateVector &xHat)
Set initial state estimate x-hat.
Definition: UnscentedKalmanFilter.h:175
UnscentedKalmanFilter(std::function< StateVector(const StateVector &, const InputVector &)> f, std::function< OutputVector(const StateVector &, const InputVector &)> h, const StateArray &stateStdDevs, const OutputArray &measurementStdDevs, units::second_t dt)
Constructs an unscented Kalman filter.
Definition: UnscentedKalmanFilter.inc:21
void SetXhat(int i, double value)
Set an element of the initial state estimate x-hat.
Definition: UnscentedKalmanFilter.h:183
Vectord< Inputs > InputVector
Definition: UnscentedKalmanFilter.h:50
void SetP(const StateMatrix &P)
Set the current square-root error covariance matrix S by taking the square root of P.
Definition: UnscentedKalmanFilter.h:156
void Reset()
Resets the observer.
Definition: UnscentedKalmanFilter.h:188
void Correct(const InputVector &u, const OutputVector &y)
Correct the state estimate x-hat using the measurements in y.
Definition: UnscentedKalmanFilter.h:208
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.
static constexpr const unit_t< compound_unit< energy::joule, time::seconds > > h(6.626070040e-34)
Planck constant.