final_state_constraints.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 
30 
31 #include <cmath>
32 
33 namespace corbo {
34 
36 {
37  if (S.size() == 0) return false;
38  if (!is_square(S)) return false;
39 
40  // check if we have a diagonal matrix
41  if (S.isDiagonal(1e-10)) return setWeightS(S.diagonal().asDiagonal());
42 
43  _diagonal_mode = false;
45  _S = S;
46  return true;
47 }
48 
50 {
51  if (S.size() == 0) return false;
52 
54  _diagonal_mode = true;
55  _S_diag = S;
57  return true;
58 }
59 
61 {
62  assert(cost.size() == getNonIntegralStateTermDimension(k));
63 
64  if (_zero_x_ref)
65  {
66  if (_diagonal_mode)
67  cost[0] = x_k.transpose() * _S_diag * x_k - _gamma;
68  else
69  cost[0] = x_k.transpose() * _S * x_k - _gamma;
70  }
71  else
72  {
73  Eigen::VectorXd xd = x_k - _x_ref->getReferenceCached(k);
74  if (_diagonal_mode)
75  cost[0] = xd.transpose() * _S_diag * xd - _gamma;
76  else
77  cost[0] = xd.transpose() * _S * xd - _gamma;
78  }
79 }
80 
81 bool TerminalBall::checkParameters(int state_dim, int control_dim, FinalStageCost::ConstPtr final_stage_cost, std::stringstream* issues) const
82 {
83  bool success = true;
84 
86  {
87  if (_S.diagonal().size() != state_dim)
88  {
89  if (issues)
90  *issues << "TerminalBall: Diagonal matrix dimension of S (" << _S_diag.diagonal().size()
91  << ") does not match state vector dimension (" << state_dim << "); Please specify diagonal elements only." << std::endl;
92  success = false;
93  }
94  }
95  else
96  {
97  if (_S.rows() != state_dim || _S.cols() != state_dim)
98  {
99  if (issues)
100  *issues << "TerminalBall: Matrix dimension of S (" << _S.rows() << "x" << _S.cols() << ") does not match state vector dimension ("
101  << state_dim << "); Please specify " << (state_dim * state_dim) << " elements (Row-Major)." << std::endl;
102  success = false;
103  }
104  }
105 
106  return success;
107 }
108 
109 #ifdef MESSAGE_SUPPORT
110 bool TerminalBall::fromMessage(const messages::FinalStageConstraints& message, std::stringstream* issues)
111 {
112  const messages::TerminalBall& msg = message.terminal_ball();
113 
114  _diagonal_mode = msg.s_diagonal_only();
115 
116  if (_diagonal_mode)
117  {
118  if (!setWeightS(Eigen::Map<const Eigen::Matrix<double, -1, 1>>(msg.s().data(), msg.s_size()).asDiagonal()))
119  {
120  *issues << "TerminalBall: cannot set diagonal weight matrix S.\n";
121  return false;
122  }
123  }
124  else
125  {
126  if (!is_square(msg.s_size()))
127  {
128  *issues << "TerminalBall: weight matrix S is not square.\n";
129  return false;
130  }
131  int p = std::sqrt(msg.s_size());
132 
133  if (!setWeightS(Eigen::Map<const Eigen::Matrix<double, -1, -1, Eigen::RowMajor>>(msg.s().data(), p, p)) && issues)
134  {
135  *issues << "TerminalBall: cannot set weight matrix S.\n";
136  return false;
137  }
138  }
139 
140  // gamma
141  _gamma = msg.gamma();
142  return true;
143 }
144 
145 void TerminalBall::toMessage(messages::FinalStageConstraints& message) const
146 {
147  messages::TerminalBall* msg = message.mutable_terminal_ball();
148 
149  // weight matrix S
151  {
152  Eigen::VectorXd Sdiag = _S_diag.diagonal();
153  msg->mutable_s()->Resize(Sdiag.size(), 0);
154  Eigen::Map<Eigen::VectorXd>(msg->mutable_s()->mutable_data(), Sdiag.size()) = Sdiag;
155 
156  msg->set_s_diagonal_only(true);
157  }
158  else
159  {
160  msg->mutable_s()->Resize(_S.rows() * _S.cols(), 0);
161  Eigen::Map<Eigen::Matrix<double, -1, -1, Eigen::RowMajor>>(msg->mutable_s()->mutable_data(), _S.rows(), _S.cols()) = _S;
162 
163  msg->set_s_diagonal_only(false);
164  }
165 
166  // gamma
167  msg->set_gamma(_gamma);
168 }
169 #endif
170 
171 bool TerminalBallInheritFromCost::update(int n, double t, ReferenceTrajectoryInterface& xref, ReferenceTrajectoryInterface& uref,
172  ReferenceTrajectoryInterface* sref, bool single_dt, const Eigen::VectorXd& x0,
173  FinalStageCost::ConstPtr final_state_cost, StagePreprocessor::Ptr stage_preprocessor,
174  const std::vector<double>& dts, const DiscretizationGridInterface* grid)
175 {
176  // call parent update method
177  bool dimension_modified = TerminalBall::update(n, t, xref, uref, sref, single_dt, x0, final_state_cost, stage_preprocessor, dts, grid);
178 
179  BaseQuadraticFinalStateCost::ConstPtr quadratic_cost = std::dynamic_pointer_cast<const BaseQuadraticFinalStateCost>(final_state_cost);
180  if (quadratic_cost)
181  {
182  if (quadratic_cost->getWeightQf().rows() == 0)
183  {
184  PRINT_ERROR("TerminalBallInheritFromCost::update(): weight matrix obtained from terminal cost function has zero size!");
185  TerminalBall::setWeightS(Eigen::MatrixXd::Zero(xref.getDimension(), xref.getDimension()));
186  }
187  TerminalBall::setWeightS(quadratic_cost->getWeightQf());
188  }
189  else
190  {
191  PRINT_ERROR("TerminalBallInheritFromCost::update(): this constraint requires quadratic final cost! Setting final weight matrix to zero!");
192  TerminalBall::setWeightS(Eigen::MatrixXd::Zero(xref.getDimension(), xref.getDimension()));
193  }
194  return dimension_modified;
195 }
196 
198  Eigen::Ref<Eigen::VectorXd> cost) const
199 {
200  assert(cost.size() == getNonIntegralStateTermDimension(k));
201  assert(_S_diag.diagonal().size() == x_k.size());
202  assert(_S.rows() == x_k.size());
203 
204  if (_zero_x_ref)
205  {
206  if (_diagonal_mode)
207  cost[0] = x_k.transpose() * _S_diag * x_k - _gamma;
208  else
209  cost[0] = x_k.transpose() * _S * x_k - _gamma;
210  }
211  else
212  {
213  Eigen::VectorXd xd = x_k - _x_ref->getReferenceCached(k);
214  if (_diagonal_mode)
215  cost[0] = xd.transpose() * _S_diag * xd - _gamma;
216  else
217  cost[0] = xd.transpose() * _S * xd - _gamma;
218  }
219 }
220 
221 bool TerminalBallInheritFromCost::checkParameters(int state_dim, int control_dim, FinalStageCost::ConstPtr final_stage_cost,
222  std::stringstream* issues) const
223 {
224  bool success = true;
225 
226  BaseQuadraticFinalStateCost::ConstPtr quadratic_cost = std::dynamic_pointer_cast<const BaseQuadraticFinalStateCost>(final_stage_cost);
227  if (!quadratic_cost)
228  {
229  if (issues)
230  *issues << "TerminalBallInheritFromCost: This final cost requires a complementary quadratic final/terminal cost function." << std::endl;
231  success = false;
232  }
233 
234  // success = success && TerminalBall::checkParameters(state_dim, control_dim, final_stage_cost, issues);
235 
236  return success;
237 }
238 
239 #ifdef MESSAGE_SUPPORT
240 bool TerminalBallInheritFromCost::fromMessage(const messages::FinalStageConstraints& message, std::stringstream* issues)
241 {
242  const messages::TerminalBallInheritFromCost& msg = message.terminal_ball_from_cost();
243 
244  _gamma = msg.gamma();
245  return true;
246 }
247 
248 void TerminalBallInheritFromCost::toMessage(messages::FinalStageConstraints& message) const
249 {
250  messages::TerminalBallInheritFromCost* msg = message.mutable_terminal_ball_from_cost();
251  msg->set_gamma(msg->gamma());
252 }
253 #endif
254 
255 } // namespace corbo
sqrt
const EIGEN_DEVICE_FUNC SqrtReturnType sqrt() const
Definition: ArrayCwiseUnaryOps.h:152
corbo::TerminalBall::_gamma
double _gamma
Definition: final_state_constraints.h:132
Eigen::DiagonalMatrix< double, -1 >
corbo::StagePreprocessor::Ptr
std::shared_ptr< StagePreprocessor > Ptr
Definition: stage_preprocessor.h:66
Eigen::DiagonalBase::toDenseMatrix
EIGEN_DEVICE_FUNC DenseMatrixType toDenseMatrix() const
Definition: DiagonalMatrix.h:46
corbo::TerminalBall::_diagonal_mode
bool _diagonal_mode
Definition: final_state_constraints.h:137
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::ReferenceTrajectoryInterface::getReferenceCached
virtual const OutputVector & getReferenceCached(int k) const =0
final_state_constraints.h
Eigen::RowMajor
@ RowMajor
Definition: Constants.h:322
corbo::TerminalBall::_diagonal_mode_intentionally
bool _diagonal_mode_intentionally
Definition: final_state_constraints.h:138
corbo::TerminalBallInheritFromCost::getNonIntegralStateTermDimension
int getNonIntegralStateTermDimension(int k) const override
Definition: final_state_constraints.h:130
Eigen::EigenBase::size
EIGEN_DEVICE_FUNC Index size() const
Definition: EigenBase.h:66
corbo::FinalStageCost::ConstPtr
std::shared_ptr< const FinalStageCost > ConstPtr
Definition: stage_functions.h:176
corbo::TerminalBall::update
bool update(int n, double t, ReferenceTrajectoryInterface &xref, ReferenceTrajectoryInterface &uref, ReferenceTrajectoryInterface *sref, bool single_dt, const Eigen::VectorXd &x0, FinalStageCost::ConstPtr final_stage_cost, StagePreprocessor::Ptr stage_preprocessor, const std::vector< double > &dts, const DiscretizationGridInterface *) override
Definition: final_state_constraints.h:111
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::TerminalBallInheritFromCost::checkParameters
bool checkParameters(int state_dim, int control_dim, FinalStageCost::ConstPtr final_stage_cost, std::stringstream *issues) const override
Definition: final_state_constraints.cpp:243
corbo::TerminalBall::setWeightS
bool setWeightS(const Eigen::Ref< const Eigen::MatrixXd > &S)
Definition: final_state_constraints.cpp:57
corbo::TerminalBall::getNonIntegralStateTermDimension
int getNonIntegralStateTermDimension(int k) const override
Definition: final_state_constraints.h:100
corbo::TerminalBall::_S_diag
Eigen::DiagonalMatrix< double, -1 > _S_diag
Definition: final_state_constraints.h:131
matrix_utilities.h
corbo::TerminalBallInheritFromCost::update
bool update(int n, double t, ReferenceTrajectoryInterface &xref, ReferenceTrajectoryInterface &uref, ReferenceTrajectoryInterface *sref, bool single_dt, const Eigen::VectorXd &x0, FinalStageCost::ConstPtr final_stage_cost, StagePreprocessor::Ptr stage_preprocessor, const std::vector< double > &dts, const DiscretizationGridInterface *) override
Definition: final_state_constraints.cpp:193
Eigen::Map
A matrix or vector expression mapping an existing array of data.
Definition: Map.h:94
corbo::TerminalBall::_zero_x_ref
bool _zero_x_ref
Definition: final_state_constraints.h:135
corbo::TerminalBallInheritFromCost::computeNonIntegralStateTerm
void computeNonIntegralStateTerm(int k, const Eigen::Ref< const Eigen::VectorXd > &x_k, Eigen::Ref< Eigen::VectorXd > cost) const override
Definition: final_state_constraints.cpp:219
corbo::TerminalBall::checkParameters
bool checkParameters(int state_dim, int control_dim, FinalStageCost::ConstPtr final_stage_cost, std::stringstream *issues) const override
Definition: final_state_constraints.cpp:103
utilities.h
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
corbo::BaseQuadraticFinalStateCost::ConstPtr
std::shared_ptr< const BaseQuadraticFinalStateCost > ConstPtr
Definition: final_state_cost.h:86
corbo::TerminalBall::computeNonIntegralStateTerm
void computeNonIntegralStateTerm(int k, const Eigen::Ref< const Eigen::VectorXd > &x_k, Eigen::Ref< Eigen::VectorXd > cost) const override
Definition: final_state_constraints.cpp:82
corbo::TerminalBallInheritFromCost::_gamma
double _gamma
Definition: final_state_constraints.h:148
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: Matrix.h:178
n
PlainMatrixType mat * n
Definition: eigenvalues.cpp:41
corbo::TerminalBall::_x_ref
const ReferenceTrajectoryInterface * _x_ref
Definition: final_state_constraints.h:134
PRINT_ERROR
#define PRINT_ERROR(msg)
Print msg-stream as error msg.
Definition: console.h:173
corbo::TerminalBall::_S
Eigen::MatrixXd _S
Definition: final_state_constraints.h:130


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