simple_state_controller.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_SIMPLE_STATE_CONTROLLER_H_
26 #define SRC_CONTROLLERS_INCLUDE_CORBO_CONTROLLERS_SIMPLE_STATE_CONTROLLER_H_
27 
29 #include <memory>
30 
31 namespace corbo {
32 
47 {
48  public:
49  SimpleStateController() = default;
50 
51  // implements interface method
52  int getControlInputDimension() const override { return _K.rows(); }
53  // implements interface method
54  int getStateDimension() const override { return _V.cols() > 0 ? _V.cols() : _K.cols(); }
55  // implements interface method
56  bool hasPiecewiseConstantControls() const override { return false; }
57  // implements interface method
58  bool providesFutureControls() const override { return false; }
59  // implements interface method
60  bool providesFutureStates() const override { return false; }
61 
62  // implements interface method
63  Ptr getInstance() const override { return std::make_shared<SimpleStateController>(); }
64 
67 
70 
71  // implements interface method
72  bool initialize(const StateVector& x, ReferenceTrajectoryInterface& expected_xref, ReferenceTrajectoryInterface& expected_uref,
73  const Duration& expected_dt, const Time& t, ReferenceTrajectoryInterface* sref = nullptr) override;
74 
75  // implements interface method
76  bool step(const StateVector& x, ReferenceTrajectoryInterface& xref, ReferenceTrajectoryInterface& uref, const Duration& dt, const Time& t,
77  TimeSeries::Ptr u_sequence, TimeSeries::Ptr x_sequence, SignalTargetInterface* signal_target = nullptr,
78  ReferenceTrajectoryInterface* sref = nullptr, ReferenceTrajectoryInterface* xinit = nullptr,
79  ReferenceTrajectoryInterface* uinit = nullptr, const std::string& ns = "") override;
80 
81  // implements interface method
82  void getAvailableSignals(SignalTargetInterface& signal_target, const std::string& ns = "") const override;
83 
84 #ifdef MESSAGE_SUPPORT
85  // implements interface method
86  void toMessage(corbo::messages::Controller& message) const override;
87  // implements interface method
88  void fromMessage(const corbo::messages::Controller& message, std::stringstream* issues = nullptr) override;
89 #endif
90 
91  // implements interface method
92  void reset() override;
93 
95  void setPublishError(bool publish) { _publish_error = publish; }
96 
97  private:
98  bool _publish_error = true;
99  Eigen::MatrixXd _K;
100  Eigen::MatrixXd _V;
101 };
102 
104 
105 } // namespace corbo
106 
107 #endif // SRC_CONTROLLERS_INCLUDE_CORBO_CONTROLLERS_SIMPLE_STATE_CONTROLLER_H_
Scalar * x
void reset() override
Reset internal controller state and caches.
State feedback controller wigh feedback gain matrix K.
void getAvailableSignals(SignalTargetInterface &signal_target, const std::string &ns="") const override
Retrieve available signals from the controller.
void setFilterMatrixV(const Eigen::Ref< const Eigen::MatrixXd > &V)
Set reference filter matrix V [control input dimension x output dimension].
void setPublishError(bool publish)
Specify whether the state error should be published via signal.
bool providesFutureControls() const override
void setGainMatrixK(const Eigen::Ref< const Eigen::MatrixXd > &K)
Set feedback gain matrix K [control input dimension x state dimension].
Interface class for signal targets.
Representation of time stamps.
Definition: time.h:251
int getControlInputDimension() const override
Return the control input dimension.
bool providesFutureStates() const override
#define FACTORY_REGISTER_CONTROLLER(type)
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
Interface class for reference trajectories.
bool hasPiecewiseConstantControls() const override
Return true if the controller returns piecewise constant control pieces.
bool initialize(const StateVector &x, ReferenceTrajectoryInterface &expected_xref, ReferenceTrajectoryInterface &expected_uref, const Duration &expected_dt, const Time &t, ReferenceTrajectoryInterface *sref=nullptr) override
Initialize the controller.
Interface class for controllers.
std::shared_ptr< TimeSeries > Ptr
Definition: time_series.h:64
Representation of time durations.
Definition: time.h:106
std::shared_ptr< ControllerInterface > Ptr
bool step(const StateVector &x, ReferenceTrajectoryInterface &xref, ReferenceTrajectoryInterface &uref, const Duration &dt, const Time &t, TimeSeries::Ptr u_sequence, TimeSeries::Ptr x_sequence, SignalTargetInterface *signal_target=nullptr, ReferenceTrajectoryInterface *sref=nullptr, ReferenceTrajectoryInterface *xinit=nullptr, ReferenceTrajectoryInterface *uinit=nullptr, const std::string &ns="") override
int getStateDimension() const override
Return the dimension of the required plant state/output.


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Mon Feb 28 2022 22:07:18