Interface class for system dynamic equations. More...
#include <system_dynamics_interface.h>
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 |
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.
or in discrete-time, e.g.
. Subclasses must overload isContinuousTime() appropriately.
Definition at line 66 of file system_dynamics_interface.h.
using corbo::SystemDynamicsInterface::ControlVector = Eigen::VectorXd |
Definition at line 71 of file system_dynamics_interface.h.
using corbo::SystemDynamicsInterface::Ptr = std::shared_ptr<SystemDynamicsInterface> |
Definition at line 69 of file system_dynamics_interface.h.
using corbo::SystemDynamicsInterface::StateVector = Eigen::VectorXd |
Definition at line 70 of file system_dynamics_interface.h.
corbo::SystemDynamicsInterface::SystemDynamicsInterface | ( | ) |
Default constructor.
Definition at line 31 of file system_dynamics_interface.cpp.
|
virtualdefault |
Default destructor.
|
pure virtual |
Evaluate the system dynamics equation.
Implement this method to specify the actual system dynamics equation (continuous-time) or
(discrete-time).
[in] | x | State vector x [getStateDimension() x 1] |
[in] | u | Control input vector u [getInputDimension() x 1] |
[out] | f | Resulting function value ![]() ![]() |
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.
|
inlinevirtual |
Return deadtime which might be taken into account by controllers/simulators if supported.
Definition at line 107 of file system_dynamics_interface.h.
|
pure virtual |
Return the plant input dimension (u)
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.
|
pure virtual |
Return a newly created shared instance of the implemented class.
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.
|
virtual |
Return linear system matrix A (linearized system dynamics)
Linearizes the system dynamics equation (cont. case) specified with dynamics() using finite differences (refer to setLinearizationMethod()). The linearizes system dynamics at x=x0 and u=u0 are defined as:
And for the discrete-time case:
. This method returns matrix . For matrix
refer to getLinearB().
[in] | x0 | State at which the system dynamics should be linearized [getStateDimension() x 1] |
[in] | u0 | Control input at which the dynamics should be linearized [getInputDimension() x 1] |
[out] | A | Linear system matrix A [getStateDimension() x getStateDimension()] (must be preallocated) |
Definition at line 33 of file system_dynamics_interface.cpp.
|
virtual |
Return linear control input matrix B (linearized system dynamics)
Refer to the description of method getLinearA().
[in] | x0 | State at which the system dynamics should be linearized [getStateDimension() x 1] |
[in] | u0 | Control input at which the dynamics should be linearized [getInputDimension() x 1] |
[out] | B | Linear input matrix B [getStateDimension() x getInputDimension()] (must be preallocated) |
Definition at line 47 of file system_dynamics_interface.cpp.
|
pure virtual |
Return state dimension (x)
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.
|
pure virtual |
Check if the system dynamics are defined in continuous-time.
Continous-time equations are defined as and discrete-time equations as
.
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.
|
pure virtual |
Check if the system dynamics are linear.
Linear system can be written in the form (continuous-time) or
(discrete-time). Consequently, getLinearA() and getLinearB() are independet of x0 and u0.
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.
|
inlinevirtual |
Definition at line 165 of file system_dynamics_interface.h.
void corbo::SystemDynamicsInterface::setLinearizationMethod | ( | std::shared_ptr< FiniteDifferencesInterface > | lin_method | ) |
Set linearization method in case getLinearA() or getLinearB() are not overriden.
[in] | lin_method | shared instance of a FiniteDifferencesInterface implementation |
Definition at line 61 of file system_dynamics_interface.cpp.
|
private |
Definition at line 176 of file system_dynamics_interface.h.
|
private |
Definition at line 175 of file system_dynamics_interface.h.