Public Types | Public Member Functions | Private Attributes | List of all members
corbo::SystemDynamicsInterface Class Referenceabstract

Interface class for system dynamic equations. More...

#include <system_dynamics_interface.h>

Inheritance diagram for corbo::SystemDynamicsInterface:
Inheritance graph
[legend]

Public Types

using ControlVector = Eigen::VectorXd
 
using Ptr = std::shared_ptr< SystemDynamicsInterface >
 
using StateVector = Eigen::VectorXd
 

Public Member Functions

virtual void dynamics (const Eigen::Ref< const StateVector > &x, const Eigen::Ref< const ControlVector > &u, Eigen::Ref< StateVector > f) const =0
 Evaluate the system dynamics equation. More...
 
virtual double getDeadTime () const
 Return deadtime which might be taken into account by controllers/simulators if supported. More...
 
virtual int getInputDimension () const =0
 Return the plant input dimension (u) More...
 
virtual Ptr getInstance () const =0
 Return a newly created shared instance of the implemented class. 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 int getStateDimension () const =0
 Return state dimension (x) More...
 
virtual bool isContinuousTime () const =0
 Check if the system dynamics are defined in continuous-time. More...
 
virtual bool isLinear () const =0
 Check if the system dynamics are linear. 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

double _deadtime = 0.0
 
std::shared_ptr< FiniteDifferencesInterface_linearization_method
 

Detailed Description

Interface class for system dynamic equations.

This class specifies methods that are required to be implemented by specific subclasses in order to allow their general utilization in a variety of control tasks.

System dynamics can be either defined in continuous-time, e.g.

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

or in discrete-time, e.g.

\[ x_{k+1} = f(x_k, u_k) \]

. Subclasses must overload isContinuousTime() appropriately.

Remarks
This interface is provided with factory support (SystemDynamicsFactory).
See also
SystemOutputInterface PlantInterface
Author
Christoph Rösmann (chris.nosp@m.toph.nosp@m..roes.nosp@m.mann.nosp@m.@tu-d.nosp@m.ortm.nosp@m.und.d.nosp@m.e)

Definition at line 66 of file system_dynamics_interface.h.

Member Typedef Documentation

◆ ControlVector

Definition at line 71 of file system_dynamics_interface.h.

◆ Ptr

Definition at line 69 of file system_dynamics_interface.h.

◆ StateVector

Definition at line 70 of file system_dynamics_interface.h.

Constructor & Destructor Documentation

◆ SystemDynamicsInterface()

corbo::SystemDynamicsInterface::SystemDynamicsInterface ( )

Default constructor.

Definition at line 31 of file system_dynamics_interface.cpp.

◆ ~SystemDynamicsInterface()

virtual corbo::SystemDynamicsInterface::~SystemDynamicsInterface ( )
virtualdefault

Default destructor.

Member Function Documentation

◆ dynamics()

virtual void corbo::SystemDynamicsInterface::dynamics ( const Eigen::Ref< const StateVector > &  x,
const Eigen::Ref< const ControlVector > &  u,
Eigen::Ref< StateVector f 
) const
pure virtual

Evaluate the system dynamics equation.

Implement this method to specify the actual system dynamics equation $ \dot{x} = f(x,u) $ (continuous-time) or $ x_{k+1} = f(x_k, u_k) $ (discrete-time).

Parameters
[in]xState vector x [getStateDimension() x 1]
[in]uControl input vector u [getInputDimension() x 1]
[out]fResulting function value $ \dot{x} $ respectively $ x_{k+1} $ (f must be preallocated with dimension [getStateDimension() x 1])

Implemented in corbo::ArtsteinsCircle, corbo::ToyExample, corbo::CartPole, corbo::DoubleIntegratorDiscreteTime, corbo::MasslessPendulum, corbo::SimplePendulum, corbo::LinearStateSpaceModel, corbo::FreeSpaceRocket, corbo::ParallelIntegratorSystem, corbo::DuffingOscillator, corbo::SerialIntegratorSystem, and corbo::VanDerPolOscillator.

◆ getDeadTime()

virtual double corbo::SystemDynamicsInterface::getDeadTime ( ) const
inlinevirtual

Return deadtime which might be taken into account by controllers/simulators if supported.

Definition at line 107 of file system_dynamics_interface.h.

◆ getInputDimension()

virtual int corbo::SystemDynamicsInterface::getInputDimension ( ) const
pure virtual

◆ getInstance()

virtual Ptr corbo::SystemDynamicsInterface::getInstance ( ) const
pure virtual

◆ getLinearA()

void corbo::SystemDynamicsInterface::getLinearA ( const StateVector x0,
const ControlVector u0,
Eigen::MatrixXd &  A 
) const
virtual

Return linear system matrix A (linearized system dynamics)

Linearizes the system dynamics equation $ \dot{x} = f(x,u) $ (cont. case) specified with dynamics() using finite differences (refer to setLinearizationMethod()). The linearizes system dynamics at x=x0 and u=u0 are defined as:

\[ \dot{x} = A x + B u \]

And for the discrete-time case:

\[ x_{k+1} = A x_k + B u_k \]

. This method returns matrix $ A $. For matrix $ B $ refer to getLinearB().

Remarks
This method might be overriden in order to specify analytically derived matrices.
Parameters
[in]x0State at which the system dynamics should be linearized [getStateDimension() x 1]
[in]u0Control input at which the dynamics should be linearized [getInputDimension() x 1]
[out]ALinear system matrix A [getStateDimension() x getStateDimension()] (must be preallocated)

Definition at line 33 of file system_dynamics_interface.cpp.

◆ getLinearB()

void corbo::SystemDynamicsInterface::getLinearB ( const StateVector x0,
const ControlVector u0,
Eigen::MatrixXd &  B 
) const
virtual

Return linear control input matrix B (linearized system dynamics)

Refer to the description of method getLinearA().

Remarks
This method might be overriden in order to specify analytically derived matrices.
Parameters
[in]x0State at which the system dynamics should be linearized [getStateDimension() x 1]
[in]u0Control input at which the dynamics should be linearized [getInputDimension() x 1]
[out]BLinear input matrix B [getStateDimension() x getInputDimension()] (must be preallocated)

Definition at line 47 of file system_dynamics_interface.cpp.

◆ getStateDimension()

virtual int corbo::SystemDynamicsInterface::getStateDimension ( ) const
pure virtual

◆ isContinuousTime()

virtual bool corbo::SystemDynamicsInterface::isContinuousTime ( ) const
pure virtual

Check if the system dynamics are defined in continuous-time.

Continous-time equations are defined as $ \dot{x} = f(x,u) $ and discrete-time equations as $ x_{k+1} = f(x_k,u_k) $.

Returns
true if the system is specified in continuous time, false otherwise.

Implemented in corbo::ArtsteinsCircle, corbo::ToyExample, corbo::CartPole, corbo::DoubleIntegratorDiscreteTime, corbo::MasslessPendulum, corbo::SimplePendulum, corbo::LinearStateSpaceModel, corbo::FreeSpaceRocket, corbo::ParallelIntegratorSystem, corbo::DuffingOscillator, corbo::SerialIntegratorSystem, and corbo::VanDerPolOscillator.

◆ isLinear()

virtual bool corbo::SystemDynamicsInterface::isLinear ( ) const
pure virtual

Check if the system dynamics are linear.

Linear system can be written in the form $ \dot{x} = Ax + Bu $ (continuous-time) or $ x_{k+1} = A x_k + B u_k $ (discrete-time). Consequently, getLinearA() and getLinearB() are independet of x0 and u0.

Returns
true if the system behavior is linear, false otherwise.

Implemented in corbo::ArtsteinsCircle, corbo::ToyExample, corbo::CartPole, corbo::DoubleIntegratorDiscreteTime, corbo::MasslessPendulum, corbo::SimplePendulum, corbo::LinearStateSpaceModel, corbo::FreeSpaceRocket, corbo::ParallelIntegratorSystem, corbo::DuffingOscillator, corbo::SerialIntegratorSystem, and corbo::VanDerPolOscillator.

◆ reset()

virtual void corbo::SystemDynamicsInterface::reset ( )
inlinevirtual

Definition at line 165 of file system_dynamics_interface.h.

◆ setLinearizationMethod()

void corbo::SystemDynamicsInterface::setLinearizationMethod ( std::shared_ptr< FiniteDifferencesInterface lin_method)

Set linearization method in case getLinearA() or getLinearB() are not overriden.

Parameters
[in]lin_methodshared instance of a FiniteDifferencesInterface implementation

Definition at line 61 of file system_dynamics_interface.cpp.

Member Data Documentation

◆ _deadtime

double corbo::SystemDynamicsInterface::_deadtime = 0.0
private

Definition at line 176 of file system_dynamics_interface.h.

◆ _linearization_method

std::shared_ptr<FiniteDifferencesInterface> corbo::SystemDynamicsInterface::_linearization_method
private

Definition at line 175 of file system_dynamics_interface.h.


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


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Mon Feb 28 2022 22:08:03