- 3.0.2 optimal control module.
ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR > Class Template Referenceabstract

Estimator base. More...

#include <EstimatorBase.h>

Inheritance diagram for ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >:
ct::optcon::ExtendedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR > ct::optcon::SteadyStateKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR > ct::optcon::UnscentedKalmanFilter< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >

Public Types

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

 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_tpredict (const control_vector_t &u, const ct::core::Time &dt, const ct::core::Time &t)=0
 Estimator predict method. More...
 
virtual const state_vector_tupdate (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_tgetEstimate () const
 Estimate getter. More...
 
void setEstimate (const state_vector_t &x)
 Estimate setter. More...
 

Protected Attributes

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...
 

Detailed Description

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.

Member Typedef Documentation

◆ control_vector_t

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR = double>
using ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::control_vector_t = ct::core::ControlVector<CONTROL_DIM, SCALAR>

◆ state_vector_t

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR = double>
using ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::state_vector_t = ct::core::StateVector<STATE_DIM, SCALAR>

◆ state_matrix_t

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR = double>
using ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::state_matrix_t = ct::core::StateMatrix<STATE_DIM, SCALAR>

◆ output_vector_t

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR = double>
using ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::output_vector_t = ct::core::OutputVector<OUTPUT_DIM, SCALAR>

◆ output_matrix_t

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR = double>
using ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::output_matrix_t = ct::core::OutputMatrix<OUTPUT_DIM, SCALAR>

Constructor & Destructor Documentation

◆ EstimatorBase() [1/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR = double>
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() 
)
inline

Constructor.

◆ EstimatorBase() [2/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR = double>
ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::EstimatorBase ( const EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR > &  arg)
inline

◆ ~EstimatorBase()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR = double>
virtual ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::~EstimatorBase ( )
virtualdefault

Member Function Documentation

◆ predict()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR = double>
virtual const state_vector_t& ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::predict ( const control_vector_t u,
const ct::core::Time dt,
const ct::core::Time t 
)
pure virtual

◆ update()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR = double>
virtual const state_vector_t& ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::update ( const output_vector_t y,
const ct::core::Time dt,
const ct::core::Time t 
)
pure virtual

◆ setSystemModel()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR = double>
void ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::setSystemModel ( std::shared_ptr< SystemModelBase< STATE_DIM, CONTROL_DIM, SCALAR >>  f)
inline

◆ setMeasurementModel()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR = double>
void ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::setMeasurementModel ( std::shared_ptr< LinearMeasurementModel< OUTPUT_DIM, STATE_DIM, SCALAR >>  h)
inline

◆ getEstimate()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR = double>
const state_vector_t& ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::getEstimate ( ) const
inline

◆ setEstimate()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t OUTPUT_DIM, typename SCALAR = double>
void ct::optcon::EstimatorBase< STATE_DIM, CONTROL_DIM, OUTPUT_DIM, SCALAR >::setEstimate ( const state_vector_t x)
inline

Member Data Documentation

◆ f_

◆ h_

◆ x_est_


The documentation for this class was generated from the following file: