- 3.0.2 core module.
ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR > Class Template Reference

A linear state feedback controller. More...

#include <StateFeedbackController.h>

Inheritance diagram for ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >:
ct::core::Controller< STATE_DIM, CONTROL_DIM, SCALAR > ct::core::DiscreteController< STATE_DIM, CONTROL_DIM, SCALAR >

Public Types

typedef DiscreteController< STATE_DIM, CONTROL_DIM, SCALARDiscreteBase
 
typedef DiscreteBase::state_vector_t state_vector_t
 
typedef DiscreteBase::control_vector_t control_vector_t
 
typedef StateVectorArray< STATE_DIM, SCALARstate_vector_array_t
 
typedef ControlVectorArray< CONTROL_DIM, SCALARcontrol_vector_array_t
 
typedef FeedbackArray< STATE_DIM, CONTROL_DIM, SCALARfeedback_array_t
 
- Public Types inherited from ct::core::DiscreteController< STATE_DIM, CONTROL_DIM, SCALAR >
typedef ControlVector< CONTROL_DIM, SCALARcontrol_vector_t
 

Public Member Functions

 StateFeedbackController ()
 default constructor More...
 
 StateFeedbackController (const StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR > &other)
 copy constructor More...
 
 StateFeedbackController (const state_vector_array_t &x_ref, const control_vector_array_t &uff, const feedback_array_t &K, const SCALAR deltaT, const SCALAR t0=0.0, const InterpolationType &intType=ZOH)
 constructor More...
 
virtual ~StateFeedbackController ()
 destructor More...
 
StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR > * clone () const override
 deep cloning More...
 
virtual void computeControl (const state_vector_t &state, const SCALAR &t, control_vector_t &controlAction) override
 computes the control action in the continuous case More...
 
virtual void computeControl (const state_vector_t &state, const int n, control_vector_t &controlAction) override
 computes the control action in the discrete case More...
 
void update (const DiscreteArray< state_vector_t > &x_ref, const DiscreteArray< control_vector_t > &uff, const DiscreteArray< FeedbackMatrix< STATE_DIM, CONTROL_DIM, SCALAR >> &K, const tpl::TimeArray< SCALAR > &t)
 updates the controller More...
 
const DiscreteArray< state_vector_t > & x_ref () const
 get reference state vector array (without timings) More...
 
const DiscreteArray< control_vector_t > & uff () const
 get feedforward array (without timings) More...
 
const DiscreteArray< FeedbackMatrix< STATE_DIM, CONTROL_DIM, SCALAR > > & K () const
 get feedback array (without timings) More...
 
const tpl::TimeArray< SCALAR > & time () const
 get time array More...
 
StateTrajectory< STATE_DIM, SCALAR > & getReferenceStateTrajectory ()
 get a reference to the feedforward trajectory More...
 
const StateTrajectory< STATE_DIM, SCALAR > & getReferenceStateTrajectory () const
 get a reference to the feedforward trajectory More...
 
ControlTrajectory< CONTROL_DIM, SCALAR > & getFeedforwardTrajectory ()
 get a reference to the feedforward trajectory More...
 
const ControlTrajectory< CONTROL_DIM, SCALAR > & getFeedforwardTrajectory () const
 get a reference to the feedforward trajectory More...
 
FeedbackTrajectory< STATE_DIM, CONTROL_DIM, SCALAR > & getFeedbackTrajectory ()
 get a reference to the feedback trajectory More...
 
const FeedbackTrajectory< STATE_DIM, CONTROL_DIM, SCALAR > & getFeedbackTrajectory () const
 get a reference to the feedback trajectory More...
 
void extractControlTrajectory (const StateTrajectory< STATE_DIM, SCALAR > &x_traj, ControlTrajectory< CONTROL_DIM, SCALAR > &u_traj)
 extracts a physically meaningful control trajectory from the given state-feedback law and a reference state trajectory More...
 
- Public Member Functions inherited from ct::core::Controller< STATE_DIM, CONTROL_DIM, SCALAR >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Controller ()
 Default constructor. More...
 
 Controller (const Controller &other)
 Copy constructor. More...
 
virtual ~Controller ()
 Destructor. More...
 
virtual void computeControl (const StateVector< STATE_DIM, SCALAR > &state, const SCALAR &t, ControlVector< CONTROL_DIM, SCALAR > &controlAction)=0
 Compute control signal. More...
 
virtual ControlMatrix< CONTROL_DIM, SCALARgetDerivativeU0 (const StateVector< STATE_DIM, SCALAR > &state, const SCALAR time)
 Returns the the derivative of the control with respect to the initial control input u0. More...
 
virtual ControlMatrix< CONTROL_DIM, SCALARgetDerivativeUf (const StateVector< STATE_DIM, SCALAR > &state, const SCALAR time)
 Returns the the derivative of the control with respect to the final control input uF. More...
 
- Public Member Functions inherited from ct::core::DiscreteController< STATE_DIM, CONTROL_DIM, SCALAR >
 DiscreteController ()
 Default constructor. More...
 
 DiscreteController (const DiscreteController &other)
 Copy constructor. More...
 
virtual ~DiscreteController ()
 Destructor. More...
 
virtual void computeControl (const state_vector_t &state, const int n, control_vector_t &controlAction)=0
 Compute control signal. More...
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef Controller< STATE_DIM, CONTROL_DIM, SCALARContinuousBase
 
- Public Attributes inherited from ct::core::DiscreteController< STATE_DIM, CONTROL_DIM, SCALAR >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef StateVector< STATE_DIM, SCALARstate_vector_t
 

Protected Attributes

StateTrajectory< STATE_DIM, SCALARx_ref_
 
ControlTrajectory< CONTROL_DIM, SCALARuff_
 state reference trajectory More...
 
FeedbackTrajectory< STATE_DIM, CONTROL_DIM, SCALARK_
 feedforward control trajectory More...
 

Detailed Description

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
class ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >

A linear state feedback controller.

A general, time-varying linear state feedback controller with feedforward action of type. It supports both continuous and discrete time.

\[ u(x,t) = u_{ff}(t) + K(t) (x - x_{ref}) \]

or

\[ u(x,n) = u_{ff}[n] + K[n] (x - x_{ref}) \]

where $ u_{ff} $ is a time varying feedforward and $ K(t) $ a time-varying linear feedback controller.

Template Parameters
STATE_DIMstate vector size
CONTROL_DIMcontrol vector size
SCALARprimitive type

Member Typedef Documentation

◆ DiscreteBase

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
typedef DiscreteController<STATE_DIM, CONTROL_DIM, SCALAR> ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::DiscreteBase

◆ state_vector_t

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
typedef DiscreteBase::state_vector_t ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::state_vector_t

◆ control_vector_t

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
typedef DiscreteBase::control_vector_t ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::control_vector_t

◆ state_vector_array_t

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
typedef StateVectorArray<STATE_DIM, SCALAR> ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::state_vector_array_t

◆ control_vector_array_t

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
typedef ControlVectorArray<CONTROL_DIM, SCALAR> ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::control_vector_array_t

◆ feedback_array_t

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
typedef FeedbackArray<STATE_DIM, CONTROL_DIM, SCALAR> ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::feedback_array_t

Constructor & Destructor Documentation

◆ StateFeedbackController() [1/3]

◆ StateFeedbackController() [2/3]

◆ StateFeedbackController() [3/3]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::StateFeedbackController ( const state_vector_array_t x_ref,
const control_vector_array_t uff,
const feedback_array_t K,
const SCALAR  deltaT,
const SCALAR  t0 = 0.0,
const InterpolationType intType = ZOH 
)

constructor

Constructs a state feedback controller. The feedforward and feedback parts get interpolated where required.

Note: in the discrete setting, the initial time step is always assumed to be n=0

Parameters
ufffeedforward controller.
Kfeedback controller.
deltaTdiscretization step
t0initial time.
intTypeinterpolation type

◆ ~StateFeedbackController()

Member Function Documentation

◆ clone()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR >
StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR > * ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::clone ( ) const
overridevirtual

◆ computeControl() [1/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR >
void ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::computeControl ( const state_vector_t state,
const SCALAR t,
control_vector_t controlAction 
)
overridevirtual

computes the control action in the continuous case

evaluates the controller using interpolation where required using interpolation

Parameters
statecurrent state
tcurrent time
controlActionresulting control action

References ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::K_, ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::uff_, and ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::x_ref_.

Referenced by ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::~StateFeedbackController().

◆ computeControl() [2/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR >
void ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::computeControl ( const state_vector_t state,
const int  n,
control_vector_t controlAction 
)
overridevirtual

computes the control action in the discrete case

Evaluate the given controller for a given state and time index returns the computed control action.

Parameters
statecurrent state of the system
ncurrent time index of the system
controlActionthe corresponding control action

References ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::K_, n, ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::uff_, and ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::x_ref_.

◆ update()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR >
void ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::update ( const DiscreteArray< state_vector_t > &  x_ref,
const DiscreteArray< control_vector_t > &  uff,
const DiscreteArray< FeedbackMatrix< STATE_DIM, CONTROL_DIM, SCALAR >> &  K,
const tpl::TimeArray< SCALAR > &  t 
)

◆ x_ref()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR >
const DiscreteArray< typename StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::state_vector_t > & ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::x_ref ( ) const

◆ uff()

◆ K()

◆ time()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR >
const tpl::TimeArray< SCALAR > & ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::time ( ) const

◆ getReferenceStateTrajectory() [1/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR >
StateTrajectory< STATE_DIM, SCALAR > & ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::getReferenceStateTrajectory ( )

◆ getReferenceStateTrajectory() [2/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR >
const StateTrajectory< STATE_DIM, SCALAR > & ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::getReferenceStateTrajectory ( ) const

get a reference to the feedforward trajectory

References ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::x_ref_.

◆ getFeedforwardTrajectory() [1/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR >
ControlTrajectory< CONTROL_DIM, SCALAR > & ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::getFeedforwardTrajectory ( )

◆ getFeedforwardTrajectory() [2/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR >
const ControlTrajectory< CONTROL_DIM, SCALAR > & ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::getFeedforwardTrajectory ( ) const

get a reference to the feedforward trajectory

References ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::uff_.

◆ getFeedbackTrajectory() [1/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR >
FeedbackTrajectory< STATE_DIM, CONTROL_DIM, SCALAR > & ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::getFeedbackTrajectory ( )

◆ getFeedbackTrajectory() [2/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR >
const FeedbackTrajectory< STATE_DIM, CONTROL_DIM, SCALAR > & ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::getFeedbackTrajectory ( ) const

get a reference to the feedback trajectory

References ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::K_.

◆ extractControlTrajectory()

Member Data Documentation

◆ ContinuousBase

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef Controller<STATE_DIM, CONTROL_DIM, SCALAR> ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::ContinuousBase

◆ x_ref_

◆ uff_

◆ K_


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