nlp_solver_ipopt.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 
25 #ifdef IPOPT
26 
28 
29 #include <corbo-core/console.h>
30 
31 namespace corbo {
32 
33 bool SolverIpopt::initialize(OptimizationProblemInterface* /*problem*/)
34 {
35  if (_initialized) return true;
36 
37  _ipopt_nlp = new IpoptWrapper(this);
38  _ipopt_app = IpoptApplicationFactory();
39 
40  if (!_param_msg_received) // TODO(roesmann) we need a default paramerter mechanism with protobuf!
41  {
42  setRelTolerance(1e-3);
43 
44  setMuStrategyAdaptive(true);
45  setWarmStartInitPoint(true);
46  setNlpAutoScaling(true);
47  setPrintLevel(2); // Default = 5
48 
49  /*
50  #ifdef __unix__
51  if (!setLinearSolver(LinearSolver::MA57)) setLinearSolver(LinearSolver::MUMPS);
52  #else
53  setLinearSolver(LinearSolver::MUMPS); // the default solver on systems other than linux is MUMPS
54  // since setLinearSolver() returns true, even if MA57 is not available
55  #endif
56  */
57  // _ipopt_app->Options()->SetStringValue("output_file", "ipopt.out");
58 
59  // _ipopt_app->Options()->SetStringValue("hessian_approximation", "exact"); // or "limited-memory"
60 
61  // _ipopt_app->Options()->SetStringValue("derivative_test", "second-order"); // "none", "first-order", "second-order", "only-second-order"
62  // _ipopt_app->Options()->SetNumericValue("derivative_test_tol", 1e-3);
63 
64  Ipopt::ApplicationReturnStatus status;
65  status = _ipopt_app->Initialize();
66  if (status != Ipopt::Solve_Succeeded)
67  {
68  PRINT_INFO("SolverIPOPT(): Error during IPOPT initialization!");
69  return false;
70  }
71  }
72 
73  static bool copyright_printed = false;
74  if (!copyright_printed)
75  {
76  _ipopt_app->PrintCopyrightMessage();
77  copyright_printed = true;
78  }
79 
80  _initialized = true;
81  return true;
82 }
83 
84 SolverStatus SolverIpopt::solve(OptimizationProblemInterface& problem, bool new_structure, bool new_run, double* obj_value)
85 {
86  if (!_initialized)
87  {
88  if (!initialize(&problem)) return SolverStatus::Error;
89  }
90 
91  _ipopt_nlp->setOptimizationProblem(problem);
92 
93  if (new_structure)
94  {
95  _nnz_jac_constraints = problem.computeCombinedSparseJacobiansNNZ(false, true, true);
96 
97  problem.computeSparseHessiansNNZ(_nnz_hes_obj, _nnz_hes_eq, _nnz_hes_ineq, true);
98  _nnz_h_lagrangian = _nnz_hes_obj + _nnz_hes_eq + _nnz_hes_ineq;
99 
100  _lambda_cache.resize(problem.getEqualityDimension() + problem.getInequalityDimension());
101  _lambda_cache.setZero();
102 
103  _zl_cache.resize(problem.getParameterDimension());
104  _zl_cache.setZero();
105 
106  _zu_cache.resize(problem.getParameterDimension());
107  _zu_cache.setZero();
108 
109  // set max number of iterations
110  _ipopt_app->Options()->SetIntegerValue("max_iter", _iterations); // max_cpu_time // TODO(roesmann) parameter for number of iterations
111 
112  // Set bfgs method
113  // if (cfg->optim.solver.nonlin_prog.hessian.hessian_method == HessianMethod::BFGS)
114  // _ipopt_app->Options()->SetStringValue("hessian_approximation", "limited-memory");
115  // else
116  // _ipopt_app->Options()->SetStringValue("hessian_approximation", "exact");
117  }
118 
119  if (_max_cpu_time > 0)
120  _ipopt_app->Options()->SetNumericValue("max_cpu_time", _max_cpu_time);
121  else if (_max_cpu_time == 0)
122  _ipopt_app->Options()->SetNumericValue("max_cpu_time", 10e6);
123 
124  Ipopt::ApplicationReturnStatus ipopt_status;
125  if (new_structure)
126  ipopt_status = _ipopt_app->OptimizeTNLP(_ipopt_nlp);
127  else
128  ipopt_status = _ipopt_app->ReOptimizeTNLP(_ipopt_nlp);
129 
130  if (obj_value) *obj_value = _last_obj_value;
131 
132  return convertIpoptToNlpSolverStatus(ipopt_status);
133 }
134 
135 bool SolverIpopt::setLinearSolver(LinearSolver solver_type)
136 {
137  if (!Ipopt::IsValid(_ipopt_app)) return false;
138 
139  bool success = false;
140 
141  switch (solver_type)
142  {
143  case LinearSolver::MUMPS:
144  success = _ipopt_app->Options()->SetStringValue("linear_solver", "mumps");
145  break;
146  case LinearSolver::MA27:
147  success = _ipopt_app->Options()->SetStringValue("linear_solver", "ma27");
148  break;
149  case LinearSolver::MA57:
150  success = _ipopt_app->Options()->SetStringValue("linear_solver", "ma57");
151  break;
152  case LinearSolver::MA77:
153  success = _ipopt_app->Options()->SetStringValue("linear_solver", "ma77");
154  break;
155  case LinearSolver::MA86:
156  success = _ipopt_app->Options()->SetStringValue("linear_solver", "ma86");
157  break;
158  case LinearSolver::MA97:
159  success = _ipopt_app->Options()->SetStringValue("linear_solver", "ma97");
160  break;
161  default:
162  success = false;
163  }
164 
165  if (success)
166  {
167  _current_lin_solver = solver_type;
168  return true;
169  }
170  return false;
171 }
172 
173 SolverIpopt::LinearSolver SolverIpopt::getLinearSolver() const
174 {
175  if (!Ipopt::IsValid(_ipopt_app)) return LinearSolver::NO_SOLVER;
176 
177  std::string linear_solver;
178  if (!_ipopt_app->Options()->GetStringValue("linear_solver", linear_solver, "")) return LinearSolver::NO_SOLVER;
179 
180  if (!linear_solver.compare("mumps")) return LinearSolver::MUMPS;
181  if (!linear_solver.compare("ma27")) return LinearSolver::MA27;
182  if (!linear_solver.compare("ma57")) return LinearSolver::MA57;
183  if (!linear_solver.compare("ma77")) return LinearSolver::MA77;
184  if (!linear_solver.compare("ma86")) return LinearSolver::MA86;
185  if (!linear_solver.compare("ma97")) return LinearSolver::MA97;
186 
188 }
189 
190 bool SolverIpopt::setLinearSolverByName(const std::string& solver_name)
191 {
192  if (!Ipopt::IsValid(_ipopt_app)) return false;
193  return _ipopt_app->Options()->SetStringValue("linear_solver", solver_name);
194 }
195 
196 std::string SolverIpopt::getLinearSolverByName()
197 {
198  if (!Ipopt::IsValid(_ipopt_app)) return "";
199  std::string linear_solver;
200  if (!_ipopt_app->Options()->GetStringValue("linear_solver", linear_solver, "")) return "";
201  return linear_solver;
202 }
203 
204 bool SolverIpopt::setRelTolerance(double tolerance) { return _ipopt_app->Options()->SetNumericValue("tol", tolerance); }
205 double SolverIpopt::getRelTolerance() const
206 {
207  double val = CORBO_INF_DBL;
208  _ipopt_app->Options()->GetNumericValue("tol", val, "");
209  return val;
210 }
211 
212 bool SolverIpopt::setDualInfTolerance(double tolerance) { return _ipopt_app->Options()->SetNumericValue("dual_inf_tol", tolerance); }
213 double SolverIpopt::getDualInfTolerance() const
214 {
215  double val = CORBO_INF_DBL;
216  _ipopt_app->Options()->GetNumericValue("dual_inf_tol", val, "");
217  return val;
218 }
219 
220 bool SolverIpopt::setConstrViolTolerance(double tolerance) { return _ipopt_app->Options()->SetNumericValue("constr_viol_tol", tolerance); }
221 double SolverIpopt::getConstrViolTolerance() const
222 {
223  double val = CORBO_INF_DBL;
224  _ipopt_app->Options()->GetNumericValue("constr_viol_tol", val, "");
225  return val;
226 }
227 
228 bool SolverIpopt::setComplInfTolerance(double tolerance) { return _ipopt_app->Options()->SetNumericValue("compl_inf_tol", tolerance); }
229 double SolverIpopt::getComplInfTolerance() const
230 {
231  double val = CORBO_INF_DBL;
232  _ipopt_app->Options()->GetNumericValue("compl_inf_tol", val, "");
233  return val;
234 }
235 
236 bool SolverIpopt::setMuStrategyAdaptive(bool enabled)
237 {
238  if (enabled) return _ipopt_app->Options()->SetStringValue("mu_strategy", "adaptive");
239  return _ipopt_app->Options()->SetStringValue("mu_strategy", "monotone");
240 }
241 bool SolverIpopt::isMuStrategyAdaptive() const
242 {
243  std::string opt;
244  _ipopt_app->Options()->GetStringValue("mu_strategy", opt, "");
245  return opt.compare("adaptive") == 0 ? true : false;
246 }
247 
248 bool SolverIpopt::setHessianApproxExact(bool enabled)
249 {
250  if (enabled) return _ipopt_app->Options()->SetStringValue("hessian_approximation", "exact");
251  return _ipopt_app->Options()->SetStringValue("hessian_approximation", "limited-memory");
252 }
253 bool SolverIpopt::isHessianApproxExact() const
254 {
255  std::string opt;
256  _ipopt_app->Options()->GetStringValue("hessian_approximation", opt, "");
257  return opt.compare("exact") == 0 ? true : false;
258 }
259 
260 bool SolverIpopt::setWarmStartInitPoint(bool enabled)
261 {
262  if (enabled) return _ipopt_app->Options()->SetStringValue("warm_start_init_point", "yes");
263  return _ipopt_app->Options()->SetStringValue("warm_start_init_point", "no");
264 }
265 bool SolverIpopt::isWarmStartInitPoint() const
266 {
267  std::string opt;
268  _ipopt_app->Options()->GetStringValue("warm_start_init_point", opt, "");
269  return opt.compare("yes") == 0 ? true : false;
270 }
271 
272 bool SolverIpopt::setMehrotraAlgorithm(bool enabled)
273 {
274  if (enabled) return _ipopt_app->Options()->SetStringValue("mehrotra_algorithm", "yes");
275  return _ipopt_app->Options()->SetStringValue("mehrotra_algorithm", "no");
276 }
277 bool SolverIpopt::isMehrotraAlgorithm() const
278 {
279  std::string opt;
280  _ipopt_app->Options()->GetStringValue("mehrotra_algorithm", opt, "");
281  return opt.compare("yes") == 0 ? true : false;
282 }
283 
284 bool SolverIpopt::setPrintLevel(int print_level) { return _ipopt_app->Options()->SetIntegerValue("print_level", print_level); } // level 0-5
285 int SolverIpopt::getPrintLevel() const
286 {
287  int val = -1;
288  _ipopt_app->Options()->GetIntegerValue("print_level", val, "");
289  return val;
290 }
291 
292 bool SolverIpopt::setNlpAutoScaling(bool enabled)
293 {
294  if (enabled) return _ipopt_app->Options()->SetStringValue("nlp_scaling_method", "gradient-based");
295  return _ipopt_app->Options()->SetStringValue("nlp_scaling_method", "none");
296 }
297 bool SolverIpopt::isNlpAutoScaling() const
298 {
299  std::string opt;
300  _ipopt_app->Options()->GetStringValue("nlp_scaling_method", opt, "");
301  return opt.compare("gradient-based") == 0 ? true : false;
302 }
303 
304 bool SolverIpopt::setCheckDerivativesForNan(bool enabled)
305 {
306  if (enabled) return _ipopt_app->Options()->SetStringValue("check_derivatives_for_naninf", "yes");
307  return _ipopt_app->Options()->SetStringValue("check_derivatives_for_naninf", "no");
308 }
309 bool SolverIpopt::isCheckDerivativesForNan() const
310 {
311  std::string opt;
312  _ipopt_app->Options()->GetStringValue("check_derivatives_for_naninf", opt, "");
313  return opt.compare("yes") == 0 ? true : false;
314 }
315 
316 bool SolverIpopt::setDerivativeTest(bool first_order, bool second_order)
317 {
318  _ipopt_app->Options()->SetNumericValue("derivative_test_perturbation", 6e-3);
319  _ipopt_app->Options()->SetNumericValue("derivative_test_tol", 1e-3);
320 
321  if (first_order && second_order)
322  return _ipopt_app->Options()->SetStringValue("derivative_test", "second-order");
323  else if (first_order)
324  return _ipopt_app->Options()->SetStringValue("derivative_test", "first-order");
325  else if (second_order)
326  return _ipopt_app->Options()->SetStringValue("derivative_test", "only-second-order");
327  return _ipopt_app->Options()->SetStringValue("derivative_test", "none");
328 }
329 void SolverIpopt::isDerivativeTest(bool& first_order, bool& second_order) const
330 {
331  std::string opt;
332  _ipopt_app->Options()->GetStringValue("derivative_test", opt, "");
333  if (opt.compare("second-order") == 0)
334  {
335  first_order = true;
336  second_order = true;
337  }
338  else if (opt.compare("first-order") == 0)
339  {
340  first_order = true;
341  second_order = false;
342  }
343  else if (opt.compare("fonly-second-order") == 0)
344  {
345  first_order = false;
346  second_order = true;
347  }
348  else
349  {
350  first_order = false;
351  second_order = false;
352  }
353 }
354 
355 bool SolverIpopt::setIpoptOptionString(const std::string& param, const std::string& option)
356 {
357  if (!Ipopt::IsValid(_ipopt_app)) return false;
358  return _ipopt_app->Options()->SetStringValue(param, option);
359 }
360 
361 bool SolverIpopt::setIpoptOptionInt(const std::string& param, int option)
362 {
363  if (!Ipopt::IsValid(_ipopt_app)) return false;
364  return _ipopt_app->Options()->SetIntegerValue(param, option);
365 }
366 
367 bool SolverIpopt::setIpoptOptionNumeric(const std::string& param, double option)
368 {
369  if (!Ipopt::IsValid(_ipopt_app)) return false;
370  return _ipopt_app->Options()->SetNumericValue(param, option);
371 }
372 
373 SolverStatus SolverIpopt::convertIpoptToNlpSolverStatus(Ipopt::ApplicationReturnStatus ipopt_status) const
374 {
375  switch (ipopt_status)
376  {
377  case Ipopt::Solve_Succeeded:
378  case Ipopt::Solved_To_Acceptable_Level:
379  {
381  }
382  case Ipopt::Search_Direction_Becomes_Too_Small:
383  case Ipopt::User_Requested_Stop:
384  case Ipopt::Feasible_Point_Found:
385  case Ipopt::Maximum_Iterations_Exceeded:
386  {
388  }
389  case Ipopt::Infeasible_Problem_Detected:
390  case Ipopt::Diverging_Iterates:
391  case Ipopt::Restoration_Failed:
392  case Ipopt::Not_Enough_Degrees_Of_Freedom:
393  case Ipopt::Invalid_Problem_Definition:
394  {
396  }
397  default:
398  {
399  }
400  };
401  return SolverStatus::Error;
402 }
403 
404 void SolverIpopt::clear()
405 {
406  _last_obj_value = -1;
407 
408  _nnz_jac_constraints = 0;
409  _nnz_h_lagrangian = 0;
410  _nnz_hes_obj = 0;
411  _nnz_hes_eq = 0;
412  _nnz_hes_ineq = 0;
413 
414  // the initialize() function does not fill any problem dependent caches, so let's keep it initialized...
415  // _initialized = false;
416  // _ipopt_nlp = nullptr;
417  // _ipopt_app = nullptr;
418 }
419 
420 #ifdef MESSAGE_SUPPORT
421 void SolverIpopt::toMessage(corbo::messages::NlpSolver& message) const
422 {
423  message.mutable_solver_ipopt()->set_iterations(getIterations());
424  message.mutable_solver_ipopt()->set_max_cpu_time(getMaxCpuTime());
425 
426  switch (getLinearSolver())
427  {
428  case LinearSolver::MUMPS:
429  {
430  message.mutable_solver_ipopt()->set_linear_solver(corbo::messages::SolverIpopt::MUMPS);
431  break;
432  }
433  case LinearSolver::MA27:
434  {
435  message.mutable_solver_ipopt()->set_linear_solver(corbo::messages::SolverIpopt::MA27);
436  break;
437  }
438  case LinearSolver::MA57:
439  {
440  message.mutable_solver_ipopt()->set_linear_solver(corbo::messages::SolverIpopt::MA57);
441  break;
442  }
443  case LinearSolver::MA77:
444  {
445  message.mutable_solver_ipopt()->set_linear_solver(corbo::messages::SolverIpopt::MA77);
446  break;
447  }
448  case LinearSolver::MA86:
449  {
450  message.mutable_solver_ipopt()->set_linear_solver(corbo::messages::SolverIpopt::MA86);
451  break;
452  }
453  case LinearSolver::MA97:
454  {
455  message.mutable_solver_ipopt()->set_linear_solver(corbo::messages::SolverIpopt::MA97);
456  break;
457  }
458  default:
459  PRINT_ERROR("SolverIpopt::toMessage(): selected linear solver is currently not included in message export.");
460  }
461 
462  message.mutable_solver_ipopt()->set_rel_tolerance(getRelTolerance());
463  message.mutable_solver_ipopt()->set_adaptive_mu_strategy(isMuStrategyAdaptive());
464  message.mutable_solver_ipopt()->set_exact_hessian_approx(isHessianApproxExact());
465  message.mutable_solver_ipopt()->set_mehrotra_algorithm(isMehrotraAlgorithm());
466  message.mutable_solver_ipopt()->set_warm_start_init_point(isWarmStartInitPoint());
467  message.mutable_solver_ipopt()->set_nlp_auto_scaling(isNlpAutoScaling());
468  message.mutable_solver_ipopt()->set_print_level(getPrintLevel());
469  message.mutable_solver_ipopt()->set_cache_first_order_derivatives(_cache_first_order_derivatives);
470  message.mutable_solver_ipopt()->set_check_derivatives_for_naninf(isCheckDerivativesForNan());
471  bool check_first_order = false;
472  bool check_second_order = false;
473  isDerivativeTest(check_first_order, check_second_order);
474  message.mutable_solver_ipopt()->set_derivative_test_first_order(check_first_order);
475  message.mutable_solver_ipopt()->set_derivative_test_second_order(check_second_order);
476 }
477 
478 void SolverIpopt::fromMessage(const corbo::messages::NlpSolver& message, std::stringstream* issues)
479 {
480  if (!_initialized) initialize(); // we need valid objects // TODO(roesmann): this is not nice and not consistent in the project
481 
482  setIterations(message.solver_ipopt().iterations());
483  setMaxCpuTime(message.solver_ipopt().max_cpu_time());
484 
485  switch (message.solver_ipopt().linear_solver())
486  {
487  case corbo::messages::SolverIpopt::MUMPS:
488  {
489  if (!setLinearSolver(LinearSolver::MUMPS) && issues)
490  *issues << "LinearSolver::MUMPS: not supported with current IPOPT installation." << std::endl;
491  break;
492  }
493  case corbo::messages::SolverIpopt::MA27:
494  {
495  if (!setLinearSolver(LinearSolver::MA27) && issues)
496  *issues << "LinearSolver::MA27: not supported with current IPOPT installation." << std::endl;
497  break;
498  }
499  case corbo::messages::SolverIpopt::MA57:
500  {
501  if (!setLinearSolver(LinearSolver::MA57) && issues)
502  *issues << "LinearSolver::MA57: not supported with current IPOPT installation." << std::endl;
503  break;
504  }
505  case corbo::messages::SolverIpopt::MA77:
506  {
507  if (!setLinearSolver(LinearSolver::MA77) && issues)
508  *issues << "LinearSolver::MA77: not supported with current IPOPT installation." << std::endl;
509  break;
510  }
511  case corbo::messages::SolverIpopt::MA86:
512  {
513  if (!setLinearSolver(LinearSolver::MA86) && issues)
514  *issues << "LinearSolver::MA86: not supported with current IPOPT installation" << std::endl;
515  break;
516  }
517  case corbo::messages::SolverIpopt::MA97:
518  {
519  if (!setLinearSolver(LinearSolver::MA97) && issues)
520  *issues << "LinearSolver::MA97: not supported with current IPOPT installation." << std::endl;
521  break;
522  }
523  default:
524  {
525  if (issues) *issues << "SolverIpopt::fromMessage(): selected linear solver is currently not supported." << std::endl;
526  }
527  }
528 
529  if (!setRelTolerance(message.solver_ipopt().rel_tolerance()) && issues) *issues << "setRelTolerance() failed." << std::endl;
530  if (!setMuStrategyAdaptive(message.solver_ipopt().adaptive_mu_strategy()) && issues) *issues << "setMuStrategyAdaptive() failed." << std::endl;
531  if (!setHessianApproxExact(message.solver_ipopt().exact_hessian_approx()) && issues) *issues << "setHessianApproxExact() failed." << std::endl;
532  if (!setMehrotraAlgorithm(message.solver_ipopt().mehrotra_algorithm()) && issues) *issues << "setMehrotraAlgorithm() failed." << std::endl;
533  if (!setWarmStartInitPoint(message.solver_ipopt().warm_start_init_point()) && issues) *issues << "setWarmStartInitPoint() failed." << std::endl;
534  if (!setNlpAutoScaling(message.solver_ipopt().nlp_auto_scaling()) && issues) *issues << "setNlpAutoScaling() failed." << std::endl;
535  if (!setPrintLevel(message.solver_ipopt().print_level()) && issues) *issues << "setPrintLevel() failed." << std::endl;
536 
537  if (!setCheckDerivativesForNan(message.solver_ipopt().check_derivatives_for_naninf()) && issues)
538  *issues << "setCheckDerivativesForNan() failed." << std::endl;
539 
540  bool check_first_order = message.solver_ipopt().derivative_test_first_order();
541  bool check_second_order = message.solver_ipopt().derivative_test_second_order();
542  if (!setDerivativeTest(check_first_order, check_second_order) && issues) *issues << "setDerivativeTest() failed." << std::endl;
543 
544  _cache_first_order_derivatives = message.solver_ipopt().cache_first_order_derivatives();
545 
546  Ipopt::ApplicationReturnStatus status;
547  status = _ipopt_app->Initialize();
548  if (status != Ipopt::Solve_Succeeded)
549  {
550  if (issues)
551  *issues
552  << "SolverIpopt::fromMessage(): Error during IPOPT initialization! Maybe some parameters are not supported with current installation";
554  "SolverIpopt::fromMessage(): Error during IPOPT initialization! Maybe some parameters are not supported with current installation");
555  }
556 
557  _param_msg_received = true;
558 }
559 #endif
560 
561 } // namespace corbo
562 
563 #endif // IPOPT
void clear() override
Clear internal caches.
SolverStatus solve(OptimizationProblemInterface &problem, bool new_structure=true, bool new_run=true, double *obj_value=nullptr) override
Solve the provided optimization problem.
#define PRINT_WARNING(msg)
Print msg-stream.
Definition: console.h:145
bool initialize(OptimizationProblemInterface *problem=nullptr) override
Initialize the solver w.r.t. a given optimization problem.
constexpr const double CORBO_INF_DBL
Representation for infinity (double version)
#define PRINT_INFO(msg)
Print msg-stream.
Definition: console.h:117
#define PRINT_ERROR(msg)
Print msg-stream as error msg.
Definition: console.h:173


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Mon Feb 28 2022 22:07:06