controller_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_CONTROLLERS_INCLUDE_CORBO_CONTROLLERS_CONTROLLER_INTERFACE_H_
26 #define SRC_CONTROLLERS_INCLUDE_CORBO_CONTROLLERS_CONTROLLER_INTERFACE_H_
27 
29 #include <corbo-core/factory.h>
32 #include <corbo-core/time.h>
33 #include <corbo-core/types.h>
35 
36 #ifdef MESSAGE_SUPPORT
37 #include <corbo-communication/messages/controllers/controllers.pb.h>
38 #endif
39 
40 #include <memory>
41 
42 namespace corbo {
43 
58 class ControllerInterface
59 {
60  public:
61  using Ptr = std::shared_ptr<ControllerInterface>;
62  using UPtr = std::unique_ptr<ControllerInterface>;
63  using StateVector = Eigen::VectorXd;
64  using ControlVector = Eigen::VectorXd;
65 
67  virtual ~ControllerInterface() {}
68 
70  virtual Ptr getInstance() const = 0;
71 
73  static Factory<ControllerInterface>& getFactory() { return Factory<ControllerInterface>::instance(); }
74 
76  virtual int getControlInputDimension() const = 0;
84  virtual int getStateDimension() const = 0;
85 
86  virtual bool providesFutureControls() const = 0;
87 
88  virtual bool providesFutureStates() const = 0;
89 
95  virtual bool hasPiecewiseConstantControls() const = 0;
96 
109  virtual bool initialize(const StateVector& x, ReferenceTrajectoryInterface& expected_xref, ReferenceTrajectoryInterface& expected_uref,
110  const Duration& expected_dt, const Time& t, ReferenceTrajectoryInterface* expected_sref = nullptr)
111  {
112  return true;
113  }
114 
127  virtual bool step(const StateVector& x, ReferenceTrajectoryInterface& xref, ReferenceTrajectoryInterface& uref, const Duration& dt, const Time& t,
128  ControlVector& u, SignalTargetInterface* signal_target = nullptr, const std::string& ns = "");
129 
130  virtual bool step(const StateVector& x, ReferenceTrajectoryInterface& xref, ReferenceTrajectoryInterface& uref, const Duration& dt, const Time& t,
131  TimeSeries::Ptr u_sequence, TimeSeries::Ptr x_sequence, SignalTargetInterface* signal_target = nullptr,
132  ReferenceTrajectoryInterface* sref = nullptr, ReferenceTrajectoryInterface* xinit = nullptr,
133  ReferenceTrajectoryInterface* uinit = nullptr, const std::string& ns = "") = 0;
134 
136  virtual double getControlDuration() const { return 0.0; }
138  virtual bool supportsAsynchronousControl() const { return false; }
139 
141  virtual void reset() = 0;
142 
152  virtual void getAvailableSignals(SignalTargetInterface& signal_target, const std::string& ns = "") const {}
153 
154  virtual void sendSignals(double t, SignalTargetInterface& signal_target, const std::string& ns = "") const {}
155 
156  virtual ControllerStatistics::Ptr getStatistics() const { return {}; }
157 
158 #ifdef MESSAGE_SUPPORT
159  virtual void toMessage(corbo::messages::Controller& message) const {}
162  virtual void fromMessage(const corbo::messages::Controller& message, std::stringstream* issues = nullptr) {}
163 #endif
164 };
165 
166 using ControllerFactory = Factory<ControllerInterface>;
167 #define FACTORY_REGISTER_CONTROLLER(type) FACTORY_REGISTER_OBJECT(type, ControllerInterface)
168 
169 } // namespace corbo
170 
171 #endif // SRC_CONTROLLERS_INCLUDE_CORBO_CONTROLLERS_CONTROLLER_INTERFACE_H_
signal_target_interface.h
corbo::SignalTargetInterface
Interface class for signal targets.
Definition: signal_target_interface.h:84
corbo::ControllerInterface::getFactory
static Factory< ControllerInterface > & getFactory()
Get access to the associated factory.
Definition: controller_interface.h:117
corbo::ControllerInterface::supportsAsynchronousControl
virtual bool supportsAsynchronousControl() const
Specify whether the controllers step function is independent of dt and getControlDuration() returns a...
Definition: controller_interface.h:182
factory.h
corbo::ReferenceTrajectoryInterface
Interface class for reference trajectories.
Definition: reference_trajectory.h:82
output_function_interface.h
corbo::ControllerInterface::initialize
virtual bool initialize(const StateVector &x, ReferenceTrajectoryInterface &expected_xref, ReferenceTrajectoryInterface &expected_uref, const Duration &expected_dt, const Time &t, ReferenceTrajectoryInterface *expected_sref=nullptr)
Initialize the controller.
Definition: controller_interface.h:153
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::ControllerInterface::getControlDuration
virtual double getControlDuration() const
Return the duration for which the control u obtained from step() is valid (useful for asynchronous co...
Definition: controller_interface.h:180
corbo::ControllerInterface::getStatistics
virtual ControllerStatistics::Ptr getStatistics() const
Definition: controller_interface.h:200
statistics.h
corbo::ControllerInterface::providesFutureStates
virtual bool providesFutureStates() const =0
corbo::Factory::instance
static Factory & instance()
< Retrieve static instance of the factory
Definition: factory.h:116
corbo::ControllerFactory
Factory< ControllerInterface > ControllerFactory
Definition: controller_interface.h:188
corbo::ControllerInterface::getInstance
virtual Ptr getInstance() const =0
Return a newly created shared instance of the implemented class.
corbo::Duration
Representation of time durations.
Definition: time.h:128
corbo::ControllerInterface::ControlVector
Eigen::VectorXd ControlVector
Definition: controller_interface.h:108
time.h
x
Scalar * x
Definition: level1_cplx_impl.h:89
corbo::ControllerInterface::hasPiecewiseConstantControls
virtual bool hasPiecewiseConstantControls() const =0
Return true if the controller returns piecewise constant control pieces.
corbo::ControllerInterface::step
virtual bool step(const StateVector &x, ReferenceTrajectoryInterface &xref, ReferenceTrajectoryInterface &uref, const Duration &dt, const Time &t, ControlVector &u, SignalTargetInterface *signal_target=nullptr, const std::string &ns="")
Perform actual controller step / control law computation.
Definition: controller_interface.cpp:51
corbo::ControllerInterface::Ptr
std::shared_ptr< ControllerInterface > Ptr
Definition: controller_interface.h:105
corbo::ControllerInterface::getStateDimension
virtual int getStateDimension() const =0
Return the dimension of the required plant state/output.
corbo::ControllerInterface::getControlInputDimension
virtual int getControlInputDimension() const =0
Return the control input dimension.
corbo::ControllerInterface::~ControllerInterface
virtual ~ControllerInterface()
Virtual destructor.
Definition: controller_interface.h:111
corbo::ControllerStatistics::Ptr
std::shared_ptr< ControllerStatistics > Ptr
Definition: controllers/include/corbo-controllers/statistics.h:81
types.h
corbo::Time
Representation of time stamps.
Definition: time.h:273
corbo::ControllerInterface::sendSignals
virtual void sendSignals(double t, SignalTargetInterface &signal_target, const std::string &ns="") const
Definition: controller_interface.h:198
corbo::ControllerInterface::StateVector
Eigen::VectorXd StateVector
Definition: controller_interface.h:107
reference_trajectory.h
corbo::ControllerInterface::providesFutureControls
virtual bool providesFutureControls() const =0
corbo::ControllerInterface::getAvailableSignals
virtual void getAvailableSignals(SignalTargetInterface &signal_target, const std::string &ns="") const
Retrieve available signals from the controller.
Definition: controller_interface.h:196
corbo::TimeSeries::Ptr
std::shared_ptr< TimeSeries > Ptr
Definition: time_series.h:108
corbo::ControllerInterface::reset
virtual void reset()=0
Reset internal controller state and caches.
corbo::ControllerInterface::UPtr
std::unique_ptr< ControllerInterface > UPtr
Definition: controller_interface.h:106


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