Estimator base.  
 More...
#include <EstimatorBase.h>
 | 
|   | 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 | 
|   | 
| virtual const state_vector_t &  | predict (const control_vector_t &u, const ct::core::Time &dt, const ct::core::Time &t)=0 | 
|   | Estimator predict method.  More...
  | 
|   | 
| virtual const state_vector_t &  | update (const output_vector_t &y, const ct::core::Time &dt, const ct::core::Time &t)=0 | 
|   | Estimator update method.  More...
  | 
|   | 
| 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...
  | 
|   | 
template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR = double>
class ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >
Estimator base. 
 
◆ control_vector_t
template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR  = double> 
      
 
 
◆ state_vector_t
template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR  = double> 
      
 
 
◆ state_matrix_t
template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR  = double> 
      
 
 
◆ output_vector_t
template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR  = double> 
      
 
 
◆ output_matrix_t
template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR  = double> 
      
 
 
◆ EstimatorBase() [1/2]
template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR  = double> 
 
 
◆ EstimatorBase() [2/2]
template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR  = double> 
 
Copy constructor. 
References dt, ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::predict(), t, u, ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::update(), and ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::~EstimatorBase().
 
 
◆ ~EstimatorBase()
template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR  = double> 
 
 
◆ predict()
template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR  = double> 
 
Estimator predict method. 
Implemented in ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >, ct::optcon::SteadyStateKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >, and ct::optcon::ExtendedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >.
Referenced by ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::EstimatorBase().
 
 
◆ update()
template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR  = double> 
 
Estimator update method. 
Implemented in ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >, ct::optcon::SteadyStateKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >, and ct::optcon::ExtendedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >.
Referenced by ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::EstimatorBase().
 
 
◆ setSystemModel()
template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR  = double> 
 
 
◆ setMeasurementModel()
template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR  = double> 
 
 
◆ getEstimate()
template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR  = double> 
 
 
◆ setEstimate()
template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR  = double> 
 
 
◆ f_
template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR  = double> 
 
System model for propagating the system. 
Referenced by ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::computeSigmaPointTransition(), ct::optcon::ExtendedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::predict(), ct::optcon::SteadyStateKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::predict(), ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::predict(), and ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::setSystemModel().
 
 
◆ h_
template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR  = double> 
 
Observation model used to calculate the output error. 
Referenced by ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::computeSigmaPointMeasurements(), ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::setMeasurementModel(), ct::optcon::ExtendedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::update(), ct::optcon::SteadyStateKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::update(), and ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::update().
 
 
◆ x_est_
template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR  = double> 
 
State estimate. 
Referenced by ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::computeKalmanGain(), ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::computeSigmaPoints(), ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::getEstimate(), ct::optcon::ExtendedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::predict(), ct::optcon::SteadyStateKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::predict(), ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::predict(), ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::setEstimate(), ct::optcon::ExtendedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::update(), ct::optcon::SteadyStateKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::update(), and ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::update().
 
 
The documentation for this class was generated from the following file:
- /home/gim2rng/ct_devel_ws/src/control-toolbox/ct_optcon/include/ct/optcon/filter/EstimatorBase.h