Public Member Functions | Private Attributes | List of all members
corbo::LinearStateSpaceModel Class Reference

#include <linear_benchmark_systems.h>

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

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...
 
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...
 
 LinearStateSpaceModel ()
 Default constructor (do not forget to set the dimension) More...
 
void setParameters (const Eigen::Ref< const Eigen::MatrixXd > &A, const Eigen::Ref< const Eigen::MatrixXd > &B)
 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

Eigen::MatrixXd _A = Eigen::MatrixXd::Zero(1, 1)
 
Eigen::MatrixXd _B = Eigen::MatrixXd::Zero(1, 1)
 

Additional Inherited Members

- Public Types inherited from corbo::SystemDynamicsInterface
using ControlVector = Eigen::VectorXd
 
using Ptr = std::shared_ptr< SystemDynamicsInterface >
 
using StateVector = Eigen::VectorXd
 

Detailed Description

Definition at line 186 of file linear_benchmark_systems.h.

Constructor & Destructor Documentation

◆ LinearStateSpaceModel()

corbo::LinearStateSpaceModel::LinearStateSpaceModel ( )
inline

Default constructor (do not forget to set the dimension)

Definition at line 190 of file linear_benchmark_systems.h.

Member Function Documentation

◆ dynamics()

void corbo::LinearStateSpaceModel::dynamics ( const Eigen::Ref< const StateVector > &  x,
const Eigen::Ref< const ControlVector > &  u,
Eigen::Ref< StateVector f 
) const
inlineoverridevirtual

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])

Implements corbo::SystemDynamicsInterface.

Definition at line 206 of file linear_benchmark_systems.h.

◆ getInputDimension()

int corbo::LinearStateSpaceModel::getInputDimension ( ) const
inlineoverridevirtual

Return the plant input dimension (u)

Implements corbo::SystemDynamicsInterface.

Definition at line 201 of file linear_benchmark_systems.h.

◆ getInstance()

Ptr corbo::LinearStateSpaceModel::getInstance ( ) const
inlineoverridevirtual

Return a newly created shared instance of the implemented class.

Implements corbo::SystemDynamicsInterface.

Definition at line 193 of file linear_benchmark_systems.h.

◆ getStateDimension()

int corbo::LinearStateSpaceModel::getStateDimension ( ) const
inlineoverridevirtual

Return state dimension (x)

Implements corbo::SystemDynamicsInterface.

Definition at line 203 of file linear_benchmark_systems.h.

◆ isContinuousTime()

bool corbo::LinearStateSpaceModel::isContinuousTime ( ) const
inlineoverridevirtual

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.

Implements corbo::SystemDynamicsInterface.

Definition at line 196 of file linear_benchmark_systems.h.

◆ isLinear()

bool corbo::LinearStateSpaceModel::isLinear ( ) const
inlineoverridevirtual

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.

Implements corbo::SystemDynamicsInterface.

Definition at line 198 of file linear_benchmark_systems.h.

◆ setParameters()

void corbo::LinearStateSpaceModel::setParameters ( const Eigen::Ref< const Eigen::MatrixXd > &  A,
const Eigen::Ref< const Eigen::MatrixXd > &  B 
)
inline

Set Time constant T of the integrator.

Definition at line 218 of file linear_benchmark_systems.h.

Member Data Documentation

◆ _A

Eigen::MatrixXd corbo::LinearStateSpaceModel::_A = Eigen::MatrixXd::Zero(1, 1)
private

Definition at line 277 of file linear_benchmark_systems.h.

◆ _B

Eigen::MatrixXd corbo::LinearStateSpaceModel::_B = Eigen::MatrixXd::Zero(1, 1)
private

Definition at line 278 of file linear_benchmark_systems.h.


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


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