quadratic_control_cost.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 
26 
28 
29 #include <cmath>
30 
31 namespace corbo {
32 
34 {
36 
37  if (!is_square(R)) return false;
38 
39  // check if we have a diagonal matrix
40  if (R.isDiagonal(1e-10)) return setWeightR(R.diagonal().asDiagonal());
41 
42  _diagonal_mode = false;
43 
44  _R = R; // also store original R
45  if (R.isZero())
46  {
47  _R_sqrt.setZero();
48  return true;
49  }
51  if (cholesky.info() == Eigen::NumericalIssue) return false;
52  _R_sqrt = cholesky.matrixU();
53  return true;
54 }
55 
57 {
59  _diagonal_mode = true;
60  _R_diag = R;
61  _R_diag_sqrt = R.diagonal().cwiseSqrt().asDiagonal();
62  return true;
63 }
64 
66 {
67  assert(!_integral_form);
68  assert(cost.size() == getNonIntegralControlTermDimension(k));
69 
70  if (_lsq_form)
71  {
72  if (_zero_u_ref)
73  {
74  if (_diagonal_mode)
75  cost.noalias() = _R_diag_sqrt * u_k;
76  else
77  cost.noalias() = _R_sqrt * u_k;
78  }
79  else
80  {
81  Eigen::VectorXd ud = u_k - _u_ref->getReferenceCached(k);
82  if (_diagonal_mode)
83  cost.noalias() = _R_diag_sqrt * ud;
84  else
85  cost.noalias() = _R_sqrt * ud;
86  }
87  }
88  else
89  {
90  if (_zero_u_ref)
91  {
92  if (_diagonal_mode)
93  cost.noalias() = u_k.transpose() * _R_diag * u_k;
94  else
95  cost.noalias() = u_k.transpose() * _R * u_k;
96  }
97  else
98  {
99  Eigen::VectorXd ud = u_k - _u_ref->getReferenceCached(k);
100  if (_diagonal_mode)
101  cost.noalias() = ud.transpose() * _R_diag * ud;
102  else
103  cost.noalias() = ud.transpose() * _R * ud;
104  }
105  }
106 }
107 
110 {
111  assert(_integral_form);
112  assert(cost.size() == 1);
113 
114  cost[0] = 0;
115 
116  if (_zero_u_ref)
117  {
118  if (_diagonal_mode)
119  cost[0] += u_k.transpose() * _R_diag * u_k;
120  else
121  cost[0] += u_k.transpose() * _R * u_k;
122  }
123  else
124  {
125  Eigen::VectorXd ud = u_k - _u_ref->getReferenceCached(k);
126  if (_diagonal_mode)
127  cost[0] += ud.transpose() * _R_diag * ud;
128  else
129  cost[0] += ud.transpose() * _R * ud;
130  }
131 }
132 
133 bool QuadraticControlCost::checkParameters(int state_dim, int control_dim, std::stringstream* issues) const
134 {
135  bool success = true;
136 
138  {
139  if (_R_diag.diagonal().size() != control_dim)
140  {
141  if (issues)
142  *issues << "QuadraticControlCost: diagonal matrix dimension of R (" << _R_diag.diagonal().size()
143  << ") does not match control input vector dimension (" << control_dim << "); Please specify diagonal elements only."
144  << std::endl;
145  success = false;
146  }
147  }
148  else
149  {
150  if (_R.rows() != control_dim || _R.cols() != control_dim)
151  {
152  if (issues)
153  *issues << "QuadraticControlCost: Matrix dimension of R (" << _R.rows() << "x" << _R.cols()
154  << ") does not match control input vector dimension (" << control_dim << "); Please specify " << (control_dim * control_dim)
155  << " elements (Row-Major)." << std::endl;
156  success = false;
157  }
158  }
159 
160  return success;
161 }
162 
163 #ifdef MESSAGE_SUPPORT
164 bool QuadraticControlCost::fromMessage(const messages::QuadraticControlCost& message, std::stringstream* issues)
165 {
166  _diagonal_mode = message.diagonal_only();
167 
168  if (_diagonal_mode)
169  {
170  if (!setWeightR(Eigen::Map<const Eigen::Matrix<double, -1, 1>>(message.r().data(), message.r_size()).asDiagonal()))
171  {
172  *issues << "QuadraticControlCost: cannot set diagonal weight matrix R.\n";
173  return false;
174  }
175  }
176  else
177  {
178  int q = std::sqrt(message.r_size());
179 
180  if (q * q != message.r_size())
181  {
182  *issues << "QuadraticControlCost: weight matrix R is not square.\n";
183  return false;
184  }
185 
186  // weight matrix Q
187  // if (p * p == message.full_discretization_ocp().q_size())
188  //{
189  if (!setWeightR(Eigen::Map<const Eigen::Matrix<double, -1, -1, Eigen::RowMajor>>(message.r().data(), q, q)) && issues)
190  {
191  *issues << "QuadraticControlCost: weight matrix R is not positive definite.\n";
192  return false;
193  }
194  //}
195  // else if (issues)
196  // *issues << "QuadraticControlCost: invalid size of weight matrix Q: it shout be [" << p << " x " << p << "].\n";
197  }
198 
199  // others
200  _lsq_form = message.lsq_form();
201  _integral_form = message.integral_form();
202 
203  return true;
204 }
205 
206 void QuadraticControlCost::toMessage(messages::QuadraticControlCost& message) const
207 {
208  // weight matrix R
210  {
211  Eigen::VectorXd Rdiag = _R_diag.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_diagonal_only(true);
216  }
217  else
218  {
219  Eigen::MatrixXd R = _R; // R = _R_sqrt.adjoint() * _R_sqrt;
220  message.mutable_r()->Resize(R.rows() * R.cols(), 0);
221  Eigen::Map<Eigen::Matrix<double, -1, -1, Eigen::RowMajor>>(message.mutable_r()->mutable_data(), R.rows(),
222  R.cols()) = R;
223 
224  message.set_diagonal_only(false);
225  }
226 
227  // others
228  message.set_lsq_form(_lsq_form);
229  message.set_integral_form(_integral_form);
230 }
231 #endif
232 
233 } // namespace corbo
corbo::QuadraticControlCost::_R_sqrt
Eigen::MatrixXd _R_sqrt
Definition: quadratic_control_cost.h:134
Eigen::NumericalIssue
@ NumericalIssue
Definition: Constants.h:434
sqrt
const EIGEN_DEVICE_FUNC SqrtReturnType sqrt() const
Definition: ArrayCwiseUnaryOps.h:152
corbo::QuadraticControlCost::_lsq_form
bool _lsq_form
Definition: quadratic_control_cost.h:140
Eigen::DiagonalMatrix< double, -1 >
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::ReferenceTrajectoryInterface::getReferenceCached
virtual const OutputVector & getReferenceCached(int k) const =0
corbo::QuadraticControlCost::_R_diag_sqrt
Eigen::DiagonalMatrix< double, -1 > _R_diag_sqrt
Definition: quadratic_control_cost.h:136
corbo::QuadraticControlCost::_diagonal_mode
bool _diagonal_mode
Definition: quadratic_control_cost.h:138
corbo::QuadraticControlCost::computeIntegralStateControlTerm
void computeIntegralStateControlTerm(int k, const Eigen::Ref< const Eigen::VectorXd > &x_k, const Eigen::Ref< const Eigen::VectorXd > &u_k, Eigen::Ref< Eigen::VectorXd > cost) const override
Definition: quadratic_control_cost.cpp:130
corbo::QuadraticControlCost::computeNonIntegralControlTerm
void computeNonIntegralControlTerm(int k, const Eigen::Ref< const Eigen::VectorXd > &u_k, Eigen::Ref< Eigen::VectorXd > cost) const override
Definition: quadratic_control_cost.cpp:87
Eigen::RowMajor
@ RowMajor
Definition: Constants.h:322
corbo::QuadraticControlCost::_zero_u_ref
bool _zero_u_ref
Definition: quadratic_control_cost.h:144
corbo::QuadraticControlCost::_diagonal_mode_intentionally
bool _diagonal_mode_intentionally
Definition: quadratic_control_cost.h:139
corbo::QuadraticControlCost::_R
Eigen::MatrixXd _R
Definition: quadratic_control_cost.h:135
Eigen::DiagonalMatrix::diagonal
const EIGEN_DEVICE_FUNC DiagonalVectorType & diagonal() const
Definition: DiagonalMatrix.h:136
corbo::is_square
bool is_square(const Eigen::MatrixBase< Derived > &matrix)
Determine if a given matrix is square.
Definition: matrix_utilities.h:65
corbo::QuadraticControlCost::checkParameters
bool checkParameters(int state_dim, int control_dim, std::stringstream *issues) const override
Definition: quadratic_control_cost.cpp:155
Eigen::numext::q
EIGEN_DEVICE_FUNC const Scalar & q
Definition: SpecialFunctionsImpl.h:1520
corbo::QuadraticControlCost::_u_ref
const ReferenceTrajectoryInterface * _u_ref
Definition: quadratic_control_cost.h:143
corbo::QuadraticControlCost::setWeightR
bool setWeightR(const Eigen::Ref< const Eigen::MatrixXd > &R)
Definition: quadratic_control_cost.cpp:55
matrix_utilities.h
Eigen::Map
A matrix or vector expression mapping an existing array of data.
Definition: Map.h:94
Eigen::LLT
Standard Cholesky decomposition (LL^T) of a matrix and associated features.
Definition: LLT.h:56
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
quadratic_control_cost.h
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: Matrix.h:178
corbo::QuadraticControlCost::_R_diag
Eigen::DiagonalMatrix< double, -1 > _R_diag
Definition: quadratic_control_cost.h:137
corbo::QuadraticControlCost::getNonIntegralControlTermDimension
int getNonIntegralControlTermDimension(int k) const override
Definition: quadratic_control_cost.h:100
corbo::QuadraticControlCost::_integral_form
bool _integral_form
Definition: quadratic_control_cost.h:141


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