- 3.0.2 optimal control module.
|
Steady State Kalman Filter is a time invariant linear estimator. It starts with the same update rule as the standard Kalman Filter, but instead of propagating the covariance and estimate through time, it assumes convergence reducing the problem to solving an Algebraic Ricatti Equation. More...
#include <SteadyStateKalmanFilter.h>
Public Types | |
using | Base = EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR > |
using | control_vector_t = ct::core::ControlVector< CONTROL_DIM, SCALAR > |
using | output_matrix_t = ct::core::OutputMatrix< OUTPUT_DIM, SCALAR > |
using | output_vector_t = ct::core::OutputVector< OUTPUT_DIM, SCALAR > |
using | state_matrix_t = ct::core::StateMatrix< STATE_DIM, SCALAR > |
using | state_vector_t = ct::core::StateVector< STATE_DIM, SCALAR > |
Public Types inherited from ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR > | |
using | control_vector_t = ct::core::ControlVector< CONTROL_DIM, SCALAR > |
using | state_vector_t = ct::core::StateVector< STATE_DIM, SCALAR > |
using | state_matrix_t = ct::core::StateMatrix< STATE_DIM, SCALAR > |
using | output_vector_t = ct::core::OutputVector< OUTPUT_DIM, SCALAR > |
using | output_matrix_t = ct::core::OutputMatrix< OUTPUT_DIM, SCALAR > |
Public Member Functions | |
SteadyStateKalmanFilter (std::shared_ptr< SystemModelBase< STATE_DIM, CONTROL_DIM, SCALAR >> f, std::shared_ptr< LinearMeasurementModel< OUTPUT_DIM, STATE_DIM, SCALAR >> h, const state_matrix_t &Q, const output_matrix_t &R, const state_vector_t &x0=state_vector_t::Zero(), size_t maxDAREIterations=1000) | |
Constructor. More... | |
SteadyStateKalmanFilter (std::shared_ptr< SystemModelBase< STATE_DIM, CONTROL_DIM, SCALAR >> f, std::shared_ptr< LinearMeasurementModel< OUTPUT_DIM, STATE_DIM, SCALAR >> h, const SteadyStateKalmanFilterSettings< STATE_DIM, SCALAR > &sskf_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... | |
void | setMaxDAREIterations (size_t maxDAREIterations) |
Limit number of iterations of the DARE solver. More... | |
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... | |
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... | |
Steady State Kalman Filter is a time invariant linear estimator. It starts with the same update rule as the standard Kalman Filter, but instead of propagating the covariance and estimate through time, it assumes convergence reducing the problem to solving an Algebraic Ricatti Equation.
using ct::optcon::SteadyStateKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::Base = EstimatorBase<STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR> |
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::SteadyStateKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::SteadyStateKalmanFilter | ( | std::shared_ptr< SystemModelBase< STATE_DIM, CONTROL_DIM, SCALAR >> | f, |
std::shared_ptr< LinearMeasurementModel< OUTPUT_DIM, STATE_DIM, SCALAR >> | h, | ||
const state_matrix_t & | Q, | ||
const output_matrix_t & | R, | ||
const state_vector_t & | x0 = state_vector_t::Zero() , |
||
size_t | maxDAREIterations = 1000 |
||
) |
Constructor.
ct::optcon::SteadyStateKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::SteadyStateKalmanFilter | ( | std::shared_ptr< SystemModelBase< STATE_DIM, CONTROL_DIM, SCALAR >> | f, |
std::shared_ptr< LinearMeasurementModel< OUTPUT_DIM, STATE_DIM, SCALAR >> | h, | ||
const SteadyStateKalmanFilterSettings< STATE_DIM, SCALAR > & | sskf_settings | ||
) |
Constructor from settings.
|
overridevirtual |
Estimator predict method.
Implements ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >.
References 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::DARE< STATE_DIM, CONTROL_DIM, SCALAR >::computeSteadyStateRiccatiMatrix(), ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::h_, t, and ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::x_est_.
void ct::optcon::SteadyStateKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::setMaxDAREIterations | ( | size_t | maxDAREIterations | ) |
Limit number of iterations of the DARE solver.