- 3.0.2 core module.
|
A general, non-linear dynamic system with a control input. More...
#include <ControlledSystem.h>
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, SCALAR > | getLastControlAction () |
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, SCALAR > | Base |
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, SCALAR > | controlAction_ |
Protected Attributes inherited from ct::core::System< STATE_DIM, SCALAR > | |
SYSTEM_TYPE | type_ |
type of system More... | |
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
where is the state, the control input and the time.
For implementing your own ControlledSystem, derive from this class.
We generally assume that the Controller is a state and time dependent function which allows any ControlledSystem to be re-written as a System of the form
which can be forward propagated in time with an Integrator.
STATE_DIM | dimension of state vector |
CONTROL_DIM | dimension of input vector |
SCALAR | scalar type |
typedef std::shared_ptr<ControlledSystem<STATE_DIM, CONTROL_DIM, SCALAR> > ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >::Ptr |
typedef Base::time_t ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >::time_t |
|
inline |
default constructor
type | system type |
|
inline |
constructor
controller | controller |
type | system type |
|
inline |
copy constructor
|
inlinevirtual |
destructor
|
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().
|
inline |
set a new controller
controller | new controller |
|
inline |
get the controller instance
controller | controller instance |
|
inline |
get the controller instace
|
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.
state | current state |
t | current time |
derivative | state derivative |
|
pure virtual |
|
inline |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef System<STATE_DIM, SCALAR> ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >::Base |
|
protected |
the controller instance
Referenced by ct::core::ControlledSystem< POS_DIM+VEL_DIM, CONTROL_DIM, SCALAR >::computeDynamics(), ct::core::ControlledSystem< POS_DIM+VEL_DIM, CONTROL_DIM, SCALAR >::ControlledSystem(), ct::core::DiscreteControlledSystem< STATE_DIM, CONTROL_DIM, double >::DiscreteControlledSystem(), ct::core::ControlledSystem< POS_DIM+VEL_DIM, CONTROL_DIM, SCALAR >::getController(), and ct::core::ControlledSystem< POS_DIM+VEL_DIM, CONTROL_DIM, SCALAR >::setController().
|
protected |