output_function_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_OUTPUT_FUNCTION_INTERFACE_H_
26 #define SRC_SYSTEMS_INCLUDE_CORBO_SYSTEMS_OUTPUT_FUNCTION_INTERFACE_H_
27 
28 #include <corbo-core/factory.h>
29 #include <corbo-core/types.h>
30 
31 #ifdef MESSAGE_SUPPORT
32 #include <corbo-communication/messages/systems/output_functions.pb.h>
33 #endif
34 
35 #include <memory>
36 
37 namespace corbo {
38 
62 class SystemOutputInterface
63 {
64  public:
65  using Ptr = std::shared_ptr<SystemOutputInterface>;
66 
67  using StateVector = Eigen::VectorXd;
68  using OutputVector = Eigen::VectorXd;
69 
71  virtual ~SystemOutputInterface() = default;
72 
74  virtual int getOutputDimension() const = 0;
75 
77  virtual Ptr getInstance() const = 0;
78 
89  virtual void output(const StateVector& x, OutputVector& y) = 0;
90 
91  virtual void reset() {}
92 
93 #ifdef MESSAGE_SUPPORT
94  virtual void toMessage(corbo::messages::OutputFunction& message) const {}
97  virtual void fromMessage(const corbo::messages::OutputFunction& message, std::stringstream* issues = nullptr) {}
98 #endif
99 };
100 
101 using OutputFunctionFactory = Factory<SystemOutputInterface>;
102 #define FACTORY_REGISTER_OUTPUT_FUNCTION(type) FACTORY_REGISTER_OBJECT(type, SystemOutputInterface)
103 
115 class FullStateSystemOutput : public SystemOutputInterface
116 {
117  public:
118  // implements interface method
119  Ptr getInstance() const override { return std::make_shared<FullStateSystemOutput>(); }
120 
121  // implements interface method
122  int getOutputDimension() const override { return property::INHERITED; }
123  // implements interface method
124  void output(const StateVector& x, OutputVector& y) override { y = x; }
125 
126 #ifdef MESSAGE_SUPPORT
127  // implements interface method
128  void toMessage(corbo::messages::OutputFunction& message) const override { message.mutable_full_state_system_output(); }
129 #endif
130 };
131 FACTORY_REGISTER_OUTPUT_FUNCTION(FullStateSystemOutput)
132 
133 
145 {
146  public:
147  // implements interface method
148  Ptr getInstance() const override { return std::make_shared<FirstStateSystemOutput>(); }
149  // implements interface method
150  int getOutputDimension() const override { return 1; }
151  // implements interface method
152  void output(const StateVector& x, OutputVector& y) override { y[0] = x[0]; }
153 #ifdef MESSAGE_SUPPORT
154  // implements interface method
155  void toMessage(corbo::messages::OutputFunction& message) const override { message.mutable_first_state_system_output(); }
156 #endif
157 };
158 FACTORY_REGISTER_OUTPUT_FUNCTION(FirstStateSystemOutput)
159 
160 
171 class LastStateSystemOutput : public SystemOutputInterface
172 {
173  public:
174  // implements interface method
175  Ptr getInstance() const override { return std::make_shared<LastStateSystemOutput>(); }
176  // implements interface method
177  int getOutputDimension() const override { return 1; }
178  // implements interface method
179  void output(const StateVector& x, OutputVector& y) override { y[0] = x.tail(1)[0]; }
180 #ifdef MESSAGE_SUPPORT
181  // implements interface method
182  void toMessage(corbo::messages::OutputFunction& message) const override { message.mutable_last_state_system_output(); }
183 #endif
184 };
185 FACTORY_REGISTER_OUTPUT_FUNCTION(LastStateSystemOutput)
186 
187 
202 {
203  public:
204  // implements interface method
205  Ptr getInstance() const override { return std::make_shared<LastStateSystemOutput>(); }
206  // implements interface method
207  int getOutputDimension() const override { return 1; }
208  // implements interface method
209  void output(const StateVector& x, OutputVector& y) override { y.noalias() = _mat_c * x; }
210 #ifdef MESSAGE_SUPPORT
211  // implements interface method
212  void toMessage(corbo::messages::OutputFunction& message) const override { message.mutable_last_state_system_output(); }
213 #endif
214 
216  const Eigen::MatrixXd& getLinearMatrixC() const { return _mat_c; }
218  void setLinearMatrixC(const Eigen::Ref<const Eigen::MatrixXd>& matric_c) { _mat_c = matric_c; }
219 
220  private:
221  Eigen::MatrixXd _mat_c;
222 };
224 
225 } // namespace corbo
226 
227 #endif // SRC_SYSTEMS_INCLUDE_CORBO_SYSTEMS_OUTPUT_FUNCTION_INTERFACE_H_
FACTORY_REGISTER_OUTPUT_FUNCTION
#define FACTORY_REGISTER_OUTPUT_FUNCTION(type)
Definition: output_function_interface.h:124
corbo::FullStateSystemOutput::getOutputDimension
int getOutputDimension() const override
Get dimension of the system output y.
Definition: output_function_interface.h:144
factory.h
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::FirstStateSystemOutput
Return first state vector component as system output.
Definition: output_function_interface.h:166
corbo::LastStateSystemOutput::getOutputDimension
int getOutputDimension() const override
Get dimension of the system output y.
Definition: output_function_interface.h:199
corbo::SystemOutputInterface::OutputVector
Eigen::VectorXd OutputVector
Definition: output_function_interface.h:112
corbo::LinearStateSystemOutput
Linear system output function.
Definition: output_function_interface.h:223
corbo::LastStateSystemOutput::getInstance
Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
Definition: output_function_interface.h:197
corbo::SystemOutputInterface
Interface class for system output functions.
Definition: output_function_interface.h:84
corbo::FullStateSystemOutput::getInstance
Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
Definition: output_function_interface.h:141
x
Scalar * x
Definition: level1_cplx_impl.h:89
corbo::property::INHERITED
constexpr const int INHERITED
Inherit property.
Definition: core/include/corbo-core/types.h:84
corbo::SystemOutputInterface::output
virtual void output(const StateVector &x, OutputVector &y)=0
Evaluate the system output equation.
corbo::SystemOutputInterface::getInstance
virtual Ptr getInstance() const =0
Return a newly created shared instance of the implemented class.
y
Scalar * y
Definition: level1_cplx_impl.h:102
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
corbo::SystemOutputInterface::reset
virtual void reset()
Definition: output_function_interface.h:135
corbo::SystemOutputInterface::getOutputDimension
virtual int getOutputDimension() const =0
Get dimension of the system output y.
types.h
corbo::LastStateSystemOutput::output
void output(const StateVector &x, OutputVector &y) override
Evaluate the system output equation.
Definition: output_function_interface.h:201
corbo::SystemOutputInterface::Ptr
std::shared_ptr< SystemOutputInterface > Ptr
Definition: output_function_interface.h:109
corbo::FullStateSystemOutput::output
void output(const StateVector &x, OutputVector &y) override
Evaluate the system output equation.
Definition: output_function_interface.h:146
corbo::OutputFunctionFactory
Factory< SystemOutputInterface > OutputFunctionFactory
Definition: output_function_interface.h:123
corbo::SystemOutputInterface::~SystemOutputInterface
virtual ~SystemOutputInterface()=default
Default destructor.
corbo::SystemOutputInterface::StateVector
Eigen::VectorXd StateVector
Definition: output_function_interface.h:111


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