Go to the documentation of this file.
   25 #ifndef SRC_SYSTEMS_INCLUDE_CORBO_SYSTEMS_SYSTEM_DYNAMICS_INTERFACE_H_ 
   26 #define SRC_SYSTEMS_INCLUDE_CORBO_SYSTEMS_SYSTEM_DYNAMICS_INTERFACE_H_ 
   32 #ifdef MESSAGE_SUPPORT 
   33 #include <corbo-communication/messages/systems/system_dynamics.pb.h> 
   40 class FiniteDifferencesInterface;  
 
   66 class SystemDynamicsInterface
 
   69     using Ptr           = std::shared_ptr<SystemDynamicsInterface>;
 
  165     virtual void reset() {}
 
  167 #ifdef MESSAGE_SUPPORT 
  168     virtual void toMessage(messages::SystemDynamics& message) 
const;
 
  171     virtual void fromMessage(
const messages::SystemDynamics& message, std::stringstream* issues = 
nullptr);
 
  180 #define FACTORY_REGISTER_SYSTEM_DYNAMICS(type) FACTORY_REGISTER_OBJECT(type, SystemDynamicsInterface) 
  184 #endif  // SRC_SYSTEMS_INCLUDE_CORBO_SYSTEMS_SYSTEM_DYNAMICS_INTERFACE_H_ 
  
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.
virtual int getStateDimension() const =0
Return state dimension (x)
virtual bool isContinuousTime() const =0
Check if the system dynamics are defined in continuous-time.
virtual double getDeadTime() const
Return deadtime which might be taken into account by controllers/simulators if supported.
void setLinearizationMethod(std::shared_ptr< FiniteDifferencesInterface > lin_method)
Set linearization method in case getLinearA() or getLinearB() are not overriden.
virtual void getLinearA(const StateVector &x0, const ControlVector &u0, Eigen::MatrixXd &A) const
Return linear system matrix A (linearized system dynamics)
MatrixType B(b, *n, *nrhs, *ldb)
virtual void getLinearB(const StateVector &x0, const ControlVector &u0, Eigen::MatrixXd &B) const
Return linear control input matrix B (linearized system dynamics)
std::shared_ptr< FiniteDifferencesInterface > _linearization_method
virtual ~SystemDynamicsInterface()=default
Default destructor.
std::shared_ptr< SystemDynamicsInterface > Ptr
A matrix or vector expression mapping an existing expression.
virtual int getInputDimension() const =0
Return the plant input dimension (u)
virtual Ptr getInstance() const =0
Return a newly created shared instance of the implemented class.
Factory< SystemDynamicsInterface > SystemDynamicsFactory
SystemDynamicsInterface()
Default constructor.
virtual bool isLinear() const =0
Check if the system dynamics are linear.
MatrixType A(a, *n, *n, *lda)
Eigen::VectorXd StateVector
Eigen::VectorXd ControlVector
control_box_rst
Author(s): Christoph Rösmann 
autogenerated on Wed Mar 2 2022 00:06:33