- 3.0.2 optimal control module.
|
Unscented Kalman Filter is a nonlinear estimator best suited for highly nonlinear systems. It combines the principles of EKF and particle filter. The downside is the computation complexity. More...
#include <UnscentedKalmanFilter.h>
Public Member Functions | |
UnscentedKalmanFilter (std::shared_ptr< SystemModelBase< STATE_DIM, CONTROL_DIM, SCALAR >> f, std::shared_ptr< LinearMeasurementModel< OUTPUT_DIM, STATE_DIM, SCALAR >> h, const state_vector_t &x0=state_vector_t::Zero(), SCALAR alpha=SCALAR(1.0), SCALAR beta=SCALAR(2.0), SCALAR kappa=SCALAR(0.0), const ct::core::StateMatrix< STATE_DIM, SCALAR > &P0=ct::core::StateMatrix< STATE_DIM, SCALAR >::Identity()) | |
Constructor. More... | |
UnscentedKalmanFilter (std::shared_ptr< SystemModelBase< STATE_DIM, CONTROL_DIM, SCALAR >> f, std::shared_ptr< LinearMeasurementModel< OUTPUT_DIM, STATE_DIM, SCALAR >> h, const UnscentedKalmanFilterSettings< STATE_DIM, SCALAR > &ukf_settings) | |
Constructor from settings. More... | |
const state_vector_t & | predict (const control_vector_t &u, const ct::core::Time &dt, const ct::core::Time &t) override |
Estimator predict method. More... | |
const state_vector_t & | update (const output_vector_t &y, const ct::core::Time &dt, const ct::core::Time &t) override |
Estimator update method. More... | |
bool | computeSigmaPoints () |
Compute sigma points from current state and covariance estimates. More... | |
template<size_t SIZE> | |
bool | computeCovarianceFromSigmaPoints (const Eigen::Matrix< SCALAR, SIZE, 1 > &mean, const SigmaPoints< SIZE > &sigmaPoints, const Covariance< SIZE > &noiseCov, Covariance< SIZE > &cov) |
Estimate covariance from sigma points and noise covariance. More... | |
bool | computeKalmanGain (const ct::core::OutputVector< OUTPUT_DIM, SCALAR > &y, const SigmaPoints< OUTPUT_DIM > &sigmaMeasurementPoints, const Covariance< OUTPUT_DIM > &P_yy, Eigen::Matrix< SCALAR, STATE_DIM, OUTPUT_DIM > &K) |
Compute the Kalman Gain using sigma points.. More... | |
bool | updateStateCovariance (const Eigen::Matrix< SCALAR, STATE_DIM, OUTPUT_DIM > &K, const Covariance< OUTPUT_DIM > &P) |
Compute the Kalman Gain using sigma points.. More... | |
const state_vector_t | computeStatePrediction (const ct::core::ControlVector< CONTROL_DIM, SCALAR > &u, const ct::core::Time &dt, const ct::core::Time &t=0) |
Update state covariance from Kalman gain and sigma points. More... | |
ct::core::OutputVector< OUTPUT_DIM, SCALAR > | computeMeasurementPrediction (SigmaPoints< OUTPUT_DIM > &sigmaMeasurementPoints, const ct::core::Time &t=0) |
Predict the next measurement. More... | |
void | computeWeights () |
Compute weights of sigma points. More... | |
void | computeSigmaPointTransition (const ct::core::ControlVector< CONTROL_DIM, SCALAR > &u, const ct::core::Time &dt, const ct::core::Time &t) |
Propagate sigma points through the system dynamics. Using CTSystemModel here will not provide a desired effect since it disregards the control input u. More... | |
void | computeSigmaPointMeasurements (SigmaPoints< OUTPUT_DIM > &sigmaMeasurementPoints, const ct::core::Time &t=0) |
Predict measurements of sigma points. More... | |
template<size_t DIM> | |
state_vector_t | computePredictionFromSigmaPoints (const SigmaPoints< DIM > &sigmaPoints) |
Make a prediction based on sigma points. More... | |
template<size_t DIM> | |
auto | computePredictionFromSigmaPoints (const SigmaPoints< DIM > &sigmaPoints) -> state_vector_t |
Public Member Functions inherited from ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR > | |
EstimatorBase (std::shared_ptr< SystemModelBase< STATE_DIM, CONTROL_DIM, SCALAR >> f, std::shared_ptr< LinearMeasurementModel< OUTPUT_DIM, STATE_DIM, SCALAR >> h, const state_vector_t &x0=state_vector_t::Zero()) | |
Constructor. More... | |
EstimatorBase (const EstimatorBase &arg) | |
Copy constructor. More... | |
virtual | ~EstimatorBase ()=default |
void | setSystemModel (std::shared_ptr< SystemModelBase< STATE_DIM, CONTROL_DIM, SCALAR >> f) |
update the system model More... | |
void | setMeasurementModel (std::shared_ptr< LinearMeasurementModel< OUTPUT_DIM, STATE_DIM, SCALAR >> h) |
update the measurement model More... | |
const state_vector_t & | getEstimate () const |
Estimate getter. More... | |
void | setEstimate (const state_vector_t &x) |
Estimate setter. More... | |
Static Public Attributes | |
static constexpr size_t | SigmaPointCount = 2 * STATE_DIM + 1 |
Additional Inherited Members | |
Protected Attributes inherited from ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR > | |
std::shared_ptr< SystemModelBase< STATE_DIM, CONTROL_DIM, SCALAR > > | f_ |
System model for propagating the system. More... | |
std::shared_ptr< LinearMeasurementModel< OUTPUT_DIM, STATE_DIM, SCALAR > > | h_ |
Observation model used to calculate the output error. More... | |
state_vector_t | x_est_ |
State estimate. More... | |
Unscented Kalman Filter is a nonlinear estimator best suited for highly nonlinear systems. It combines the principles of EKF and particle filter. The downside is the computation complexity.
STATE_DIM |
using ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::Base = EstimatorBase<STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR> |
using ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::SigmaPoints = Eigen::Matrix<SCALAR, SIZE, SigmaPointCount> |
using ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::Covariance = Eigen::Matrix<SCALAR, SIZE, SIZE> |
using ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::CovarianceSquareRoot = Cholesky<Eigen::Matrix<SCALAR, SIZE, SIZE> > |
using ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::control_vector_t = ct::core::ControlVector<CONTROL_DIM, SCALAR> |
using ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::output_matrix_t = ct::core::OutputMatrix<OUTPUT_DIM, SCALAR> |
using ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::output_vector_t = ct::core::OutputVector<OUTPUT_DIM, SCALAR> |
using ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::state_matrix_t = ct::core::StateMatrix<STATE_DIM, SCALAR> |
using ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::state_vector_t = ct::core::StateVector<STATE_DIM, SCALAR> |
ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::UnscentedKalmanFilter | ( | std::shared_ptr< SystemModelBase< STATE_DIM, CONTROL_DIM, SCALAR >> | f, |
std::shared_ptr< LinearMeasurementModel< OUTPUT_DIM, STATE_DIM, SCALAR >> | h, | ||
const state_vector_t & | x0 = state_vector_t::Zero() , |
||
SCALAR | alpha = SCALAR(1.0) , |
||
SCALAR | beta = SCALAR(2.0) , |
||
SCALAR | kappa = SCALAR(0.0) , |
||
const ct::core::StateMatrix< STATE_DIM, SCALAR > & | P0 = ct::core::StateMatrix<STATE_DIM, SCALAR>::Identity() |
||
) |
Constructor.
ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::UnscentedKalmanFilter | ( | std::shared_ptr< SystemModelBase< STATE_DIM, CONTROL_DIM, SCALAR >> | f, |
std::shared_ptr< LinearMeasurementModel< OUTPUT_DIM, STATE_DIM, SCALAR >> | h, | ||
const UnscentedKalmanFilterSettings< STATE_DIM, SCALAR > & | ukf_settings | ||
) |
Constructor from settings.
|
overridevirtual |
Estimator predict method.
Implements ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >.
References ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::computeSigmaPoints(), ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::computeStatePrediction(), dt, ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::f_, t, u, and ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::x_est_.
|
overridevirtual |
Estimator update method.
Implements ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >.
References ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::computeKalmanGain(), ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::computeMeasurementPrediction(), ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::h_, t, ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::updateStateCovariance(), and ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::x_est_.
bool ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::computeSigmaPoints | ( | ) |
Compute sigma points from current state and covariance estimates.
References ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::x_est_.
Referenced by ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::predict().
bool ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::computeCovarianceFromSigmaPoints | ( | const Eigen::Matrix< SCALAR, SIZE, 1 > & | mean, |
const SigmaPoints< SIZE > & | sigmaPoints, | ||
const Covariance< SIZE > & | noiseCov, | ||
Covariance< SIZE > & | cov | ||
) |
Estimate covariance from sigma points and noise covariance.
bool ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::computeKalmanGain | ( | const ct::core::OutputVector< OUTPUT_DIM, SCALAR > & | y, |
const SigmaPoints< OUTPUT_DIM > & | sigmaMeasurementPoints, | ||
const Covariance< OUTPUT_DIM > & | P_yy, | ||
Eigen::Matrix< SCALAR, STATE_DIM, OUTPUT_DIM > & | K | ||
) |
Compute the Kalman Gain using sigma points..
References ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::x_est_.
Referenced by ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::update().
bool ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::updateStateCovariance | ( | const Eigen::Matrix< SCALAR, STATE_DIM, OUTPUT_DIM > & | K, |
const Covariance< OUTPUT_DIM > & | P | ||
) |
Compute the Kalman Gain using sigma points..
Referenced by ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::update().
auto ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::computeStatePrediction | ( | const ct::core::ControlVector< CONTROL_DIM, SCALAR > & | u, |
const ct::core::Time & | dt, | ||
const ct::core::Time & | t = 0 |
||
) |
Update state covariance from Kalman gain and sigma points.
References ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::computeSigmaPointTransition(), dt, t, and u.
Referenced by ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::predict().
ct::core::OutputVector< OUTPUT_DIM, SCALAR > ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::computeMeasurementPrediction | ( | SigmaPoints< OUTPUT_DIM > & | sigmaMeasurementPoints, |
const ct::core::Time & | t = 0 |
||
) |
Predict the next measurement.
Referenced by ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::update().
void ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::computeWeights | ( | ) |
Compute weights of sigma points.
References i, and ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::SigmaPointCount.
void ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::computeSigmaPointTransition | ( | const ct::core::ControlVector< CONTROL_DIM, SCALAR > & | u, |
const ct::core::Time & | dt, | ||
const ct::core::Time & | t | ||
) |
Propagate sigma points through the system dynamics. Using CTSystemModel here will not provide a desired effect since it disregards the control input u.
References dt, ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::f_, i, ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::SigmaPointCount, t, and u.
Referenced by ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::computeStatePrediction().
void ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::computeSigmaPointMeasurements | ( | SigmaPoints< OUTPUT_DIM > & | sigmaMeasurementPoints, |
const ct::core::Time & | t = 0 |
||
) |
Predict measurements of sigma points.
References ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::h_, i, ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::SigmaPointCount, and t.
Referenced by ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::computeMeasurementPrediction().
state_vector_t ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::computePredictionFromSigmaPoints | ( | const SigmaPoints< DIM > & | sigmaPoints | ) |
Make a prediction based on sigma points.
auto ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::computePredictionFromSigmaPoints | ( | const SigmaPoints< DIM > & | sigmaPoints | ) | -> state_vector_t |
|
static |
Referenced by ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::computeSigmaPointMeasurements(), ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::computeSigmaPointTransition(), and ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::computeWeights().