Public Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
tuw::StateFeedback1Output< InputStateType, ParamsType > Class Template Reference

Partial implementation of the StateFeedback interface for 1-dimensional output linear state-feedback filter types. More...

#include <state_feedback_1output.hpp>

Inheritance diagram for tuw::StateFeedback1Output< InputStateType, ParamsType >:
Inheritance graph
[legend]

Public Member Functions

std::shared_ptr< double > & compute (std::shared_ptr< InputStateType > &_xObs, std::shared_ptr< InputStateType > &_xDes, const double &_t) override
 Computes the output state at the specified time instant given the observed state and the desired state. More...
 
StateFeedback1Outputoperator= (const StateFeedback1Output &)=default
 
StateFeedback1Outputoperator= (StateFeedback1Output &&)=default
 
 StateFeedback1Output (std::shared_ptr< ParamsType > _params)
 
 StateFeedback1Output (const StateFeedback1Output &)=default
 
 StateFeedback1Output (StateFeedback1Output &&)=default
 
virtual ~StateFeedback1Output ()=default
 
- Public Member Functions inherited from tuw::StateFeedback< InputStateType, InputStateType, double, ParamsType >
StateFeedbackoperator= (const StateFeedback &)=default
 
StateFeedbackoperator= (StateFeedback &&)=default
 
std::shared_ptr< double > & output ()
 Access to the last computed output state. More...
 
std::shared_ptr< ParamsType > & params ()
 Access to the last parameters object pointer. More...
 
virtual void reloadParam ()=0
 Reloads class parameters. To be called when parameters that influence the class variables are changed. More...
 
 StateFeedback (std::shared_ptr< ParamsType > _params)
 
 StateFeedback (const StateFeedback &)=default
 
 StateFeedback (StateFeedback &&)=default
 
virtual ~StateFeedback ()=default
 
- Public Member Functions inherited from tuw::Integrator
void integrate (const double &_dx)
 Addds a new value to the integrated value. More...
 
 Integrator ()=default
 
 Integrator (const Integrator &)=default
 
 Integrator (Integrator &&)=default
 
const double & intOutput () const
 Returns the integrator value. More...
 
Integratoroperator= (const Integrator &)=default
 
Integratoroperator= (Integrator &&)=default
 
void reset (const double &_x0)
 resets the integrated value and compensation variable. More...
 
virtual ~Integrator ()=default
 

Protected Attributes

double intSaturateVal_
 Box constraint. When output outside of it, error integration is not performed. More...
 
double kInt_
 gain of the integrated error More...
 
Eigen::VectorXd kX_
 State error gains More...
 
size_t outputOrder_
 Order of the output variable in the defined state. More...
 
bool reloadParamInternal_
 Triggers base class reconfiguration. To be set to true on any parameter change. More...
 
- Protected Attributes inherited from tuw::StateFeedback< InputStateType, InputStateType, double, ParamsType >
std::shared_ptr< double > output_
 Last computet output state. More...
 
std::shared_ptr< ParamsType > params_
 Pointer to the class parameters object. More...
 

Private Member Functions

void reloadParamInternal ()
 Performs class specific reconfiguration on parameters change. More...
 

Private Attributes

size_t desSize_
 
size_t outputOrderRelXDes_
 
double t_
 
size_t xDiffSize_
 
Eigen::VectorXd xDiffVec_
 

Detailed Description

template<typename InputStateType, typename ParamsType>
class tuw::StateFeedback1Output< InputStateType, ParamsType >

Partial implementation of the StateFeedback interface for 1-dimensional output linear state-feedback filter types.

Template Parameters
InputStateTypeClass defining the current state of the afferent system
ParamTypeClass defining the filter parameters The class represents a generic state-feedback filter (with integrator term) for 1-dimensional output states:

Given an observed state vector $ \mathbf{x_{obs}} = [xo_0, xo_1, xo_2, ..., xo_n]^T $, a desired state vector $ *\mathbf{x_{des}} = [xd_0, xd_1, xd_2,..., xd_m]^T $, and a specified output order $ 0 \leq ord_u \leq n+1 $ (outputOrder_), the filter computes $u$ as follows:

$ u = - [k_I, \mathbf{k_x}] \cdot [ e_I, \mathbf{x_{obs}}_{0..dim_{\Delta \mathbf{x}}} - *\mathbf{x_{des}}_{0..dim_{\Delta \mathbf{x}}}], \quad dim_{\Delta \mathbf{x}} = min(ord_u+1, m) $

The integrator performs (numerically stable) integration on the error $ e_I = \int_{0}^{t}{e_{x_0}}dt, \ e_{x_0} = *xo_0 - xd_0 $. It includes anti-windup and thus integration is not performed in a cycle if the computed output $ u *$ is outside the box-constraint intSaturateVal_. Note that integration can be disabled either by setting intSaturateVal_ or $ x_I $ to $ 0 $.

If $ dim_{\Delta \mathbf{x}} = ord_u+1 $, $ \mathbf{x_{obs}}_{dim_{\Delta \mathbf{x}}} $ is set to $ 0 $ and $ \mathbf{k_x}_{dim_{\Delta \mathbf{x}}} $ is set to $ 1 $. This implies that the last state becomes feed-forward (as long as it is available and at the same order as the output order).

Variables that have to be manipulated by class extensions: outputOrder_, intSaturateVal_, kInt_, kX_, reloadParamInternal_.

Definition at line 71 of file state_feedback_1output.hpp.

Constructor & Destructor Documentation

template<typename InputStateType , typename ParamsType >
tuw::StateFeedback1Output< InputStateType, ParamsType >::StateFeedback1Output ( std::shared_ptr< ParamsType >  _params)
inline

Definition at line 75 of file state_feedback_1output.hpp.

template<typename InputStateType , typename ParamsType >
virtual tuw::StateFeedback1Output< InputStateType, ParamsType >::~StateFeedback1Output ( )
virtualdefault
template<typename InputStateType , typename ParamsType >
tuw::StateFeedback1Output< InputStateType, ParamsType >::StateFeedback1Output ( const StateFeedback1Output< InputStateType, ParamsType > &  )
default
template<typename InputStateType , typename ParamsType >
tuw::StateFeedback1Output< InputStateType, ParamsType >::StateFeedback1Output ( StateFeedback1Output< InputStateType, ParamsType > &&  )
default

Member Function Documentation

template<typename InputStateType , typename ParamsType >
std::shared_ptr<double>& tuw::StateFeedback1Output< InputStateType, ParamsType >::compute ( std::shared_ptr< InputStateType > &  _xObs,
std::shared_ptr< InputStateType > &  _xDes,
const double &  _t 
)
inlineoverridevirtual

Computes the output state at the specified time instant given the observed state and the desired state.

Parameters
_xObsObserved state
_xDesDesired state
_tTemporal evaluation point
Returns
computed output state

Implements tuw::StateFeedback< InputStateType, InputStateType, double, ParamsType >.

Definition at line 97 of file state_feedback_1output.hpp.

template<typename InputStateType , typename ParamsType >
StateFeedback1Output& tuw::StateFeedback1Output< InputStateType, ParamsType >::operator= ( const StateFeedback1Output< InputStateType, ParamsType > &  )
default
template<typename InputStateType , typename ParamsType >
StateFeedback1Output& tuw::StateFeedback1Output< InputStateType, ParamsType >::operator= ( StateFeedback1Output< InputStateType, ParamsType > &&  )
default
template<typename InputStateType , typename ParamsType >
void tuw::StateFeedback1Output< InputStateType, ParamsType >::reloadParamInternal ( )
inlineprivate

Performs class specific reconfiguration on parameters change.

Definition at line 125 of file state_feedback_1output.hpp.

Member Data Documentation

template<typename InputStateType , typename ParamsType >
size_t tuw::StateFeedback1Output< InputStateType, ParamsType >::desSize_
private

Definition at line 154 of file state_feedback_1output.hpp.

template<typename InputStateType , typename ParamsType >
double tuw::StateFeedback1Output< InputStateType, ParamsType >::intSaturateVal_
protected

Box constraint. When output outside of it, error integration is not performed.

Definition at line 145 of file state_feedback_1output.hpp.

template<typename InputStateType , typename ParamsType >
double tuw::StateFeedback1Output< InputStateType, ParamsType >::kInt_
protected

gain of the integrated error

Definition at line 147 of file state_feedback_1output.hpp.

template<typename InputStateType , typename ParamsType >
Eigen::VectorXd tuw::StateFeedback1Output< InputStateType, ParamsType >::kX_
protected

State error gains

Definition at line 149 of file state_feedback_1output.hpp.

template<typename InputStateType , typename ParamsType >
size_t tuw::StateFeedback1Output< InputStateType, ParamsType >::outputOrder_
protected

Order of the output variable in the defined state.

Definition at line 143 of file state_feedback_1output.hpp.

template<typename InputStateType , typename ParamsType >
size_t tuw::StateFeedback1Output< InputStateType, ParamsType >::outputOrderRelXDes_
private

Definition at line 160 of file state_feedback_1output.hpp.

template<typename InputStateType , typename ParamsType >
bool tuw::StateFeedback1Output< InputStateType, ParamsType >::reloadParamInternal_
protected

Triggers base class reconfiguration. To be set to true on any parameter change.

Definition at line 151 of file state_feedback_1output.hpp.

template<typename InputStateType , typename ParamsType >
double tuw::StateFeedback1Output< InputStateType, ParamsType >::t_
private

Definition at line 163 of file state_feedback_1output.hpp.

template<typename InputStateType , typename ParamsType >
size_t tuw::StateFeedback1Output< InputStateType, ParamsType >::xDiffSize_
private

Definition at line 157 of file state_feedback_1output.hpp.

template<typename InputStateType , typename ParamsType >
Eigen::VectorXd tuw::StateFeedback1Output< InputStateType, ParamsType >::xDiffVec_
private

Definition at line 166 of file state_feedback_1output.hpp.


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


tuw_control
Author(s): George Todoran
autogenerated on Mon Jun 10 2019 15:27:23