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

A constant state feedback controller. More...

#include <ConstantStateFeedbackController.h>

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

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW ConstantStateFeedbackController ()
 Default constructor. More...
 
 ConstantStateFeedbackController (const ControlVector< CONTROL_DIM, SCALAR > &uff, const StateVector< STATE_DIM, SCALAR > &x, const FeedbackMatrix< STATE_DIM, CONTROL_DIM, SCALAR > &K)
 Constructor. More...
 
 ConstantStateFeedbackController (const ConstantStateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR > &other)
 Copy constructor. More...
 
 ~ConstantStateFeedbackController ()
 Destructor. More...
 
ConstantStateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR > * clone () const override
 Clone operator. More...
 
void computeControl (const StateVector< STATE_DIM, SCALAR > &x, const SCALAR &t, ControlVector< CONTROL_DIM, SCALAR > &controlAction) override
 Computes current control. More...
 
void updateControlLaw (const ControlVector< CONTROL_DIM, SCALAR > &uff, const StateVector< STATE_DIM, SCALAR > &x, const FeedbackMatrix< STATE_DIM, CONTROL_DIM, SCALAR > &K=FeedbackMatrix< STATE_DIM, CONTROL_DIM, SCALAR >::Zero())
 update the control law with a new set of parameters 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 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...
 

Detailed Description

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

A constant state feedback controller.

Implements a state feedback controller which works on a constant setpoint, i.e. it features

  • one constant pure feedforward term
  • one constant state reference
  • one constant Feedback matrix

and takes the form

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

Constructor & Destructor Documentation

◆ ConstantStateFeedbackController() [1/3]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW ct::core::ConstantStateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::ConstantStateFeedbackController ( )
inline

Default constructor.

Sets the control signal to zero

◆ ConstantStateFeedbackController() [2/3]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
ct::core::ConstantStateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::ConstantStateFeedbackController ( const ControlVector< CONTROL_DIM, SCALAR > &  uff,
const StateVector< STATE_DIM, SCALAR > &  x,
const FeedbackMatrix< STATE_DIM, CONTROL_DIM, SCALAR > &  K 
)
inline

Constructor.

Initializes the control to a fixed value

Parameters
uThe fixed feedforward control signal
xThe fixed reference state
Kthe fixed state feedback gain

◆ ConstantStateFeedbackController() [3/3]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
ct::core::ConstantStateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::ConstantStateFeedbackController ( const ConstantStateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR > &  other)
inline

Copy constructor.

◆ ~ConstantStateFeedbackController()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
ct::core::ConstantStateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::~ConstantStateFeedbackController ( )
inline

Destructor.

Member Function Documentation

◆ clone()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
ConstantStateFeedbackController<STATE_DIM, CONTROL_DIM, SCALAR>* ct::core::ConstantStateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::clone ( ) const
inlineoverridevirtual

Clone operator.

Clones the controller. Used for cloning ControlledSystem's

Returns
pointer to cloned controller

Implements ct::core::Controller< STATE_DIM, CONTROL_DIM, SCALAR >.

◆ computeControl()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
void ct::core::ConstantStateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::computeControl ( const StateVector< STATE_DIM, SCALAR > &  x,
const SCALAR t,
ControlVector< CONTROL_DIM, SCALAR > &  controlAction 
)
inlineoverridevirtual

Computes current control.

Returns the fixed control signal. Therefore, the return value is invariant to the parameters.

Parameters
stateThe current state of the system (ignored)
tThe time of the system (ignored)
controlActionThe (fixed) control action

Implements ct::core::Controller< STATE_DIM, CONTROL_DIM, SCALAR >.

◆ updateControlLaw()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
void ct::core::ConstantStateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::updateControlLaw ( const ControlVector< CONTROL_DIM, SCALAR > &  uff,
const StateVector< STATE_DIM, SCALAR > &  x,
const FeedbackMatrix< STATE_DIM, CONTROL_DIM, SCALAR > &  K = FeedbackMatrix<STATE_DIM, CONTROL_DIM, SCALAR>::Zero() 
)
inline

update the control law with a new set of parameters

Parameters
uThe fixed feedforward control signal
xThe fixed reference state
Kthe fixed state feedback gain

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