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

A constant controller. More...

#include <ConstantController.h>

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

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW ConstantController ()
 Default constructor. More...
 
 ConstantController (ControlVector< CONTROL_DIM, SCALAR > &u)
 Constructor. More...
 
 ConstantController (const ConstantController< STATE_DIM, CONTROL_DIM, SCALAR > &other)
 Copy constructor. More...
 
virtual ~ConstantController ()
 Destructor. More...
 
ConstantController< STATE_DIM, CONTROL_DIM, SCALAR > * clone () const override
 Clone operator. More...
 
void computeControl (const StateVector< STATE_DIM, SCALAR > &state, const SCALAR &t, ControlVector< CONTROL_DIM, SCALAR > &controlAction) override
 Computes current control. More...
 
void computeControl (const StateVector< STATE_DIM, SCALAR > &state, const int n, ControlVector< CONTROL_DIM, SCALAR > &controlAction) override
 Equivalent method for discrete version. More...
 
void setControl (const ControlVector< CONTROL_DIM, SCALAR > &u)
 Sets the control signal. More...
 
const ControlVector< CONTROL_DIM, SCALAR > & getControl () const
 Get the fixed control signal. More...
 
virtual ControlMatrix< CONTROL_DIM, SCALARgetDerivativeU0 (const StateVector< STATE_DIM, SCALAR > &state, const SCALAR time) override
 Returns the the derivative of the control with respect to the initial control input u0. 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, 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...
 

Additional Inherited Members

- Public Types inherited from ct::core::DiscreteController< STATE_DIM, CONTROL_DIM, SCALAR >
typedef ControlVector< CONTROL_DIM, SCALARcontrol_vector_t
 
- Public Attributes inherited from ct::core::DiscreteController< STATE_DIM, CONTROL_DIM, SCALAR >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef StateVector< STATE_DIM, SCALARstate_vector_t
 

Detailed Description

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

A constant controller.

Implements a controller that is time and state invariant, i.e. fully constant. This class is useful to integrate a ControlledSystem forward subject to a constant control input.

Constructor & Destructor Documentation

◆ ConstantController() [1/3]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR >
ct::core::ConstantController< STATE_DIM, CONTROL_DIM, SCALAR >::ConstantController ( )

Default constructor.

Sets the control signal to zero

◆ ConstantController() [2/3]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR >
ct::core::ConstantController< STATE_DIM, CONTROL_DIM, SCALAR >::ConstantController ( ControlVector< CONTROL_DIM, SCALAR > &  u)

Constructor.

Initializes the control to a fixed value

Parameters
uThe fixed control signal

◆ ConstantController() [3/3]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR >
ct::core::ConstantController< STATE_DIM, CONTROL_DIM, SCALAR >::ConstantController ( const ConstantController< STATE_DIM, CONTROL_DIM, SCALAR > &  other)

Copy constructor.

◆ ~ConstantController()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR >
ct::core::ConstantController< STATE_DIM, CONTROL_DIM, SCALAR >::~ConstantController ( )
virtual

Destructor.

Member Function Documentation

◆ clone()

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

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() [1/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR >
void ct::core::ConstantController< STATE_DIM, CONTROL_DIM, SCALAR >::computeControl ( const StateVector< STATE_DIM, SCALAR > &  state,
const SCALAR t,
ControlVector< CONTROL_DIM, SCALAR > &  controlAction 
)
overridevirtual

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

Referenced by ct::core::ConstantController< STATE_DIM, CONTROL_DIM, SCALAR >::computeControl().

◆ computeControl() [2/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR >
void ct::core::ConstantController< STATE_DIM, CONTROL_DIM, SCALAR >::computeControl ( const StateVector< STATE_DIM, SCALAR > &  state,
const int  n,
ControlVector< CONTROL_DIM, SCALAR > &  controlAction 
)
override

Equivalent method for discrete version.

References ct::core::ConstantController< STATE_DIM, CONTROL_DIM, SCALAR >::computeControl().

◆ setControl()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR >
void ct::core::ConstantController< STATE_DIM, CONTROL_DIM, SCALAR >::setControl ( const ControlVector< CONTROL_DIM, SCALAR > &  u)

Sets the control signal.

Parameters
uThe fixed control signal

◆ getControl()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR >
const ControlVector< CONTROL_DIM, SCALAR > & ct::core::ConstantController< STATE_DIM, CONTROL_DIM, SCALAR >::getControl ( ) const

Get the fixed control signal.

Parameters
uThe control input to write the signal to.

◆ getDerivativeU0()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR >
ControlMatrix< CONTROL_DIM, SCALAR > ct::core::ConstantController< STATE_DIM, CONTROL_DIM, SCALAR >::getDerivativeU0 ( const StateVector< STATE_DIM, SCALAR > &  state,
const SCALAR  time 
)
overridevirtual

Returns the the derivative of the control with respect to the initial control input u0.

Parameters
[in]stateThe state at which the method will be evaluated
[in]timeThe time at which the method will be evaluated
Returns
The derivatives with respect to u0.

Reimplemented from ct::core::Controller< STATE_DIM, CONTROL_DIM, SCALAR >.


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