lqr_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_LQR_CONTROLLER_H_
26 #define SRC_CONTROLLERS_INCLUDE_CORBO_CONTROLLERS_LQR_CONTROLLER_H_
27 
30 #include <memory>
31 
32 namespace corbo {
33 
74 class LqrController : public ControllerInterface
75 {
76  public:
77  using Ptr = std::shared_ptr<LqrController>;
78 
79  LqrController();
80  explicit LqrController(SystemDynamicsInterface::Ptr system_model);
81 
82  // implements interface method
83  int getControlInputDimension() const override { return _system_model ? _system_model->getInputDimension() : 0; }
84  // implements interface method
85  int getStateDimension() const override { return _system_model ? _system_model->getStateDimension() : 0; }
86  // implements interface method
87  bool hasPiecewiseConstantControls() const override { return false; }
88  // implements interface method
89  bool providesFutureControls() const override { return false; }
90  // implements interface method
91  bool providesFutureStates() const override { return false; }
92 
93  // implements interface method
94  ControllerInterface::Ptr getInstance() const override { return std::make_shared<LqrController>(); }
95 
97  void setSystemModel(SystemDynamicsInterface::Ptr system_model);
98 
105  bool setWeights(const Eigen::Ref<const Eigen::MatrixXd>& R, const Eigen::Ref<const Eigen::MatrixXd>& Q);
106 
108  bool setWeightR(const Eigen::Ref<const Eigen::MatrixXd>& R);
110  bool setWeightQ(const Eigen::Ref<const Eigen::MatrixXd>& Q);
111 
112  // implements interface method
113  bool initialize(const StateVector& x, ReferenceTrajectoryInterface& expected_xref, ReferenceTrajectoryInterface& expected_uref,
114  const Duration& expected_dt, const Time& t, ReferenceTrajectoryInterface* sref = nullptr) override;
115 
116  // implements interface method
117  bool step(const StateVector& x, ReferenceTrajectoryInterface& xref, ReferenceTrajectoryInterface& uref, const Duration& dt, const Time& t,
118  TimeSeries::Ptr u_sequence, TimeSeries::Ptr x_sequence, SignalTargetInterface* signal_target = nullptr,
119  ReferenceTrajectoryInterface* sref = nullptr, ReferenceTrajectoryInterface* xinit = nullptr,
120  ReferenceTrajectoryInterface* uinit = nullptr, const std::string& ns = "") override;
121 
122  // implements interface method
123  void getAvailableSignals(SignalTargetInterface& signal_target, const std::string& ns = "") const override;
124 
125  ControllerStatistics::Ptr getStatistics() const override { return {}; }
126 
127 #ifdef MESSAGE_SUPPORT
128  void toMessage(corbo::messages::LqrController& message) const;
129  void fromMessage(const corbo::messages::LqrController& message, std::stringstream* issues = nullptr);
130  // implements interface method
131  void toMessage(corbo::messages::Controller& message) const override { toMessage(*message.mutable_lqr_controller()); }
132  // implements interface method
133  void fromMessage(const corbo::messages::Controller& message, std::stringstream* issues = nullptr) override
134  {
135  fromMessage(message.lqr_controller(), issues);
136  }
137 #endif
138 
139  // implements interface method
140  void reset() override;
141 
143  void setPublishError(bool publish) { _publish_error = publish; }
144 
145  private:
146  SystemDynamicsInterface::Ptr _system_model;
147  bool _discrete_time = false;
148 
149  bool _initialized = false;
150 
151  bool _publish_error = true;
152 
153  double _dt = 0.1;
154 
155  Eigen::MatrixXd _A;
156  Eigen::MatrixXd _B;
157 
158  Eigen::MatrixXd _R;
159  Eigen::MatrixXd _Q;
160 
161  Eigen::MatrixXd _S;
162 
163  Eigen::MatrixXd _K;
164 };
165 
166 FACTORY_REGISTER_CONTROLLER(LqrController)
167 
168 } // namespace corbo
169 
170 #endif // SRC_CONTROLLERS_INCLUDE_CORBO_CONTROLLERS_LQR_CONTROLLER_H_
system_dynamics_interface.h
corbo
Definition: communication/include/corbo-communication/utilities.h:37
controller_interface.h
x
Scalar * x
Definition: level1_cplx_impl.h:89
corbo::SystemDynamicsInterface::Ptr
std::shared_ptr< SystemDynamicsInterface > Ptr
Definition: system_dynamics_interface.h:91
corbo::ControllerInterface::Ptr
std::shared_ptr< ControllerInterface > Ptr
Definition: controller_interface.h:105
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
corbo::ControllerStatistics::Ptr
std::shared_ptr< ControllerStatistics > Ptr
Definition: controllers/include/corbo-controllers/statistics.h:81
corbo::TimeSeries::Ptr
std::shared_ptr< TimeSeries > Ptr
Definition: time_series.h:108
FACTORY_REGISTER_CONTROLLER
#define FACTORY_REGISTER_CONTROLLER(type)
Definition: controller_interface.h:189


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