System dynamics for a series of integrators (continuous-time) More...
#include <linear_benchmark_systems.h>

| Public Member Functions | |
| void | dynamics (const Eigen::Ref< const StateVector > &x, const Eigen::Ref< const ControlVector > &u, Eigen::Ref< StateVector > f) const override | 
| Evaluate the system dynamics equation.  More... | |
| const int & | getDimension () const | 
| Get current integrator chain dimension / order of the system.  More... | |
| int | getInputDimension () const override | 
| Return the plant input dimension (u)  More... | |
| Ptr | getInstance () const override | 
| Return a newly created shared instance of the implemented class.  More... | |
| int | getStateDimension () const override | 
| Return state dimension (x)  More... | |
| const double & | getTimeConstant () const | 
| Get time constant T of the integrator.  More... | |
| bool | isContinuousTime () const override | 
| Check if the system dynamics are defined in continuous-time.  More... | |
| bool | isLinear () const override | 
| Check if the system dynamics are linear.  More... | |
| SerialIntegratorSystem () | |
| Default constructor (do not forget to set the dimension)  More... | |
| SerialIntegratorSystem (int dimension) | |
| Construct ingerator system with given order/dimension.  More... | |
| void | setDimension (int dim) | 
| Set integrator dimension (p >= 1)  More... | |
| void | setTimeConstant (double time_constant) | 
| Set Time constant T of the integrator.  More... | |
|  Public Member Functions inherited from corbo::SystemDynamicsInterface | |
| virtual double | getDeadTime () const | 
| Return deadtime which might be taken into account by controllers/simulators if supported.  More... | |
| virtual void | getLinearA (const StateVector &x0, const ControlVector &u0, Eigen::MatrixXd &A) const | 
| Return linear system matrix A (linearized system dynamics)  More... | |
| virtual void | getLinearB (const StateVector &x0, const ControlVector &u0, Eigen::MatrixXd &B) const | 
| Return linear control input matrix B (linearized system dynamics)  More... | |
| virtual void | reset () | 
| void | setLinearizationMethod (std::shared_ptr< FiniteDifferencesInterface > lin_method) | 
| Set linearization method in case getLinearA() or getLinearB() are not overriden.  More... | |
| SystemDynamicsInterface () | |
| Default constructor.  More... | |
| virtual | ~SystemDynamicsInterface ()=default | 
| Default destructor.  More... | |
| Private Attributes | |
| int | _dimension = 1 | 
| double | _time_constant = 1.0 | 
| Additional Inherited Members | |
|  Public Types inherited from corbo::SystemDynamicsInterface | |
| using | ControlVector = Eigen::VectorXd | 
| using | Ptr = std::shared_ptr< SystemDynamicsInterface > | 
| using | StateVector = Eigen::VectorXd | 
System dynamics for a series of integrators (continuous-time)
An continuous-time integrator chain of order  is defiend as:
 is defiend as: 
![\[ T x^{(p)} = u \]](form_284.png) 
 in which superscript  defines the p-th derivative of x w.r.t. time.
 defines the p-th derivative of x w.r.t. time.  denotes a time constant.
 denotes a time constant.
Definition at line 72 of file linear_benchmark_systems.h.
| 
 | inline | 
Default constructor (do not forget to set the dimension)
Definition at line 98 of file linear_benchmark_systems.h.
| 
 | inlineexplicit | 
Construct ingerator system with given order/dimension.
Definition at line 100 of file linear_benchmark_systems.h.
| 
 | inlineoverridevirtual | 
Evaluate the system dynamics equation.
Implement this method to specify the actual system dynamics equation  (continuous-time) or
 (continuous-time) or  (discrete-time).
 (discrete-time).
| [in] | x | State vector x [getStateDimension() x 1] | 
| [in] | u | Control input vector u [getInputDimension() x 1] | 
| [out] | f | Resulting function value  respectively  (f must be preallocated with dimension [getStateDimension() x 1]) | 
Implements corbo::SystemDynamicsInterface.
Definition at line 116 of file linear_benchmark_systems.h.
| 
 | inline | 
Get current integrator chain dimension / order of the system.
Definition at line 131 of file linear_benchmark_systems.h.
| 
 | inlineoverridevirtual | 
Return the plant input dimension (u)
Implements corbo::SystemDynamicsInterface.
Definition at line 111 of file linear_benchmark_systems.h.
| 
 | inlineoverridevirtual | 
Return a newly created shared instance of the implemented class.
Implements corbo::SystemDynamicsInterface.
Definition at line 103 of file linear_benchmark_systems.h.
| 
 | inlineoverridevirtual | 
Return state dimension (x)
Implements corbo::SystemDynamicsInterface.
Definition at line 113 of file linear_benchmark_systems.h.
| 
 | inline | 
Get time constant T of the integrator.
Definition at line 135 of file linear_benchmark_systems.h.
| 
 | inlineoverridevirtual | 
Check if the system dynamics are defined in continuous-time.
Continous-time equations are defined as  and discrete-time equations as
 and discrete-time equations as  .
. 
Implements corbo::SystemDynamicsInterface.
Definition at line 106 of file linear_benchmark_systems.h.
| 
 | inlineoverridevirtual | 
Check if the system dynamics are linear.
Linear system can be written in the form  (continuous-time) or
 (continuous-time) or  (discrete-time). Consequently, getLinearA() and getLinearB() are independet of x0 and u0.
 (discrete-time). Consequently, getLinearA() and getLinearB() are independet of x0 and u0. 
Implements corbo::SystemDynamicsInterface.
Definition at line 108 of file linear_benchmark_systems.h.
| 
 | inline | 
Set integrator dimension (p >= 1)
Definition at line 133 of file linear_benchmark_systems.h.
| 
 | inline | 
Set Time constant T of the integrator.
Definition at line 137 of file linear_benchmark_systems.h.
| 
 | private | 
Definition at line 159 of file linear_benchmark_systems.h.
| 
 | private | 
Definition at line 160 of file linear_benchmark_systems.h.