10#include <Eigen/Cholesky>
53template <
int States,
int Inputs,
int Outputs>
85 : m_f(
std::move(f)), m_h(
std::move(h)) {
157 m_meanFuncX(
std::move(meanFuncX)),
158 m_meanFuncY(
std::move(meanFuncY)),
159 m_residualFuncX(
std::move(residualFuncX)),
160 m_residualFuncY(
std::move(residualFuncY)),
161 m_addFuncX(
std::move(addFuncX)) {
180 double S(
int i,
int j)
const {
return m_S(i, j); }
212 double Xhat(
int i)
const {
return m_xHat(i); }
227 void SetXhat(
int i,
double value) { m_xHat(i) = value; }
253 Eigen::internal::llt_inplace<double, Eigen::Lower>::blocked(discQ);
256 m_pts.SquareRootSigmaPoints(m_xHat, m_S);
258 for (
int i = 0; i < m_pts.NumSigmas(); ++i) {
259 StateVector x = sigmas.template block<States, 1>(0, i);
260 m_sigmasF.template block<States, 1>(0, i) =
RK4(m_f, x, u, dt);
264 m_sigmasF, m_pts.Wm(), m_pts.Wc(), m_meanFuncX, m_residualFuncX,
265 discQ.template triangularView<Eigen::Lower>());
278 m_residualFuncX, m_addFuncX);
293 m_residualFuncX, m_addFuncX);
329 std::move(residualFuncY), std::move(residualFuncX),
330 std::move(addFuncX));
368 Eigen::internal::llt_inplace<double, Eigen::Lower>::blocked(discR);
373 m_pts.SquareRootSigmaPoints(m_xHat, m_S);
374 for (
int i = 0; i < m_pts.NumSigmas(); ++i) {
375 sigmasH.template block<Rows, 1>(0, i) =
376 h(sigmas.template block<States, 1>(0, i), u);
381 sigmasH, m_pts.Wm(), m_pts.Wc(), meanFuncY, residualFuncY,
382 discR.template triangularView<Eigen::Lower>());
387 for (
int i = 0; i < m_pts.NumSigmas(); ++i) {
391 (residualFuncX(m_sigmasF.template block<States, 1>(0, i), m_xHat)) *
392 (residualFuncY(sigmasH.template block<Rows, 1>(0, i), yHat))
401 .fullPivHouseholderQr()
402 .solve(Sy.fullPivHouseholderQr().solve(Pxy.transpose()))
406 m_xHat = addFuncX(m_xHat, K * residualFuncY(y, yHat));
409 for (
int i = 0; i < Rows; i++) {
410 Eigen::internal::llt_inplace<double, Eigen::Upper>::rankUpdate(
411 m_S, U.template block<States, 1>(0, i), -1);
434 units::second_t m_dt;
440 UnscentedKalmanFilter<3, 3, 1>;
442 UnscentedKalmanFilter<5, 3, 3>;
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
#define EXPORT_TEMPLATE_DECLARE(export)
Definition SymbolExports.hpp:92
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:54
const StateVector & Xhat() const
Returns the state estimate x-hat.
Definition UnscentedKalmanFilter.h:205
Matrixd< States, States > StateMatrix
Definition UnscentedKalmanFilter.h:63
const StateMatrix & S() const
Returns the square-root error covariance matrix S.
Definition UnscentedKalmanFilter.h:172
Vectord< Outputs > OutputVector
Definition UnscentedKalmanFilter.h:58
double Xhat(int i) const
Returns an element of the state estimate x-hat.
Definition UnscentedKalmanFilter.h:212
void Predict(const InputVector &u, units::second_t dt)
Project the model into the future with a new control input u.
Definition UnscentedKalmanFilter.h:244
void Correct(const InputVector &u, const Vectord< Rows > &y, std::function< Vectord< Rows >(const StateVector &, const InputVector &)> h, const Matrixd< Rows, Rows > &R, std::function< Vectord< Rows >(const Matrixd< Rows, 2 *States+1 > &, const Vectord< 2 *States+1 > &)> meanFuncY, std::function< Vectord< Rows >(const Vectord< Rows > &, const Vectord< Rows > &)> residualFuncY, std::function< StateVector(const StateVector &, const StateVector &)> residualFuncX, std::function< StateVector(const StateVector &, const StateVector &)> addFuncX)
Correct the state estimate x-hat using the measurements in y.
Definition UnscentedKalmanFilter.h:354
double S(int i, int j) const
Returns an element of the square-root error covariance matrix S.
Definition UnscentedKalmanFilter.h:180
Vectord< States > StateVector
Definition UnscentedKalmanFilter.h:56
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:290
void SetS(const StateMatrix &S)
Set the current square-root error covariance matrix S.
Definition UnscentedKalmanFilter.h:187
UnscentedKalmanFilter(std::function< StateVector(const StateVector &, const InputVector &)> f, std::function< OutputVector(const StateVector &, const InputVector &)> h, const StateArray &stateStdDevs, const OutputArray &measurementStdDevs, std::function< StateVector(const Matrixd< States, 2 *States+1 > &, const Vectord< 2 *States+1 > &)> meanFuncX, std::function< OutputVector(const Matrixd< Outputs, 2 *States+1 > &, const Vectord< 2 *States+1 > &)> meanFuncY, std::function< StateVector(const StateVector &, const StateVector &)> residualFuncX, std::function< OutputVector(const OutputVector &, const OutputVector &)> residualFuncY, std::function< StateVector(const StateVector &, const StateVector &)> addFuncX, units::second_t dt)
Constructs an unscented Kalman filter with custom mean, residual, and addition functions.
Definition UnscentedKalmanFilter.h:138
StateMatrix P() const
Returns the reconstructed error covariance matrix P.
Definition UnscentedKalmanFilter.h:192
void SetXhat(const StateVector &xHat)
Set initial state estimate x-hat.
Definition UnscentedKalmanFilter.h:219
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.h:80
void SetXhat(int i, double value)
Set an element of the initial state estimate x-hat.
Definition UnscentedKalmanFilter.h:227
void Correct(const InputVector &u, const Vectord< Rows > &y, std::function< Vectord< Rows >(const StateVector &, const InputVector &)> h, const Matrixd< Rows, Rows > &R)
Correct the state estimate x-hat using the measurements in y.
Definition UnscentedKalmanFilter.h:310
Vectord< Inputs > InputVector
Definition UnscentedKalmanFilter.h:57
void SetP(const StateMatrix &P)
Set the current square-root error covariance matrix S by taking the square root of P.
Definition UnscentedKalmanFilter.h:200
void Reset()
Resets the observer.
Definition UnscentedKalmanFilter.h:232
void Correct(const InputVector &u, const OutputVector &y)
Correct the state estimate x-hat using the measurements in y.
Definition UnscentedKalmanFilter.h:276
This class is a wrapper around std::array that does compile time size checking.
Definition array.h:26
std::tuple< Vectord< CovDim >, Matrixd< CovDim, CovDim > > SquareRootUnscentedTransform(const Matrixd< CovDim, 2 *States+1 > &sigmas, const Vectord< 2 *States+1 > &Wm, const Vectord< 2 *States+1 > &Wc, std::function< Vectord< CovDim >(const Matrixd< CovDim, 2 *States+1 > &, const Vectord< 2 *States+1 > &)> meanFunc, std::function< Vectord< CovDim >(const Vectord< CovDim > &, const Vectord< CovDim > &)> residualFunc, const Matrixd< CovDim, CovDim > &squareRootR)
Computes unscented transform of a set of sigma points and weights.
Definition UnscentedTransform.h:40
T RK4(F &&f, T x, units::second_t dt)
Performs 4th order Runge-Kutta integration of dx/dt = f(x) for dt.
Definition NumericalIntegration.h:23
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
auto NumericalJacobianX(F &&f, const Vectord< States > &x, const Vectord< Inputs > &u, Args &&... args)
Returns numerical Jacobian with respect to x for f(x, u, ...).
Definition NumericalJacobian.h:51
Implement std::hash so that hash_code can be used in STL containers.
Definition PointerIntPair.h:280