levenberg_marquardt_dense.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 
27 #include <corbo-core/console.h>
28 
29 #include <Eigen/Cholesky>
30 
31 namespace corbo {
32 
33 bool LevenbergMarquardtDense::initialize(OptimizationProblemInterface* problem)
34 {
35  if (problem && !problem->isLeastSquaresProblem())
36  {
37  PRINT_ERROR("LevenbergMarquardtDense(): cannot handle non-least-squares objectives or LS objectives in non-LS form.");
38  return false;
39  }
40 
41  return true;
42 }
43 
44 SolverStatus LevenbergMarquardtDense::solve(OptimizationProblemInterface& problem, bool new_structure, bool new_run, double* obj_value)
45 {
46  if (obj_value) *obj_value = -1; // set to invalid first
47 
48  if (new_structure)
49  {
50  if (!problem.isLeastSquaresProblem())
51  {
52  PRINT_ERROR("LevenbergMarquardtDense(): cannot handle non-least-squares objectives or LS objectives in non-LS form.");
53  return SolverStatus::Error;
54  }
55 
56  // get dimension for the value/cost vector
57  _obj_dim = problem.getLsqObjectiveDimension();
58  _eq_dim = problem.getEqualityDimension();
59  _ineq_dim = problem.getInequalityDimension();
60  _finite_bounds_dim = problem.finiteCombinedBoundsDimension();
62  _param_dim = problem.getParameterDimension();
63 
64  if (_param_dim == 0)
65  {
66  PRINT_WARNING("LevenbergMarquardtDense: problem has zero dimension");
67  return SolverStatus::Error;
68  }
69 
70  _values.resize(_val_dim);
71  _jacobian.resize(_val_dim, _param_dim);
72  _jacobian.setZero();
74  _delta.resize(_param_dim);
75  _rhs.resize(_param_dim);
76  }
77 
78  // adapt weights
79  if (new_run)
80  resetWeights();
81  else
82  adaptWeights();
83 
84  // compute complete value vector
85  computeValues(problem);
86 
87  // compute jacobian
88  computeJacobian(problem);
89 
90  // construct quasi-newton hessian approximation
91  _hessian.noalias() = _jacobian.transpose() * _jacobian;
92 
93  // construct right-hand-side of the approxiamted linear system
94  _rhs.noalias() = _jacobian.transpose() * -_values;
95 
96  // convergence consts
97  constexpr const double eps1 = 1e-5;
98  constexpr const double eps2 = 1e-5;
99  constexpr const double eps3 = 1e-5;
100  constexpr const double eps4 = 0;
101 
102  // lm variables
103  unsigned int v = 2;
104  double tau = 1e-5;
105 
106  constexpr const double goodStepUpperScale = 2. / 3.;
107  constexpr const double goodStepLowerScale = 1. / 3.;
108 
109  bool stop = (_rhs.lpNorm<Eigen::Infinity>() <= eps1);
110 
111  double mu = tau * _hessian.diagonal().maxCoeff();
112  if (mu < 0) mu = 0;
113 
114  double rho = 0;
115 
116  // get old chi2
117  double chi2_old = _values.squaredNorm();
118  if (obj_value) *obj_value = chi2_old;
119 
120  // start levenberg marquardt optimization loop
121  for (int k = 0; k < _iterations; ++k)
122  {
123  do
124  {
125  // augment hessian diagonal with damping factor
126  _hessian.diagonal().array() += mu;
127 
128  // solve linear system
129  _delta = _hessian.ldlt().solve(_rhs);
130 
131  // if (delta.norm() <= eps2 * (x.norm() + eps2) stop = true; // x -> values of vertices, not constructed until now. modify check
132  if (_delta.norm() <= eps2)
133  stop = true;
134  else
135  {
136  // backup current parameter values
137  problem.backupParameters();
138 
139  // apply new delta/increment to vertices
140  problem.applyIncrement(_delta);
141 
142  // calculate new costs/values
143  computeValues(problem);
144 
145  // get new chi2
146  double chi2_new = _values.squaredNorm();
147 
148  rho = (chi2_old - chi2_new) / (_delta.transpose() * (mu * _delta + _rhs));
149 
150  if (rho > 0 && !std::isnan(chi2_new) && !std::isinf(chi2_new)) // adaptation of mu to find a sufficient descent step
151  {
152  stop = (std::sqrt(chi2_old) - std::sqrt(chi2_new) < eps4 * std::sqrt(chi2_old));
153 
154  // accept update and discard backup
155  problem.discardBackupParameters();
156 
157  if (!stop && k < _iterations - 1) // do not recalculate jacobian and hessian in the last iteration
158  {
159  // get new cost/value vector
160  // computeValues(problem); // redundant
161 
162  // calculate new jacobian
163  computeJacobian(problem);
164 
165  // get new hessian
166  _hessian.noalias() = _jacobian.transpose() * _jacobian;
167 
168  // calculate new right hand side
169  _rhs.noalias() = _jacobian.transpose() * -_values;
170 
171  stop = stop || (_rhs.lpNorm<Eigen::Infinity>() <= eps1);
172 
173  double alpha = std::min(goodStepUpperScale, 1 - std::pow((2 * rho - 1), 3));
174  double scaleFactor = std::max(goodStepLowerScale, alpha);
175  mu *= scaleFactor;
176  v = 2;
177  }
178 
179  chi2_old = chi2_new;
180  if (obj_value) *obj_value = chi2_old;
181  }
182  else
183  {
184  // restore from backup
185  problem.restoreBackupParameters(false);
186  // hessian.diagonal().array() -= mu; // this should be done here, but it works in the matlab version without for some
187  // time now.
188 
189  mu = mu * v;
190  v = 2 * v;
191  }
192  }
193  } while (rho <= 0 && !stop);
194  stop = (_values.norm() <= eps3);
195  }
196  return (stop || rho <= 0) ? SolverStatus::Converged
197  : SolverStatus::EarlyTerminated; // TODO(roesmann): proper solver status (especially w.r.t. rho)
198 }
199 
200 void LevenbergMarquardtDense::computeValues(OptimizationProblemInterface& problem)
201 {
202  int idx = 0;
203  if (_obj_dim > 0)
204  {
205  problem.computeValuesLsqObjective(_values.segment(idx, _obj_dim));
206  idx += _obj_dim;
207  }
208  if (_eq_dim > 0)
209  {
210  problem.computeValuesEquality(_values.segment(idx, _eq_dim));
211  _values.segment(idx, _eq_dim) *= _weight_eq;
212  idx += _eq_dim;
213  }
214  if (_ineq_dim > 0)
215  {
216  problem.computeValuesActiveInequality(_values.segment(idx, _ineq_dim), _weight_ineq);
217  idx += _ineq_dim;
218  }
219  if (_finite_bounds_dim > 0)
220  {
221  problem.computeDistanceFiniteCombinedBounds(_values.segment(idx, _finite_bounds_dim));
223  }
224 }
225 
226 void LevenbergMarquardtDense::computeJacobian(OptimizationProblemInterface& problem)
227 {
228  int idx = 0;
229  if (_obj_dim > 0)
230  {
231  problem.computeDenseJacobianLsqObjective(_jacobian.block(idx, 0, _obj_dim, _param_dim));
232  idx += _obj_dim;
233  }
234  if (_eq_dim > 0)
235  {
236  problem.computeDenseJacobianEqualities(_jacobian.block(idx, 0, _eq_dim, _param_dim));
237  _jacobian.block(idx, 0, _eq_dim, _param_dim) *= _weight_eq; // TODO(roesmann) include scalar multiplier to OptimizationProblemInterface
238  idx += _eq_dim;
239  }
240  if (_ineq_dim > 0)
241  {
242  // compute only for active inequalities in order to apply quadratic penalties
243  problem.computeDenseJacobianActiveInequalities(_jacobian.block(idx, 0, _ineq_dim, _param_dim), _weight_ineq);
244  idx += _ineq_dim;
245  }
246  if (_finite_bounds_dim > 0)
247  {
248  problem.computeDenseJacobianFiniteCombinedBounds(_jacobian.block(idx, 0, _finite_bounds_dim, _param_dim), _weight_bounds);
249  }
250 }
251 
252 void LevenbergMarquardtDense::setPenaltyWeights(double weight_eq, double weight_ineq, double weight_bounds)
253 {
254  _weight_init_eq = weight_eq;
255  _weight_init_ineq = weight_ineq;
256  _weight_init_bounds = weight_bounds;
257 
258  PRINT_WARNING_COND(_weight_init_eq > _weight_adapt_max_eq, "LevenbergMarquardtDense(): weight_eq > max_eq");
259  PRINT_WARNING_COND(_weight_init_ineq > _weight_adapt_max_ineq, "LevenbergMarquardtDense(): weight_ineq > max_ineq");
260  PRINT_WARNING_COND(_weight_init_bounds > _weight_adapt_max_bounds, "LevenbergMarquardtDense(): weight_bounds > max_bounds");
261 }
262 
263 void LevenbergMarquardtDense::setWeightAdapation(double factor_eq, double factor_ineq, double factor_bounds, double max_eq, double max_ineq,
264  double max_bounds)
265 {
266  _weight_adapt_factor_eq = factor_eq;
267  _weight_adapt_factor_ineq = factor_ineq;
268  _weight_adapt_factor_bounds = factor_bounds;
269  _weight_adapt_max_eq = max_eq;
270  _weight_adapt_max_ineq = max_ineq;
271  _weight_adapt_max_bounds = max_bounds;
272 }
273 
275 {
279 }
280 
282 {
285 
288 
291 }
292 
294 {
295  _param_dim = 0;
296  _obj_dim = 0;
297  _eq_dim = 0;
298  _ineq_dim = 0;
299  _finite_bounds_dim = 0;
300  _val_dim = 0;
301 
305 }
306 
307 #ifdef MESSAGE_SUPPORT
308 void LevenbergMarquardtDense::toMessage(corbo::messages::NlpSolver& message) const
309 {
310  message.mutable_levenberg_marquardt_dense()->set_iterations(_iterations);
311  message.mutable_levenberg_marquardt_dense()->set_weight_eq(_weight_init_eq);
312  message.mutable_levenberg_marquardt_dense()->set_weight_ineq(_weight_init_ineq);
313  message.mutable_levenberg_marquardt_dense()->set_weight_bounds(_weight_init_bounds);
314  message.mutable_levenberg_marquardt_dense()->set_weight_eq_factor(_weight_adapt_factor_eq);
315  message.mutable_levenberg_marquardt_dense()->set_weight_ineq_factor(_weight_adapt_factor_ineq);
316  message.mutable_levenberg_marquardt_dense()->set_weight_bounds_factor(_weight_adapt_factor_bounds);
317  message.mutable_levenberg_marquardt_dense()->set_weight_eq_max(_weight_adapt_max_eq);
318  message.mutable_levenberg_marquardt_dense()->set_weight_ineq_max(_weight_adapt_max_ineq);
319  message.mutable_levenberg_marquardt_dense()->set_weight_bounds_max(_weight_adapt_max_bounds);
320 }
321 
322 void LevenbergMarquardtDense::fromMessage(const corbo::messages::NlpSolver& message, std::stringstream* issues)
323 {
324  _iterations = message.levenberg_marquardt_dense().iterations();
325  _weight_init_eq = message.levenberg_marquardt_dense().weight_eq();
326  _weight_init_ineq = message.levenberg_marquardt_dense().weight_ineq();
327  _weight_init_bounds = message.levenberg_marquardt_dense().weight_bounds();
328  _weight_adapt_factor_eq = message.levenberg_marquardt_dense().weight_eq_factor();
329  _weight_adapt_factor_ineq = message.levenberg_marquardt_dense().weight_ineq_factor();
330  _weight_adapt_factor_bounds = message.levenberg_marquardt_dense().weight_bounds_factor();
331  _weight_adapt_max_eq = message.levenberg_marquardt_dense().weight_eq_max();
332  _weight_adapt_max_ineq = message.levenberg_marquardt_dense().weight_ineq_max();
333  _weight_adapt_max_bounds = message.levenberg_marquardt_dense().weight_bounds_max();
334 }
335 #endif
336 
337 } // namespace corbo
corbo::LevenbergMarquardtDense::_weight_init_bounds
double _weight_init_bounds
Definition: levenberg_marquardt_dense.h:157
sqrt
const EIGEN_DEVICE_FUNC SqrtReturnType sqrt() const
Definition: ArrayCwiseUnaryOps.h:152
PRINT_WARNING
#define PRINT_WARNING(msg)
Print msg-stream.
Definition: console.h:145
corbo::LevenbergMarquardtDense::_val_dim
int _val_dim
Definition: levenberg_marquardt_dense.h:173
corbo::LevenbergMarquardtDense::_iterations
int _iterations
Definition: levenberg_marquardt_dense.h:153
alpha
RealScalar alpha
Definition: level1_cplx_impl.h:125
corbo::LevenbergMarquardtDense::initialize
bool initialize(OptimizationProblemInterface *problem=nullptr) override
Initialize the solver w.r.t. a given optimization problem.
Definition: levenberg_marquardt_dense.cpp:55
Eigen::half_impl::pow
EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half pow(const half &a, const half &b)
Definition: Half.h:477
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::SolverStatus::Converged
@ Converged
corbo::LevenbergMarquardtDense::_delta
Eigen::VectorXd _delta
Definition: levenberg_marquardt_dense.h:178
corbo::LevenbergMarquardtDense::_weight_init_eq
double _weight_init_eq
Definition: levenberg_marquardt_dense.h:155
levenberg_marquardt_dense.h
corbo::LevenbergMarquardtDense::computeJacobian
void computeJacobian(OptimizationProblemInterface &problem)
Compute overall jacobian including constraint approximation.
Definition: levenberg_marquardt_dense.cpp:248
Eigen::half_impl::isinf
EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool() isinf(const half &a)
Definition: Half.h:431
corbo::LevenbergMarquardtDense::_weight_adapt_max_eq
double _weight_adapt_max_eq
Definition: levenberg_marquardt_dense.h:163
corbo::LevenbergMarquardtDense::_eq_dim
int _eq_dim
Definition: levenberg_marquardt_dense.h:170
console.h
corbo::LevenbergMarquardtDense::_weight_bounds
double _weight_bounds
Definition: levenberg_marquardt_dense.h:183
corbo::SolverStatus
SolverStatus
Definition: optimization/include/corbo-optimization/types.h:52
corbo::SolverStatus::EarlyTerminated
@ EarlyTerminated
corbo::LevenbergMarquardtDense::setPenaltyWeights
void setPenaltyWeights(double weight_eq, double weight_ineq, double weight_bounds)
Define penalty weights (equality constraints, inequality constraints, bounds)
Definition: levenberg_marquardt_dense.cpp:274
corbo::SolverStatus::Error
@ Error
corbo::LevenbergMarquardtDense::adaptWeights
void adaptWeights()
Perform single weight adapation step.
Definition: levenberg_marquardt_dense.cpp:303
corbo::LevenbergMarquardtDense::_weight_ineq
double _weight_ineq
Definition: levenberg_marquardt_dense.h:182
corbo::LevenbergMarquardtDense::setWeightAdapation
void setWeightAdapation(double factor_eq, double factor_ineq, double factor_bounds, double max_eq, double max_ineq, double max_bounds)
Set parameters for weight adaptation (refer to the class description); set factors to 1 in order to d...
Definition: levenberg_marquardt_dense.cpp:285
PRINT_WARNING_COND
#define PRINT_WARNING_COND(cond, msg)
Print msg-stream only if cond == true.
Definition: console.h:159
corbo::LevenbergMarquardtDense::_weight_eq
double _weight_eq
Definition: levenberg_marquardt_dense.h:181
corbo::LevenbergMarquardtDense::_finite_bounds_dim
int _finite_bounds_dim
Definition: levenberg_marquardt_dense.h:172
corbo::LevenbergMarquardtDense::clear
void clear() override
Clear internal caches.
Definition: levenberg_marquardt_dense.cpp:315
corbo::LevenbergMarquardtDense::_hessian
Eigen::MatrixXd _hessian
Definition: levenberg_marquardt_dense.h:177
corbo::LevenbergMarquardtDense::_rhs
Eigen::VectorXd _rhs
Definition: levenberg_marquardt_dense.h:179
corbo::LevenbergMarquardtDense::_weight_adapt_max_bounds
double _weight_adapt_max_bounds
Definition: levenberg_marquardt_dense.h:165
corbo::LevenbergMarquardtDense::computeValues
void computeValues(OptimizationProblemInterface &problem)
Compute overall value vector including constraint approximation.
Definition: levenberg_marquardt_dense.cpp:222
corbo::LevenbergMarquardtDense::_weight_init_ineq
double _weight_init_ineq
Definition: levenberg_marquardt_dense.h:156
corbo::LevenbergMarquardtDense::_weight_adapt_max_ineq
double _weight_adapt_max_ineq
Definition: levenberg_marquardt_dense.h:164
corbo::LevenbergMarquardtDense::_values
Eigen::VectorXd _values
Definition: levenberg_marquardt_dense.h:175
corbo::LevenbergMarquardtDense::_weight_adapt_factor_ineq
double _weight_adapt_factor_ineq
Definition: levenberg_marquardt_dense.h:160
corbo::LevenbergMarquardtDense::_ineq_dim
int _ineq_dim
Definition: levenberg_marquardt_dense.h:171
corbo::LevenbergMarquardtDense::_obj_dim
int _obj_dim
Definition: levenberg_marquardt_dense.h:169
min
#define min(a, b)
Definition: datatypes.h:19
corbo::LevenbergMarquardtDense::_weight_adapt_factor_bounds
double _weight_adapt_factor_bounds
Definition: levenberg_marquardt_dense.h:161
corbo::LevenbergMarquardtDense::_jacobian
Eigen::MatrixXd _jacobian
Definition: levenberg_marquardt_dense.h:176
max
#define max(a, b)
Definition: datatypes.h:20
corbo::LevenbergMarquardtDense::solve
SolverStatus solve(OptimizationProblemInterface &problem, bool new_structure=true, bool new_run=true, double *obj_value=nullptr) override
Solve the provided optimization problem.
Definition: levenberg_marquardt_dense.cpp:66
Eigen::Infinity
const int Infinity
Definition: Constants.h:31
PRINT_ERROR
#define PRINT_ERROR(msg)
Print msg-stream as error msg.
Definition: console.h:173
corbo::LevenbergMarquardtDense::_weight_adapt_factor_eq
double _weight_adapt_factor_eq
Definition: levenberg_marquardt_dense.h:159
Eigen::half_impl::isnan
EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool() isnan(const half &a)
Definition: Half.h:434
corbo::LevenbergMarquardtDense::_param_dim
int _param_dim
Definition: levenberg_marquardt_dense.h:168
corbo::LevenbergMarquardtDense::resetWeights
void resetWeights()
Reset weights to their original values.
Definition: levenberg_marquardt_dense.cpp:296


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