#include <nonlinear_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 double & | getDampingCoefficient () const |
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... | |
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... | |
void | setDampingCoefficient (double a) |
VanDerPolOscillator () | |
Default constructor. More... | |
![]() | |
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 | |
double | _a = 1 |
Additional Inherited Members | |
![]() | |
using | ControlVector = Eigen::VectorXd |
using | Ptr = std::shared_ptr< SystemDynamicsInterface > |
using | StateVector = Eigen::VectorXd |
Definition at line 32 of file nonlinear_benchmark_systems.h.
|
inline |
Default constructor.
Definition at line 36 of file nonlinear_benchmark_systems.h.
|
inlineoverridevirtual |
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 ![]() ![]() |
Implements corbo::SystemDynamicsInterface.
Definition at line 52 of file nonlinear_benchmark_systems.h.
|
inline |
Definition at line 63 of file nonlinear_benchmark_systems.h.
|
inlineoverridevirtual |
Return the plant input dimension (u)
Implements corbo::SystemDynamicsInterface.
Definition at line 47 of file nonlinear_benchmark_systems.h.
|
inlineoverridevirtual |
Return a newly created shared instance of the implemented class.
Implements corbo::SystemDynamicsInterface.
Definition at line 39 of file nonlinear_benchmark_systems.h.
|
inlineoverridevirtual |
Return state dimension (x)
Implements corbo::SystemDynamicsInterface.
Definition at line 49 of file nonlinear_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
.
Implements corbo::SystemDynamicsInterface.
Definition at line 42 of file nonlinear_benchmark_systems.h.
|
inlineoverridevirtual |
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.
Implements corbo::SystemDynamicsInterface.
Definition at line 44 of file nonlinear_benchmark_systems.h.
|
inline |
Definition at line 64 of file nonlinear_benchmark_systems.h.
|
private |
Definition at line 84 of file nonlinear_benchmark_systems.h.