nlp_solver_ipopt.h
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 #ifndef SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_SOLVER_NLP_SOLVER_IPOPT_H_
26 #define SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_SOLVER_NLP_SOLVER_IPOPT_H_
27 
29 
30 #include <memory>
31 
32 #ifdef IPOPT
34 #include <IpIpoptApplication.hpp>
35 #endif
36 
37 namespace corbo {
38 
39 #ifdef IPOPT
40 
48 class SolverIpopt : public NlpSolverInterface
49 {
50  friend class IpoptWrapper;
51 
52  public:
53  using Ptr = std::shared_ptr<SolverIpopt>;
54  using UPtr = std::unique_ptr<SolverIpopt>;
55 
56  enum class LinearSolver { MUMPS, MA27, MA57, MA77, MA86, MA97, NO_SOLVER };
57 
58  // implements interface method
59  NlpSolverInterface::Ptr getInstance() const override { return std::make_shared<SolverIpopt>(); }
60 
61  // implements interface method
62  bool isLsqSolver() const override { return false; }
63 
64  // implements interface method
65  bool initialize(OptimizationProblemInterface* problem = nullptr) override;
66  // implements interface method
67  SolverStatus solve(OptimizationProblemInterface& problem, bool new_structure = true, bool new_run = true, double* obj_value = nullptr) override;
68 
71 
72  bool setLinearSolver(LinearSolver solver_type);
73  LinearSolver getLinearSolver() const;
74 
75  // alternative method to directly pass sovler_name to ipopt
76  bool setLinearSolverByName(const std::string& solver_name);
77  std::string getLinearSolverByName();
78 
79  bool setRelTolerance(double tolerance);
80  double getRelTolerance() const;
81 
82  bool setDualInfTolerance(double tolerance);
83  double getDualInfTolerance() const;
84 
85  bool setConstrViolTolerance(double tolerance);
86  double getConstrViolTolerance() const;
87 
88  bool setComplInfTolerance(double tolerance);
89  double getComplInfTolerance() const;
90 
91  bool setMuStrategyAdaptive(bool enabled);
92  bool isMuStrategyAdaptive() const;
93 
94  bool setHessianApproxExact(bool enabled);
95  bool isHessianApproxExact() const;
96 
97  bool setWarmStartInitPoint(bool enabled);
98  bool isWarmStartInitPoint() const;
99 
100  bool setMehrotraAlgorithm(bool enabled);
101  bool isMehrotraAlgorithm() const;
102 
103  bool setPrintLevel(int print_level); // level 0-5
104  int getPrintLevel() const;
105 
106  bool setNlpAutoScaling(bool enabled);
107  bool isNlpAutoScaling() const;
108 
109  void setIterations(int iterations) { _iterations = iterations; }
110  int getIterations() const { return _iterations; }
111 
112  void setMaxCpuTime(double max_cpu_time) { _max_cpu_time = max_cpu_time; }
113  double getMaxCpuTime() const { return _max_cpu_time; }
114 
115  bool setCheckDerivativesForNan(bool enabled);
116  bool isCheckDerivativesForNan() const;
117 
118  bool setDerivativeTest(bool first_order, bool second_order);
119  void isDerivativeTest(bool& first_order, bool& second_order) const;
120 
121  // generic setter methods
122  bool setIpoptOptionString(const std::string& param, const std::string& option);
123  bool setIpoptOptionInt(const std::string& param, int option);
124  bool setIpoptOptionNumeric(const std::string& param, double option);
125 
126  void setCacheFirstOrderDerivatives(bool active) { _cache_first_order_derivatives = active; }
127 
129 
130  void clear() override;
131 
132  // void setIterations(int iterations) { _iterations = iterations; }
133 
134 #ifdef MESSAGE_SUPPORT
135  // implements interface method
136  void toMessage(corbo::messages::NlpSolver& message) const override;
137  // implements interface method
138  void fromMessage(const corbo::messages::NlpSolver& message, std::stringstream* issues = nullptr) override;
139 #endif
140 
141  protected:
142  SolverStatus convertIpoptToNlpSolverStatus(Ipopt::ApplicationReturnStatus ipopt_status) const;
143 
144  private:
145  Ipopt::SmartPtr<IpoptWrapper> _ipopt_nlp;
146  Ipopt::SmartPtr<Ipopt::IpoptApplication> _ipopt_app;
147 
148  int _nnz_jac_constraints = 0;
149  int _nnz_h_lagrangian = 0;
150  int _nnz_hes_obj = 0;
151  int _nnz_hes_eq = 0;
152  int _nnz_hes_ineq = 0;
153 
154  Eigen::VectorXd _lambda_cache;
155  Eigen::VectorXd _zl_cache;
156  Eigen::VectorXd _zu_cache;
157 
158  Eigen::VectorXd _grad_f_cache;
159  Eigen::VectorXd _jac_constr_cache;
160 
161  // std::vector<double> _lambda; // backup lagrange multiplier values between calls;
162 
163  double _max_cpu_time = -1; // use ipopt default (0: deactivate) [but should be deactivated by default]
164  int _iterations = 100; // ipopt max iterations
165 
166  double _last_obj_value = -1;
167 
168  bool _cache_first_order_derivatives = false;
169 
170  LinearSolver _current_lin_solver = LinearSolver::NO_SOLVER;
171 
172  bool _initialized = false;
173 
174  int _param_msg_received = false;
175 };
176 
177 FACTORY_REGISTER_NLP_SOLVER(SolverIpopt)
178 
179 #else // IPOPT
180 
189 {
190  public:
191  using Ptr = std::shared_ptr<SolverIpopt>;
192  using UPtr = std::unique_ptr<SolverIpopt>;
193 
195 
196  // implements interface method
197  NlpSolverInterface::Ptr getInstance() const override { return std::make_shared<SolverIpopt>(); }
198 
199  // implements interface method
200  bool isLsqSolver() const override { return false; }
201 
202  // implements interface method
203  bool initialize(OptimizationProblemInterface* problem = nullptr) override
204  {
205  printWarning();
206  return false;
207  }
208  // implements interface method
209  SolverStatus solve(OptimizationProblemInterface& problem, bool new_structure = true, bool new_run = true, double* obj_value = nullptr) override
210  {
211  printWarning();
212  return SolverStatus::Error;
213  }
214 
215  void clear() override {}
216 
217 #ifdef MESSAGE_SUPPORT
218  // implements interface method
219  void toMessage(corbo::messages::NlpSolver& /*message*/) const override { printWarning(); }
220  // implements interface method
221  void fromMessage(const corbo::messages::NlpSolver& /*message*/, std::stringstream* issues) override
222  {
223  if (issues) *issues << "SolverIPOPT cannot be selected since it is not installed properly." << std::endl;
224  printWarning();
225  }
226 #endif
227 
228  protected:
229  void printWarning() const { PRINT_WARNING("SolverIPOPT cannot be selected since it is not installed properly."); }
230 };
231 
232 #endif // IPOPT
233 
234 } // namespace corbo
235 
236 #endif // SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_SOLVER_NLP_SOLVER_IPOPT_H_
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.
void printWarning() const
#define PRINT_WARNING(msg)
Print msg-stream.
Definition: console.h:145
std::unique_ptr< NlpSolverInterface > UPtr
Interface to the external interior point solver IPOPT.
Generic interface for optimization problem definitions.
bool initialize(OptimizationProblemInterface *problem=nullptr) override
Initialize the solver w.r.t. a given optimization problem.
std::unique_ptr< SolverIpopt > UPtr
bool isLsqSolver() const override
Return true if the solver onyl supports costs in lsq form.
std::shared_ptr< NlpSolverInterface > Ptr
NlpSolverInterface::Ptr getInstance() const override
Return a newly created instance of the current solver.
Generic interface for solver implementations.
std::shared_ptr< SolverIpopt > Ptr
#define FACTORY_REGISTER_NLP_SOLVER(type)


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