lqr_controller.cpp
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 
27 #include <corbo-core/console.h>
30 
31 #include <Eigen/Cholesky>
32 #include <Eigen/Core>
33 #include <Eigen/Dense>
34 
35 #include <algorithm>
36 
37 namespace corbo {
38 
39 LqrController::LqrController() {}
40 
41 LqrController::LqrController(SystemDynamicsInterface::Ptr system_model) { setSystemModel(system_model); }
42 
43 void LqrController::setSystemModel(SystemDynamicsInterface::Ptr system_model)
44 {
45  _system_model = system_model;
46 
47  const int p = getStateDimension();
48  const int q = getControlInputDimension();
49 
50  setWeights(Eigen::MatrixXd::Identity(p, p), Eigen::MatrixXd::Identity(q, q));
51 }
52 
53 bool LqrController::setWeights(const Eigen::Ref<const Eigen::MatrixXd>& R, const Eigen::Ref<const Eigen::MatrixXd>& Q)
54 {
55  bool ret_val = true;
56  if (!setWeightR(R)) ret_val = false;
57  if (!setWeightQ(Q)) ret_val = false;
58  return ret_val;
59 }
60 
61 bool LqrController::setWeightR(const Eigen::Ref<const Eigen::MatrixXd>& R)
62 {
63  if (!_system_model || R.rows() != _system_model->getInputDimension() || R.cols() != _system_model->getInputDimension()) return false;
64  _R = R;
65  return true;
66 }
67 
68 bool LqrController::setWeightQ(const Eigen::Ref<const Eigen::MatrixXd>& Q)
69 {
70  if (!_system_model || Q.rows() != _system_model->getStateDimension() || Q.cols() != _system_model->getStateDimension()) return false;
71  _Q = Q;
72  return true;
73 }
74 
75 bool LqrController::initialize(const StateVector& x, ReferenceTrajectoryInterface& expected_xref, ReferenceTrajectoryInterface& expected_uref,
76  const Duration& expected_dt, const Time& t, ReferenceTrajectoryInterface* sref)
77 {
78  assert(x.rows() == expected_xref.getDimension() && "Dimension mismatch in controller: current state x and reference");
79  assert(getStateDimension() == property::INHERITED || x.rows() == getStateDimension());
80 
81  if (!_system_model)
82  {
83  PRINT_ERROR("LqrController: no system model provided. Cancelling.");
84  return false;
85  }
86 
87  if (_system_model->isContinuousTime())
88  {
89  _discrete_time = false;
90  PRINT_INFO("LqrController configured for continuous-time system dynamics.");
91  }
92  else
93  {
94  _discrete_time = true;
95  PRINT_INFO("LqrController configured for discrete-time system dynamics.");
96  }
97 
98  ReferenceTrajectoryInterface::OutputVector xref = expected_xref.getNextSteadyState(t);
99 
100  if (xref.rows() != x.rows())
101  {
102  PRINT_WARNING("LqrController currently supports only full state reference trajectories");
103  return false;
104  }
105 
106  ReferenceTrajectoryInterface::OutputVector uref = expected_uref.getNextSteadyState(t);
107 
108  PRINT_INFO_COND(!_system_model->isLinear(), "LQR is provided with a nonlinear model: linearizing model at target state...");
109 
110  const int p = xref.rows();
111  const int q = uref.rows();
112 
113  _A.resize(p, p);
114  _system_model->getLinearA(xref, uref, _A);
115  _B.resize(p, q);
116  _system_model->getLinearB(xref, uref, _B);
117 
118  bool care_success;
119  if (_discrete_time)
120  care_success = AlgebraicRiccatiDiscrete::solve(_A, _B, _Q, _R, _S, &_K);
121  else
122  {
124  "Eigenvalues of the Hamiltonian are close to the imaginary axis. Numerically unstable results are expected.");
125  care_success = AlgebraicRiccatiContinuous::solve(_A, _B, _Q, _R, _S, &_K);
126  }
127 
128  PRINT_WARNING_COND(!care_success || !_S.allFinite(), "Riccati solving failed or NaN coefficients found in solution.");
129 
130  _initialized = true;
131 
132  return true;
133 }
134 
135 bool LqrController::step(const ControllerInterface::StateVector& x, ReferenceTrajectoryInterface& xref, ReferenceTrajectoryInterface& uref,
136  const Duration& dt, const Time& t, TimeSeries::Ptr u_sequence, TimeSeries::Ptr x_sequence,
137  SignalTargetInterface* signal_target, ReferenceTrajectoryInterface* sref, ReferenceTrajectoryInterface* xinit,
138  ReferenceTrajectoryInterface* uinit, const std::string& ns)
139 {
140  const int q = uref.getDimension();
141  ControlVector u;
142 
143  _dt = dt.toSec();
144 
145  if (!_initialized)
146  {
147  if (!initialize(x, xref, uref, dt, t, sref))
148  {
149  u.setZero(q);
150  return false;
151  }
152  }
153 
155  xref.getReference(t, xref_vec);
157  uref.getReference(t, uref_vec);
158 
159  StateVector state_error = xref_vec - x;
160 
161  u = _K * state_error + uref_vec;
162 
163  if (signal_target && _publish_error)
164  {
165  signal_target->sendMeasurement(ns + "controller/error_norml2", t.toSec(), {state_error.norm()});
166  }
167 
168  u_sequence->clear();
169  x_sequence->clear();
170  u_sequence->add(0.0, u);
171  x_sequence->add(0.0, x);
172 
173  return true;
174 }
175 
176 void LqrController::getAvailableSignals(SignalTargetInterface& signal_target, const std::string& ns) const
177 {
178  if (_publish_error)
179  {
180  signal_target.registerMeasurement(ns + "controller/error_norml2", 1);
181  }
182 }
183 
184 void LqrController::reset() { _initialized = false; }
185 
186 #ifdef MESSAGE_SUPPORT
187 void LqrController::toMessage(corbo::messages::LqrController& message) const
188 {
189  if (_system_model) _system_model->toMessage(*message.mutable_system_model());
190 
191  // weight matrix Q
192  if (_Q.isDiagonal())
193  {
194  Eigen::VectorXd Qdiag = _Q.diagonal();
195  message.mutable_q()->Resize(Qdiag.size(), 0);
196  Eigen::Map<Eigen::VectorXd>(message.mutable_q()->mutable_data(), Qdiag.size()) = Qdiag;
197 
198  message.set_q_diagonal_only(true);
199  }
200  else
201  {
202  message.mutable_q()->Resize(_Q.rows() * _Q.cols(), 0);
203  Eigen::Map<Eigen::Matrix<double, -1, -1, Eigen::RowMajor>>(message.mutable_q()->mutable_data(), _Q.rows(), _Q.cols()) = _Q;
204 
205  message.set_q_diagonal_only(false);
206  }
207 
208  // weight matrix R
209  if (_R.isDiagonal())
210  {
211  Eigen::VectorXd Rdiag = _R.diagonal();
212  message.mutable_r()->Resize(Rdiag.size(), 0);
213  Eigen::Map<Eigen::VectorXd>(message.mutable_r()->mutable_data(), Rdiag.size()) = Rdiag;
214 
215  message.set_r_diagonal_only(true);
216  }
217  else
218  {
219  message.mutable_r()->Resize(_R.rows() * _R.cols(), 0);
220  Eigen::Map<Eigen::Matrix<double, -1, -1, Eigen::RowMajor>>(message.mutable_r()->mutable_data(), _R.rows(), _R.cols()) = _R;
221 
222  message.set_r_diagonal_only(false);
223  }
224 
225  // publish error
226  message.set_publish_error(_publish_error);
227 }
228 
229 void LqrController::fromMessage(const corbo::messages::LqrController& message, std::stringstream* issues)
230 {
231  _system_model.reset();
232 
233  // system model
234  if (!message.has_system_model())
235  {
236  if (issues) *issues << "LqrController: no system model specified.\n";
237  return;
238  }
239 
240  // construct object
241  std::string type;
242  util::get_oneof_field_type_expand_isolated(message.system_model(), "system_dynamics", type, false, 1);
244  // import parameters
245  if (dynamics)
246  {
247  dynamics->fromMessage(message.system_model(), issues);
248  setSystemModel(dynamics);
249  }
250  else
251  {
252  if (issues) *issues << "LqrController: unknown system model specified.\n";
253  return;
254  }
255 
256  const int p = dynamics->getStateDimension();
257  const int q = dynamics->getInputDimension();
258 
259  // weight matrix Q
260  if (message.q_diagonal_only())
261  {
262  if (p == message.q_size())
263  {
264  Eigen::MatrixXd Q = Eigen::Map<const Eigen::Matrix<double, -1, 1>>(message.q().data(), message.q_size()).asDiagonal();
265  if (!setWeightQ(Q) && issues) *issues << "LqrController: invalid size of weight matrix Q: it shout be [" << p << " x " << p << "].\n";
266  }
267  else if (issues)
268  *issues << "LqrController: invalid size of weight matrix diag(Q): it shout be [ 1 x " << p << "].\n";
269  }
270  else
271  {
272  if (p * p == message.q_size())
273  {
274  if (!setWeightQ(Eigen::Map<const Eigen::Matrix<double, -1, -1, Eigen::RowMajor>>(message.q().data(), p, p)) && issues)
275  *issues << "LqrController: invalid size of weight matrix Q: it shout be [" << p << " x " << p << "].\n";
276  }
277  else if (issues)
278  *issues << "LqrController: invalid size of weight matrix Q: it shout be [" << p << " x " << p << "].\n";
279  }
280  // weight matrix R
281  if (message.r_diagonal_only())
282  {
283  if (q == message.r_size())
284  {
285  Eigen::MatrixXd R = Eigen::Map<const Eigen::Matrix<double, -1, 1>>(message.r().data(), message.r_size()).asDiagonal();
286  if (!setWeightR(R) && issues) *issues << "LqrController: invalid size of weight matrix R: it shout be [" << q << " x " << q << "].\n";
287  }
288  else if (issues)
289  *issues << "LqrController: invalid size of weight matrix diag(R): it shout be [ 1 x " << q << "].\n";
290  }
291  else
292  {
293  if (q * q == message.r_size())
294  {
295  if (!setWeightR(Eigen::Map<const Eigen::Matrix<double, -1, -1, Eigen::RowMajor>>(message.r().data(), q, q)) && issues)
296  *issues << "LqrController: invalid size of weight matrix R: it shout be [" << q << " x " << q << "].\n";
297  }
298  else if (issues)
299  *issues << "LqrController: invalid size of weight matrix R: it shout be [" << q << " x " << q << "].\n";
300  }
301 
302  // publish error
303  _publish_error = message.publish_error();
304 }
305 #endif
306 
307 } // namespace corbo
PRINT_WARNING_COND_NAMED
#define PRINT_WARNING_COND_NAMED(cond, msg)
Definition: console.h:257
PRINT_WARNING
#define PRINT_WARNING(msg)
Print msg-stream.
Definition: console.h:145
algebraic_riccati_discrete.h
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::AlgebraicRiccatiContinuous::isNumericallyStable
static bool isNumericallyStable(const Eigen::Ref< const Eigen::MatrixXd > &A, const Eigen::Ref< const Eigen::MatrixXd > &B, const Eigen::Ref< const Eigen::MatrixXd > &Q, const Eigen::Ref< const Eigen::MatrixXd > &R)
Determine if solving the riccati equation seems to be numerically stable.
Definition: algebraic_riccati_continuous.cpp:218
Eigen::RowMajor
@ RowMajor
Definition: Constants.h:322
console.h
lqr_controller.h
PRINT_INFO_COND
#define PRINT_INFO_COND(cond, msg)
Print msg-stream only if cond == true.
Definition: console.h:131
corbo::Factory::instance
static Factory & instance()
< Retrieve static instance of the factory
Definition: factory.h:116
Eigen::numext::q
EIGEN_DEVICE_FUNC const Scalar & q
Definition: SpecialFunctionsImpl.h:1520
corbo::AlgebraicRiccatiDiscrete::solve
static bool solve(const Eigen::Ref< const Eigen::MatrixXd > &A, const Eigen::Ref< const Eigen::MatrixXd > &B, const Eigen::Ref< const Eigen::MatrixXd > &Q, const Eigen::Ref< const Eigen::MatrixXd > &R, Eigen::MatrixXd &X, Eigen::MatrixXd *G=nullptr)
Solve discrete-time algebraic Riccati equation.
Definition: algebraic_riccati_discrete.cpp:62
x
Scalar * x
Definition: level1_cplx_impl.h:89
PRINT_WARNING_COND
#define PRINT_WARNING_COND(cond, msg)
Print msg-stream only if cond == true.
Definition: console.h:159
corbo::property::INHERITED
constexpr const int INHERITED
Inherit property.
Definition: core/include/corbo-core/types.h:84
corbo::SystemDynamicsInterface::Ptr
std::shared_ptr< SystemDynamicsInterface > Ptr
Definition: system_dynamics_interface.h:91
Eigen::Map
A matrix or vector expression mapping an existing array of data.
Definition: Map.h:94
algebraic_riccati_continuous.h
utilities.h
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
corbo::Factory::create
std::shared_ptr< Derived > create(const std::string &name, bool print_error=true) const
Create a shared instance of the desired object.
Definition: factory.h:137
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: Matrix.h:178
corbo::AlgebraicRiccatiContinuous::solve
static bool solve(const Eigen::Ref< const Eigen::MatrixXd > &A, const Eigen::Ref< const Eigen::MatrixXd > &B, const Eigen::Ref< const Eigen::MatrixXd > &Q, const Eigen::Ref< const Eigen::MatrixXd > &R, Eigen::MatrixXd &X, Eigen::MatrixXd *G=nullptr)
Solve continuous-time algebraic Riccati equation.
Definition: algebraic_riccati_continuous.cpp:62
corbo::ReferenceTrajectoryInterface::OutputVector
Eigen::VectorXd OutputVector
Definition: reference_trajectory.h:108
corbo::ControllerInterface::StateVector
Eigen::VectorXd StateVector
Definition: controller_interface.h:107
corbo::TimeSeries::Ptr
std::shared_ptr< TimeSeries > Ptr
Definition: time_series.h:108
PRINT_INFO
#define PRINT_INFO(msg)
Print msg-stream.
Definition: console.h:117
PRINT_ERROR
#define PRINT_ERROR(msg)
Print msg-stream as error msg.
Definition: console.h:173


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