- 3.0.2 core module.
ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR > Class Template Referenceabstract

A general, non-linear dynamic system with a control input. More...

#include <ControlledSystem.h>

Inheritance diagram for ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >:
ct::core::System< STATE_DIM, SCALAR > ct::core::LinearSystem< STATE_DIM, CONTROL_DIM, SCALAR > ct::core::SwitchedControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR > ct::core::SwitchedLinearSystem< STATE_DIM, CONTROL_DIM, SCALAR > ct::core::SystemLinearizer< STATE_DIM, CONTROL_DIM, SCALAR > ct::models::HyA::HyALinearizedForward ct::models::HyA::HyALinearizedReverse ct::models::HyQ::HyQBareModelLinearizedForward ct::models::HyQ::HyQBareModelLinearizedReverse ct::models::HyQ::HyQWithContactModelLinearizedForward ct::models::HyQ::HyQWithContactModelLinearizedReverse ct::models::InvertedPendulum::InvertedPendulumActDynLinearizedForward ct::models::QuadrotorLinear ct::optcon::example::DiehlSystemLinear ct::optcon::example::LinearizedSystem ct::optcon::example::LinearizedSystem ct::optcon::example::MIMOIntegratorLinear< state_dim, control_dim > ct::optcon::example::tpl::LinearOscillatorLinear< class > LinkedMasses

Public Types

typedef std::shared_ptr< ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR > > Ptr
 
typedef Base::time_t time_t
 
- Public Types inherited from ct::core::System< STATE_DIM, SCALAR >
typedef SCALAR time_t
 the type of the time variable More...
 

Public Member Functions

 ControlledSystem (const SYSTEM_TYPE &type=SYSTEM_TYPE::GENERAL)
 default constructor More...
 
 ControlledSystem (std::shared_ptr< ct::core::Controller< STATE_DIM, CONTROL_DIM, SCALAR >> controller, const SYSTEM_TYPE &type=SYSTEM_TYPE::GENERAL)
 constructor More...
 
 ControlledSystem (const ControlledSystem &arg)
 copy constructor More...
 
virtual ~ControlledSystem ()
 destructor More...
 
virtual ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR > * clone () const override=0
 deep copy More...
 
void setController (const std::shared_ptr< Controller< STATE_DIM, CONTROL_DIM, SCALAR >> &controller)
 set a new controller More...
 
void getController (std::shared_ptr< Controller< STATE_DIM, CONTROL_DIM, SCALAR >> &controller) const
 get the controller instance More...
 
std::shared_ptr< Controller< STATE_DIM, CONTROL_DIM, SCALAR > > getController ()
 get the controller instace More...
 
virtual void computeDynamics (const StateVector< STATE_DIM, SCALAR > &state, const time_t &t, StateVector< STATE_DIM, SCALAR > &derivative) override
 compute the dynamics of the system More...
 
virtual void computeControlledDynamics (const StateVector< STATE_DIM, SCALAR > &state, const time_t &t, const ControlVector< CONTROL_DIM, SCALAR > &control, StateVector< STATE_DIM, SCALAR > &derivative)=0
 
ControlVector< CONTROL_DIM, SCALARgetLastControlAction ()
 
- Public Member Functions inherited from ct::core::System< STATE_DIM, SCALAR >
 System (const SYSTEM_TYPE &type=SYSTEM_TYPE::GENERAL)
 default constructor More...
 
 System (const System &other)
 copy constructor More...
 
virtual ~System ()
 destructor More...
 
virtual void computeDynamics (const StateVector< STATE_DIM, SCALAR > &state, const time_t &t, StateVector< STATE_DIM, SCALAR > &derivative)=0
 computes the system dynamics More...
 
SYSTEM_TYPE getType () const
 get the type of system More...
 
virtual bool isSymplectic () const
 Determines if the system is in symplectic form. More...
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef System< STATE_DIM, SCALARBase
 
- Public Attributes inherited from ct::core::System< STATE_DIM, SCALAR >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef SCALAR S
 the scalar type More...
 

Protected Attributes

std::shared_ptr< Controller< STATE_DIM, CONTROL_DIM, SCALAR > > controller_
 the controller instance More...
 
ControlVector< CONTROL_DIM, SCALARcontrolAction_
 
- Protected Attributes inherited from ct::core::System< STATE_DIM, SCALAR >
SYSTEM_TYPE type_
 type of system More...
 

Detailed Description

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

A general, non-linear dynamic system with a control input.

This describes a general, non-linear dynamic system described by an Ordinary Differential Equation (ODE) of the following form

\[ \dot{x} = f(x,u,t) \]

where $ x(t) $ is the state, $ u(t) $ the control input and $ t $ the time.

For implementing your own ControlledSystem, derive from this class.

We generally assume that the Controller is a state and time dependent function $ u = g(x,t) $ which allows any ControlledSystem to be re-written as a System of the form

\[ \dot{x} = f(x(t),u(x,t),t) = g(x,t) \]

which can be forward propagated in time with an Integrator.

Template Parameters
STATE_DIMdimension of state vector
CONTROL_DIMdimension of input vector
SCALARscalar type

Member Typedef Documentation

◆ Ptr

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
typedef std::shared_ptr<ControlledSystem<STATE_DIM, CONTROL_DIM, SCALAR> > ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >::Ptr

◆ time_t

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
typedef Base::time_t ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >::time_t

Constructor & Destructor Documentation

◆ ControlledSystem() [1/3]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >::ControlledSystem ( const SYSTEM_TYPE type = SYSTEM_TYPE::GENERAL)
inline

default constructor

Parameters
typesystem type

◆ ControlledSystem() [2/3]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >::ControlledSystem ( std::shared_ptr< ct::core::Controller< STATE_DIM, CONTROL_DIM, SCALAR >>  controller,
const SYSTEM_TYPE type = SYSTEM_TYPE::GENERAL 
)
inline

constructor

Parameters
controllercontroller
typesystem type

◆ ControlledSystem() [3/3]

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

copy constructor

◆ ~ControlledSystem()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
virtual ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >::~ControlledSystem ( )
inlinevirtual

destructor

Member Function Documentation

◆ clone()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
virtual ControlledSystem<STATE_DIM, CONTROL_DIM, SCALAR>* ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >::clone ( ) const
overridepure virtual

deep copy

Reimplemented from ct::core::System< STATE_DIM, SCALAR >.

Implemented in ct::core::tpl::SecondOrderSystem< SCALAR >, ct::core::SystemLinearizer< STATE_DIM, CONTROL_DIM, SCALAR >, ct::core::SwitchedControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >, ct::core::SwitchedLinearSystem< STATE_DIM, CONTROL_DIM, SCALAR >, ct::core::SymplecticSystem< POS_DIM, VEL_DIM, CONTROL_DIM, SCALAR >, ct::core::SymplecticSystem< 1, 1, 1, SCALAR >, LinearizedOscillator, ct::core::LTISystem< STATE_DIM, CONTROL_DIM >, ct::core::LinearSystem< STATE_DIM, CONTROL_DIM, SCALAR >, ct::core::LinearSystem< STATE_DIM, CONTROL_DIM >, ct::core::LinearSystem< 2, 1, double >, ct::core::LinearSystem< 2, 1 >, ct::core::tpl::TestSymplecticSystem< SCALAR >, ct::core::tpl::TestNonlinearSystem< SCALAR >, ct::core::generated::TestNonlinearSystemLinearized, TestOscillator, ct::optcon::example::DiehlSystemLinear, ct::optcon::example::LinearizedSystem, ct::optcon::example::LinearizedSystem, ct::optcon::example::tpl::LinearOscillatorLinear< class >, LinkedMasses, ct::optcon::example::MIMOIntegratorLinear< state_dim, control_dim >, ct::optcon::example::SpringLoadedMass, ct::optcon::example::SpringLoadedMassLinear, ct::core::tpl::TestLinearSystem< class >, ct::models::HyA::HyALinearizedForward, ct::models::HyA::HyALinearizedReverse, ct::models::HyQ::HyQBareModelLinearizedForward, ct::models::HyQ::HyQBareModelLinearizedReverse, ct::models::HyQ::HyQWithContactModelLinearizedForward, ct::models::HyQ::HyQWithContactModelLinearizedReverse, ct::models::InvertedPendulum::InvertedPendulumActDynLinearizedForward, and ct::models::QuadrotorLinear.

Referenced by ct::core::ControlledSystem< POS_DIM+VEL_DIM, CONTROL_DIM, SCALAR >::~ControlledSystem().

◆ setController()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
void ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >::setController ( const std::shared_ptr< Controller< STATE_DIM, CONTROL_DIM, SCALAR >> &  controller)
inline

set a new controller

Parameters
controllernew controller

◆ getController() [1/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
void ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >::getController ( std::shared_ptr< Controller< STATE_DIM, CONTROL_DIM, SCALAR >> &  controller) const
inline

get the controller instance

Todo:
remove this function (duplicate of getController() below)
Parameters
controllercontroller instance

◆ getController() [2/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
std::shared_ptr<Controller<STATE_DIM, CONTROL_DIM, SCALAR> > ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >::getController ( )
inline

get the controller instace

Returns
controller instance

◆ computeDynamics()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
virtual void ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >::computeDynamics ( const StateVector< STATE_DIM, SCALAR > &  state,
const time_t t,
StateVector< STATE_DIM, SCALAR > &  derivative 
)
inlineoverridevirtual

compute the dynamics of the system

Compute the state derivative by evaluating the system dynamics for a given state. This calls the controller first and then calls computeControlledDynamics() with the current state and the resulting control signal.

Note
Generally, this function does not need to be overloaded. Better overload computeControlledDynamics().
Parameters
statecurrent state
tcurrent time
derivativestate derivative

◆ computeControlledDynamics()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
virtual void ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >::computeControlledDynamics ( const StateVector< STATE_DIM, SCALAR > &  state,
const time_t t,
const ControlVector< CONTROL_DIM, SCALAR > &  control,
StateVector< STATE_DIM, SCALAR > &  derivative 
)
pure virtual

◆ getLastControlAction()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
ControlVector<CONTROL_DIM, SCALAR> ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >::getLastControlAction ( )
inline

Member Data Documentation

◆ Base

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef System<STATE_DIM, SCALAR> ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >::Base

◆ controller_

◆ controlAction_


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