observer_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_OBSERVERS_INCLUDE_CORBO_OBSERVERS_OBSERVER_INTERFACE_H_
26 #define SRC_OBSERVERS_INCLUDE_CORBO_OBSERVERS_OBSERVER_INTERFACE_H_
27 
28 #include <corbo-core/factory.h>
30 #include <corbo-core/time.h>
31 #include <corbo-core/types.h>
32 
33 #ifdef MESSAGE_SUPPORT
34 #include <corbo-communication/messages/observers/observers.pb.h>
35 #endif
36 
37 #include <memory>
38 
39 namespace corbo {
40 
58 class ObserverInterface
59 {
60  public:
61  using Ptr = std::shared_ptr<ObserverInterface>;
62  using UPtr = std::unique_ptr<ObserverInterface>;
63  using StateVector = Eigen::VectorXd;
64  using OutputVector = Eigen::VectorXd;
65 
67  virtual ~ObserverInterface() {}
68 
70  virtual Ptr getInstance() const = 0;
71 
73  static Factory<ObserverInterface>& getFactory() { return Factory<ObserverInterface>::instance(); }
74 
83  virtual int getOutputDimension() const = 0;
84 
89  virtual int getStateDimension() const = 0;
90 
101  virtual bool observe(const OutputVector& y, StateVector& x, const Duration& dt, const Time& t,
102  SignalTargetInterface* signal_target = nullptr, const std::string& ns = "") = 0;
103 
105  virtual void reset() {}
106 
116  virtual void getAvailableSignals(SignalTargetInterface& signal_target, const std::string& ns = "") const {}
117 
118 #ifdef MESSAGE_SUPPORT
119  virtual void toMessage(corbo::messages::Observer& message) const {}
122  virtual void fromMessage(const corbo::messages::Observer& message, std::stringstream* issues = nullptr) {}
123 #endif
124 };
125 
126 using ObserverFactory = Factory<ObserverInterface>;
127 #define FACTORY_REGISTER_OBSERVER(type) FACTORY_REGISTER_OBJECT(type, ObserverInterface)
128 
141 class NoObserver : public ObserverInterface
142 {
143  public:
144  // implements interface method
145  Ptr getInstance() const override { return std::make_shared<NoObserver>(); }
146 
147  // implements interface method
148  int getOutputDimension() const override { return property::INHERITED; }
149  // implements interface method
150  int getStateDimension() const override { return property::INHERITED; }
151  // implements interface method
152  bool observe(const OutputVector& y, StateVector& x, const Duration& /*dt*/, const Time& /*t*/,
153  SignalTargetInterface* signal_target = nullptr, const std::string& ns = "") override
154  {
155  x = y;
156  return true;
157  }
158 
159 #ifdef MESSAGE_SUPPORT
160  // implements interface method
161  void toMessage(corbo::messages::Observer& message) const override { message.mutable_no_observer(); }
162 #endif
163 };
164 
165 FACTORY_REGISTER_OBSERVER(NoObserver)
166 
167 } // namespace corbo
168 
169 #endif // SRC_OBSERVERS_INCLUDE_CORBO_OBSERVERS_OBSERVER_INTERFACE_H_
signal_target_interface.h
FACTORY_REGISTER_OBSERVER
#define FACTORY_REGISTER_OBSERVER(type)
Definition: observer_interface.h:149
corbo::ObserverInterface::OutputVector
Eigen::VectorXd OutputVector
Definition: observer_interface.h:108
corbo::SignalTargetInterface
Interface class for signal targets.
Definition: signal_target_interface.h:84
corbo::ObserverInterface::~ObserverInterface
virtual ~ObserverInterface()
Virtual destructor.
Definition: observer_interface.h:111
factory.h
corbo::ObserverInterface::getInstance
virtual Ptr getInstance() const =0
Return a newly created shared instance of the implemented class.
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::ObserverInterface::reset
virtual void reset()
Reset internal observer state and caches.
Definition: observer_interface.h:149
corbo::ObserverInterface::getAvailableSignals
virtual void getAvailableSignals(SignalTargetInterface &signal_target, const std::string &ns="") const
Retrieve available signals from the observer.
Definition: observer_interface.h:160
corbo::ObserverInterface::observe
virtual bool observe(const OutputVector &y, StateVector &x, const Duration &dt, const Time &t, SignalTargetInterface *signal_target=nullptr, const std::string &ns="")=0
Perform actual observer step / state estimation.
corbo::ObserverInterface::getOutputDimension
virtual int getOutputDimension() const =0
Return the dimension of the supported plant output.
corbo::ObserverInterface::Ptr
std::shared_ptr< ObserverInterface > Ptr
Definition: observer_interface.h:105
corbo::Factory::instance
static Factory & instance()
< Retrieve static instance of the factory
Definition: factory.h:116
time.h
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
y
Scalar * y
Definition: level1_cplx_impl.h:102
corbo::ObserverInterface::StateVector
Eigen::VectorXd StateVector
Definition: observer_interface.h:107
corbo::ObserverInterface::UPtr
std::unique_ptr< ObserverInterface > UPtr
Definition: observer_interface.h:106
types.h
corbo::ObserverFactory
Factory< ObserverInterface > ObserverFactory
Definition: observer_interface.h:148
corbo::ObserverInterface::getStateDimension
virtual int getStateDimension() const =0
Return the dimension of the observed state.
corbo::ObserverInterface::getFactory
static Factory< ObserverInterface > & getFactory()
Get access to the associated factory.
Definition: observer_interface.h:117


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