35 if (_initialized)
return true;
37 _ipopt_nlp =
new IpoptWrapper(
this);
38 _ipopt_app = IpoptApplicationFactory();
40 if (!_param_msg_received)
42 setRelTolerance(1e-3);
44 setMuStrategyAdaptive(
true);
45 setWarmStartInitPoint(
true);
46 setNlpAutoScaling(
true);
64 Ipopt::ApplicationReturnStatus status;
65 status = _ipopt_app->Initialize();
66 if (status != Ipopt::Solve_Succeeded)
68 PRINT_INFO(
"SolverIPOPT(): Error during IPOPT initialization!");
73 static bool copyright_printed =
false;
74 if (!copyright_printed)
76 _ipopt_app->PrintCopyrightMessage();
77 copyright_printed =
true;
91 _ipopt_nlp->setOptimizationProblem(problem);
95 _nnz_jac_constraints = problem.computeCombinedSparseJacobiansNNZ(
false,
true,
true);
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;
100 _lambda_cache.resize(problem.getEqualityDimension() + problem.getInequalityDimension());
101 _lambda_cache.setZero();
103 _zl_cache.resize(problem.getParameterDimension());
106 _zu_cache.resize(problem.getParameterDimension());
110 _ipopt_app->Options()->SetIntegerValue(
"max_iter", _iterations);
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);
124 Ipopt::ApplicationReturnStatus ipopt_status;
126 ipopt_status = _ipopt_app->OptimizeTNLP(_ipopt_nlp);
128 ipopt_status = _ipopt_app->ReOptimizeTNLP(_ipopt_nlp);
130 if (obj_value) *obj_value = _last_obj_value;
132 return convertIpoptToNlpSolverStatus(ipopt_status);
135 bool SolverIpopt::setLinearSolver(
LinearSolver solver_type)
137 if (!Ipopt::IsValid(_ipopt_app))
return false;
139 bool success =
false;
144 success = _ipopt_app->Options()->SetStringValue(
"linear_solver",
"mumps");
147 success = _ipopt_app->Options()->SetStringValue(
"linear_solver",
"ma27");
150 success = _ipopt_app->Options()->SetStringValue(
"linear_solver",
"ma57");
153 success = _ipopt_app->Options()->SetStringValue(
"linear_solver",
"ma77");
156 success = _ipopt_app->Options()->SetStringValue(
"linear_solver",
"ma86");
159 success = _ipopt_app->Options()->SetStringValue(
"linear_solver",
"ma97");
167 _current_lin_solver = solver_type;
177 std::string linear_solver;
178 if (!_ipopt_app->Options()->GetStringValue(
"linear_solver", linear_solver,
""))
return LinearSolver::NO_SOLVER;
190 bool SolverIpopt::setLinearSolverByName(
const std::string& solver_name)
192 if (!Ipopt::IsValid(_ipopt_app))
return false;
193 return _ipopt_app->Options()->SetStringValue(
"linear_solver", solver_name);
196 std::string SolverIpopt::getLinearSolverByName()
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;
204 bool SolverIpopt::setRelTolerance(
double tolerance) {
return _ipopt_app->Options()->SetNumericValue(
"tol", tolerance); }
205 double SolverIpopt::getRelTolerance()
const 208 _ipopt_app->Options()->GetNumericValue(
"tol", val,
"");
212 bool SolverIpopt::setDualInfTolerance(
double tolerance) {
return _ipopt_app->Options()->SetNumericValue(
"dual_inf_tol", tolerance); }
213 double SolverIpopt::getDualInfTolerance()
const 216 _ipopt_app->Options()->GetNumericValue(
"dual_inf_tol", val,
"");
220 bool SolverIpopt::setConstrViolTolerance(
double tolerance) {
return _ipopt_app->Options()->SetNumericValue(
"constr_viol_tol", tolerance); }
221 double SolverIpopt::getConstrViolTolerance()
const 224 _ipopt_app->Options()->GetNumericValue(
"constr_viol_tol", val,
"");
228 bool SolverIpopt::setComplInfTolerance(
double tolerance) {
return _ipopt_app->Options()->SetNumericValue(
"compl_inf_tol", tolerance); }
229 double SolverIpopt::getComplInfTolerance()
const 232 _ipopt_app->Options()->GetNumericValue(
"compl_inf_tol", val,
"");
236 bool SolverIpopt::setMuStrategyAdaptive(
bool enabled)
238 if (enabled)
return _ipopt_app->Options()->SetStringValue(
"mu_strategy",
"adaptive");
239 return _ipopt_app->Options()->SetStringValue(
"mu_strategy",
"monotone");
241 bool SolverIpopt::isMuStrategyAdaptive()
const 244 _ipopt_app->Options()->GetStringValue(
"mu_strategy", opt,
"");
245 return opt.compare(
"adaptive") == 0 ? true :
false;
248 bool SolverIpopt::setHessianApproxExact(
bool enabled)
250 if (enabled)
return _ipopt_app->Options()->SetStringValue(
"hessian_approximation",
"exact");
251 return _ipopt_app->Options()->SetStringValue(
"hessian_approximation",
"limited-memory");
253 bool SolverIpopt::isHessianApproxExact()
const 256 _ipopt_app->Options()->GetStringValue(
"hessian_approximation", opt,
"");
257 return opt.compare(
"exact") == 0 ? true :
false;
260 bool SolverIpopt::setWarmStartInitPoint(
bool enabled)
262 if (enabled)
return _ipopt_app->Options()->SetStringValue(
"warm_start_init_point",
"yes");
263 return _ipopt_app->Options()->SetStringValue(
"warm_start_init_point",
"no");
265 bool SolverIpopt::isWarmStartInitPoint()
const 268 _ipopt_app->Options()->GetStringValue(
"warm_start_init_point", opt,
"");
269 return opt.compare(
"yes") == 0 ? true :
false;
272 bool SolverIpopt::setMehrotraAlgorithm(
bool enabled)
274 if (enabled)
return _ipopt_app->Options()->SetStringValue(
"mehrotra_algorithm",
"yes");
275 return _ipopt_app->Options()->SetStringValue(
"mehrotra_algorithm",
"no");
277 bool SolverIpopt::isMehrotraAlgorithm()
const 280 _ipopt_app->Options()->GetStringValue(
"mehrotra_algorithm", opt,
"");
281 return opt.compare(
"yes") == 0 ? true :
false;
284 bool SolverIpopt::setPrintLevel(
int print_level) {
return _ipopt_app->Options()->SetIntegerValue(
"print_level", print_level); }
285 int SolverIpopt::getPrintLevel()
const 288 _ipopt_app->Options()->GetIntegerValue(
"print_level", val,
"");
292 bool SolverIpopt::setNlpAutoScaling(
bool enabled)
294 if (enabled)
return _ipopt_app->Options()->SetStringValue(
"nlp_scaling_method",
"gradient-based");
295 return _ipopt_app->Options()->SetStringValue(
"nlp_scaling_method",
"none");
297 bool SolverIpopt::isNlpAutoScaling()
const 300 _ipopt_app->Options()->GetStringValue(
"nlp_scaling_method", opt,
"");
301 return opt.compare(
"gradient-based") == 0 ? true :
false;
304 bool SolverIpopt::setCheckDerivativesForNan(
bool enabled)
306 if (enabled)
return _ipopt_app->Options()->SetStringValue(
"check_derivatives_for_naninf",
"yes");
307 return _ipopt_app->Options()->SetStringValue(
"check_derivatives_for_naninf",
"no");
309 bool SolverIpopt::isCheckDerivativesForNan()
const 312 _ipopt_app->Options()->GetStringValue(
"check_derivatives_for_naninf", opt,
"");
313 return opt.compare(
"yes") == 0 ? true :
false;
316 bool SolverIpopt::setDerivativeTest(
bool first_order,
bool second_order)
318 _ipopt_app->Options()->SetNumericValue(
"derivative_test_perturbation", 6e-3);
319 _ipopt_app->Options()->SetNumericValue(
"derivative_test_tol", 1e-3);
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");
329 void SolverIpopt::isDerivativeTest(
bool& first_order,
bool& second_order)
const 332 _ipopt_app->Options()->GetStringValue(
"derivative_test", opt,
"");
333 if (opt.compare(
"second-order") == 0)
338 else if (opt.compare(
"first-order") == 0)
341 second_order =
false;
343 else if (opt.compare(
"fonly-second-order") == 0)
351 second_order =
false;
355 bool SolverIpopt::setIpoptOptionString(
const std::string& param,
const std::string& option)
357 if (!Ipopt::IsValid(_ipopt_app))
return false;
358 return _ipopt_app->Options()->SetStringValue(param, option);
361 bool SolverIpopt::setIpoptOptionInt(
const std::string& param,
int option)
363 if (!Ipopt::IsValid(_ipopt_app))
return false;
364 return _ipopt_app->Options()->SetIntegerValue(param, option);
367 bool SolverIpopt::setIpoptOptionNumeric(
const std::string& param,
double option)
369 if (!Ipopt::IsValid(_ipopt_app))
return false;
370 return _ipopt_app->Options()->SetNumericValue(param, option);
373 SolverStatus SolverIpopt::convertIpoptToNlpSolverStatus(Ipopt::ApplicationReturnStatus ipopt_status)
const 375 switch (ipopt_status)
377 case Ipopt::Solve_Succeeded:
378 case Ipopt::Solved_To_Acceptable_Level:
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:
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:
406 _last_obj_value = -1;
408 _nnz_jac_constraints = 0;
409 _nnz_h_lagrangian = 0;
420 #ifdef MESSAGE_SUPPORT 421 void SolverIpopt::toMessage(corbo::messages::NlpSolver& message)
const 423 message.mutable_solver_ipopt()->set_iterations(getIterations());
424 message.mutable_solver_ipopt()->set_max_cpu_time(getMaxCpuTime());
426 switch (getLinearSolver())
430 message.mutable_solver_ipopt()->set_linear_solver(corbo::messages::SolverIpopt::MUMPS);
435 message.mutable_solver_ipopt()->set_linear_solver(corbo::messages::SolverIpopt::MA27);
440 message.mutable_solver_ipopt()->set_linear_solver(corbo::messages::SolverIpopt::MA57);
445 message.mutable_solver_ipopt()->set_linear_solver(corbo::messages::SolverIpopt::MA77);
450 message.mutable_solver_ipopt()->set_linear_solver(corbo::messages::SolverIpopt::MA86);
455 message.mutable_solver_ipopt()->set_linear_solver(corbo::messages::SolverIpopt::MA97);
459 PRINT_ERROR(
"SolverIpopt::toMessage(): selected linear solver is currently not included in message export.");
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);
478 void SolverIpopt::fromMessage(
const corbo::messages::NlpSolver& message, std::stringstream* issues)
482 setIterations(message.solver_ipopt().iterations());
483 setMaxCpuTime(message.solver_ipopt().max_cpu_time());
485 switch (message.solver_ipopt().linear_solver())
487 case corbo::messages::SolverIpopt::MUMPS:
490 *issues <<
"LinearSolver::MUMPS: not supported with current IPOPT installation." << std::endl;
493 case corbo::messages::SolverIpopt::MA27:
496 *issues <<
"LinearSolver::MA27: not supported with current IPOPT installation." << std::endl;
499 case corbo::messages::SolverIpopt::MA57:
502 *issues <<
"LinearSolver::MA57: not supported with current IPOPT installation." << std::endl;
505 case corbo::messages::SolverIpopt::MA77:
508 *issues <<
"LinearSolver::MA77: not supported with current IPOPT installation." << std::endl;
511 case corbo::messages::SolverIpopt::MA86:
514 *issues <<
"LinearSolver::MA86: not supported with current IPOPT installation" << std::endl;
517 case corbo::messages::SolverIpopt::MA97:
520 *issues <<
"LinearSolver::MA97: not supported with current IPOPT installation." << std::endl;
525 if (issues) *issues <<
"SolverIpopt::fromMessage(): selected linear solver is currently not supported." << std::endl;
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;
537 if (!setCheckDerivativesForNan(message.solver_ipopt().check_derivatives_for_naninf()) && issues)
538 *issues <<
"setCheckDerivativesForNan() failed." << std::endl;
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;
544 _cache_first_order_derivatives = message.solver_ipopt().cache_first_order_derivatives();
546 Ipopt::ApplicationReturnStatus status;
547 status = _ipopt_app->Initialize();
548 if (status != Ipopt::Solve_Succeeded)
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");
557 _param_msg_received =
true;
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.
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.
#define PRINT_ERROR(msg)
Print msg-stream as error msg.