system_dynamics_interface.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement
4  *
5  * Copyright (c) 2020,
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
7  * All rights reserved.
8  *
9  * This program is free software: you can redistribute it and/or modify
10  * it under the terms of the GNU General Public License as published by
11  * the Free Software Foundation, either version 3 of the License, or
12  * (at your option) any later version.
13  *
14  * This program is distributed in the hope that it will be useful,
15  * but WITHOUT ANY WARRANTY; without even the implied warranty of
16  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
17  * GNU General Public License for more details.
18  *
19  * You should have received a copy of the GNU General Public License
20  * along with this program. If not, see <https://www.gnu.org/licenses/>.
21  *
22  * Authors: Christoph Rösmann
23  *********************************************************************/
24 
25 #ifndef SRC_SYSTEMS_INCLUDE_CORBO_SYSTEMS_SYSTEM_DYNAMICS_INTERFACE_H_
26 #define SRC_SYSTEMS_INCLUDE_CORBO_SYSTEMS_SYSTEM_DYNAMICS_INTERFACE_H_
27 
28 #include <corbo-core/factory.h>
29 #include <corbo-core/time.h>
30 #include <corbo-core/types.h>
31 
32 #ifdef MESSAGE_SUPPORT
33 #include <corbo-communication/messages/systems/system_dynamics.pb.h>
34 #endif
35 
36 #include <memory>
37 
38 namespace corbo {
39 
40 class FiniteDifferencesInterface; // forward declaration
41 
66 class SystemDynamicsInterface
67 {
68  public:
69  using Ptr = std::shared_ptr<SystemDynamicsInterface>;
70  using StateVector = Eigen::VectorXd;
71  using ControlVector = Eigen::VectorXd;
72 
75 
77  virtual ~SystemDynamicsInterface() = default;
78 
80  virtual Ptr getInstance() const = 0;
81 
89  virtual bool isContinuousTime() const = 0;
90 
100  virtual bool isLinear() const = 0;
101 
103  virtual int getInputDimension() const = 0;
105  virtual int getStateDimension() const = 0;
107  virtual double getDeadTime() const { return _deadtime; }
108 
122 
144  virtual void getLinearA(const StateVector& x0, const ControlVector& u0, Eigen::MatrixXd& A) const;
145 
157  virtual void getLinearB(const StateVector& x0, const ControlVector& u0, Eigen::MatrixXd& B) const;
158 
163  void setLinearizationMethod(std::shared_ptr<FiniteDifferencesInterface> lin_method);
164 
165  virtual void reset() {}
166 
167 #ifdef MESSAGE_SUPPORT
168  virtual void toMessage(messages::SystemDynamics& message) const;
171  virtual void fromMessage(const messages::SystemDynamics& message, std::stringstream* issues = nullptr);
172 #endif
173 
174  private:
175  std::shared_ptr<FiniteDifferencesInterface> _linearization_method;
176  double _deadtime = 0.0;
177 };
178 
179 using SystemDynamicsFactory = Factory<SystemDynamicsInterface>;
180 #define FACTORY_REGISTER_SYSTEM_DYNAMICS(type) FACTORY_REGISTER_OBJECT(type, SystemDynamicsInterface)
181 
182 } // namespace corbo
183 
184 #endif // SRC_SYSTEMS_INCLUDE_CORBO_SYSTEMS_SYSTEM_DYNAMICS_INTERFACE_H_
corbo::SystemDynamicsInterface::dynamics
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.
corbo::SystemDynamicsInterface::getStateDimension
virtual int getStateDimension() const =0
Return state dimension (x)
corbo::SystemDynamicsInterface::isContinuousTime
virtual bool isContinuousTime() const =0
Check if the system dynamics are defined in continuous-time.
corbo::SystemDynamicsInterface::getDeadTime
virtual double getDeadTime() const
Return deadtime which might be taken into account by controllers/simulators if supported.
Definition: system_dynamics_interface.h:129
factory.h
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::SystemDynamicsInterface::_deadtime
double _deadtime
Definition: system_dynamics_interface.h:198
corbo::SystemDynamicsInterface::setLinearizationMethod
void setLinearizationMethod(std::shared_ptr< FiniteDifferencesInterface > lin_method)
Set linearization method in case getLinearA() or getLinearB() are not overriden.
Definition: system_dynamics_interface.cpp:83
corbo::SystemDynamicsInterface::getLinearA
virtual void getLinearA(const StateVector &x0, const ControlVector &u0, Eigen::MatrixXd &A) const
Return linear system matrix A (linearized system dynamics)
Definition: system_dynamics_interface.cpp:55
B
MatrixType B(b, *n, *nrhs, *ldb)
corbo::SystemDynamicsInterface::getLinearB
virtual void getLinearB(const StateVector &x0, const ControlVector &u0, Eigen::MatrixXd &B) const
Return linear control input matrix B (linearized system dynamics)
Definition: system_dynamics_interface.cpp:69
corbo::SystemDynamicsInterface::_linearization_method
std::shared_ptr< FiniteDifferencesInterface > _linearization_method
Definition: system_dynamics_interface.h:197
corbo::SystemDynamicsInterface::~SystemDynamicsInterface
virtual ~SystemDynamicsInterface()=default
Default destructor.
time.h
x
Scalar * x
Definition: level1_cplx_impl.h:89
corbo::SystemDynamicsInterface::Ptr
std::shared_ptr< SystemDynamicsInterface > Ptr
Definition: system_dynamics_interface.h:91
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
corbo::SystemDynamicsInterface::getInputDimension
virtual int getInputDimension() const =0
Return the plant input dimension (u)
types.h
corbo::SystemDynamicsInterface::getInstance
virtual Ptr getInstance() const =0
Return a newly created shared instance of the implemented class.
corbo::SystemDynamicsFactory
Factory< SystemDynamicsInterface > SystemDynamicsFactory
Definition: system_dynamics_interface.h:201
corbo::SystemDynamicsInterface::SystemDynamicsInterface
SystemDynamicsInterface()
Default constructor.
Definition: system_dynamics_interface.cpp:53
corbo::SystemDynamicsInterface::isLinear
virtual bool isLinear() const =0
Check if the system dynamics are linear.
A
MatrixType A(a, *n, *n, *lda)
corbo::SystemDynamicsInterface::StateVector
Eigen::VectorXd StateVector
Definition: system_dynamics_interface.h:92
corbo::SystemDynamicsInterface::reset
virtual void reset()
Definition: system_dynamics_interface.h:187
corbo::SystemDynamicsInterface::ControlVector
Eigen::VectorXd ControlVector
Definition: system_dynamics_interface.h:93


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:06:33