ipopt_adapter.cc
Go to the documentation of this file.
1 /******************************************************************************
2 Copyright (c) 2017, Alexander W. Winkler, ETH Zurich. All rights reserved.
3 
4 Redistribution and use in source and binary forms, with or without modification,
5 are permitted provided that the following conditions are met:
6  * Redistributions of source code must retain the above copyright notice,
7  this list of conditions and the following disclaimer.
8  * Redistributions in binary form must reproduce the above copyright notice,
9  this list of conditions and the following disclaimer in the documentation
10  and/or other materials provided with the distribution.
11  * Neither the name of ETH ZURICH nor the names of its contributors may be
12  used to endorse or promote products derived from this software without
13  specific prior written permission.
14 
15 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
16 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
17 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
18 DISCLAIMED. IN NO EVENT SHALL ETH ZURICH BE LIABLE FOR ANY DIRECT, INDIRECT,
19 INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
20 LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
21 PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
22 LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
23 OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
24 ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
25 ******************************************************************************/
26 
28 
29 namespace ifopt {
30 
31 void
33 {
34  using namespace Ipopt;
35  using IpoptPtr = SmartPtr<TNLP>;
36  using IpoptApplicationPtr = SmartPtr<IpoptApplication>;
37 
38  // initialize the Ipopt solver
39  IpoptApplicationPtr ipopt_app_ = new IpoptApplication();
40  ipopt_app_->RethrowNonIpoptException(true);
41  SetOptions(ipopt_app_);
42 
43  ApplicationReturnStatus status_ = ipopt_app_->Initialize();
44  if (status_ != Solve_Succeeded) {
45  std::cout << std::endl << std::endl << "*** Error during initialization!" << std::endl;
46  throw std::length_error("Ipopt could not initialize correctly");
47  }
48 
49  // convert the NLP problem to Ipopt
50  IpoptPtr nlp_ptr = new IpoptAdapter(nlp);
51  status_ = ipopt_app_->OptimizeTNLP(nlp_ptr);
52 
53  if (status_ != Solve_Succeeded) {
54  std::string msg = "Ipopt failed to find a solution. ReturnCode: " + std::to_string(status_);
55  std::cerr << msg;
56  }
57 }
58 
59 void
60 IpoptAdapter::SetOptions (Ipopt::SmartPtr<Ipopt::IpoptApplication> ipopt_app_)
61 {
62  // A complete list of options can be found here
63  // https://www.coin-or.org/Ipopt/documentation/node40.html
64 
65  // Download and use additional solvers here: http://www.hsl.rl.ac.uk/ipopt/
66  ipopt_app_->Options()->SetStringValue("linear_solver", "ma27"); // 27, 57, 77, 86, 97
67 
68  ipopt_app_->Options()->SetStringValue("hessian_approximation", "limited-memory");
69  ipopt_app_->Options()->SetNumericValue("tol", 0.001);
70  ipopt_app_->Options()->SetNumericValue("max_cpu_time", 40.0);
71  ipopt_app_->Options()->SetIntegerValue("print_level", 5);
72  ipopt_app_->Options()->SetStringValue("print_user_options", "yes");
73  ipopt_app_->Options()->SetStringValue("print_timing_statistics", "no");
74 
75 // ipopt_app_->Options()->SetIntegerValue("max_iter", 1);
76  // ipopt_app_->Options()->SetNumericValue("derivative_test_tol", 1e-3);
77 // ipopt_app_->Options()->SetStringValue("jacobian_approximation", "finite-difference-values");
78 // ipopt_app_->Options()->SetStringValue("derivative_test", "first-order"); // "second-order"
79 }
80 
82 {
83  nlp_ = &nlp;
84 }
85 
86 bool IpoptAdapter::get_nlp_info(Index& n, Index& m, Index& nnz_jac_g,
87  Index& nnz_h_lag, IndexStyleEnum& index_style)
88 {
91 
92  nnz_jac_g = nlp_->GetJacobianOfConstraints().nonZeros();
93  nnz_h_lag = n*n;
94 
95  // start index at 0 for row/col entries
96  index_style = C_STYLE;
97 
98  return true;
99 }
100 
101 bool IpoptAdapter::get_bounds_info(Index n, double* x_lower, double* x_upper,
102  Index m, double* g_l, double* g_u)
103 {
104  auto bounds_x = nlp_->GetBoundsOnOptimizationVariables();
105  for (uint c=0; c<bounds_x.size(); ++c) {
106  x_lower[c] = bounds_x.at(c).lower_;
107  x_upper[c] = bounds_x.at(c).upper_;
108  }
109 
110  // specific bounds depending on equality and inequality constraints
111  auto bounds_g = nlp_->GetBoundsOnConstraints();
112  for (uint c=0; c<bounds_g.size(); ++c) {
113  g_l[c] = bounds_g.at(c).lower_;
114  g_u[c] = bounds_g.at(c).upper_;
115  }
116 
117  return true;
118 }
119 
120 bool IpoptAdapter::get_starting_point(Index n, bool init_x, double* x,
121  bool init_z, double* z_L, double* z_U,
122  Index m, bool init_lambda,
123  double* lambda)
124 {
125  // Here, we assume we only have starting values for x
126  assert(init_x == true);
127  assert(init_z == false);
128  assert(init_lambda == false);
129 
130  VectorXd x_all = nlp_->GetVariableValues();
131  Eigen::Map<VectorXd>(&x[0], x_all.rows()) = x_all;
132 
133  return true;
134 }
135 
136 bool IpoptAdapter::eval_f(Index n, const double* x, bool new_x, double& obj_value)
137 {
138  obj_value = nlp_->EvaluateCostFunction(x);
139  return true;
140 }
141 
142 bool IpoptAdapter::eval_grad_f(Index n, const double* x, bool new_x, double* grad_f)
143 {
144  Eigen::VectorXd grad = nlp_->EvaluateCostFunctionGradient(x);
145  Eigen::Map<Eigen::MatrixXd>(grad_f,n,1) = grad;
146  return true;
147 }
148 
149 bool IpoptAdapter::eval_g(Index n, const double* x, bool new_x, Index m, double* g)
150 {
151  VectorXd g_eig = nlp_->EvaluateConstraints(x);
152  Eigen::Map<VectorXd>(g,m) = g_eig;
153  return true;
154 }
155 
156 bool IpoptAdapter::eval_jac_g(Index n, const double* x, bool new_x,
157  Index m, Index nele_jac, Index* iRow, Index *jCol,
158  double* values)
159 {
160  // defines the positions of the nonzero elements of the jacobian
161  if (values == NULL) {
162 
163  auto jac = nlp_->GetJacobianOfConstraints();
164  int nele=0; // nonzero cells in jacobian
165  for (int k=0; k<jac.outerSize(); ++k) {
166  for (Jacobian::InnerIterator it(jac,k); it; ++it) {
167  iRow[nele] = it.row();
168  jCol[nele] = it.col();
169  nele++;
170  }
171  }
172 
173  assert(nele == nele_jac); // initial sparsity structure is never allowed to change
174  }
175  else {
176  // only gets used if "jacobian_approximation finite-difference-values" is not set
177  nlp_->EvalNonzerosOfJacobian(x, values);
178  }
179 
180  return true;
181 }
182 
183 bool IpoptAdapter::intermediate_callback(Ipopt::AlgorithmMode mode,
184  Index iter, double obj_value,
185  double inf_pr, double inf_du,
186  double mu, double d_norm,
187  double regularization_size,
188  double alpha_du, double alpha_pr,
189  Index ls_trials,
190  const Ipopt::IpoptData* ip_data,
191  Ipopt::IpoptCalculatedQuantities* ip_cq)
192 {
193  nlp_->SaveCurrent();
194  return true;
195 }
196 
197 void IpoptAdapter::finalize_solution(Ipopt::SolverReturn status,
198  Index n, const double* x, const double* z_L, const double* z_U,
199  Index m, const double* g, const double* lambda,
200  double obj_value,
201  const Ipopt::IpoptData* ip_data,
202  Ipopt::IpoptCalculatedQuantities* ip_cq)
203 {
204  nlp_->SetVariables(x);
205  nlp_->SaveCurrent();
206 }
207 
208 } // namespace opt
static void SetOptions(Ipopt::SmartPtr< Ipopt::IpoptApplication > app)
Defines settings for the Ipopt solver app.
virtual bool get_starting_point(Index n, bool init_x, double *x, bool init_z, double *z_L, double *z_U, Index m, bool init_lambda, double *lambda)
virtual bool get_bounds_info(Index n, double *x_l, double *x_u, Index m, double *g_l, double *g_u)
Problem::VectorXd VectorXd
Definition: ipopt_adapter.h:53
virtual bool eval_jac_g(Index n, const double *x, bool new_x, Index m, Index nele_jac, Index *iRow, Index *jCol, double *values)
virtual bool eval_g(Index n, const double *x, bool new_x, Index m, double *g)
VecBound GetBoundsOnConstraints() const
double EvaluateCostFunction(const double *x)
virtual bool eval_f(Index n, const double *x, bool new_x, double &obj_value)
VectorXd GetVariableValues() const
Ipopt::Index Index
Definition: ipopt_adapter.h:52
VectorXd EvaluateCostFunctionGradient(const double *x)
virtual bool eval_grad_f(Index n, const double *x, bool new_x, double *grad_f)
IpoptAdapter(Problem &nlp)
Creates an IpoptAdapter wrapping the nlp.
void SaveCurrent()
VecBound GetBoundsOnOptimizationVariables() const
virtual bool get_nlp_info(Index &n, Index &m, Index &nnz_jac_g, Index &nnz_h_lag, IndexStyleEnum &index_style)
virtual bool intermediate_callback(Ipopt::AlgorithmMode mode, Index iter, double obj_value, double inf_pr, double inf_du, double mu, double d_norm, double regularization_size, double alpha_du, double alpha_pr, Index ls_trials, const Ipopt::IpoptData *ip_data, Ipopt::IpoptCalculatedQuantities *ip_cq)
void SetVariables(const double *x)
Problem * nlp_
The solver independent problem definition.
Definition: ipopt_adapter.h:79
Jacobian GetJacobianOfConstraints() const
void EvalNonzerosOfJacobian(const double *x, double *values)
virtual void finalize_solution(Ipopt::SolverReturn status, Index n, const double *x, const double *z_L, const double *z_U, Index m, const double *g, const double *lambda, double obj_value, const Ipopt::IpoptData *ip_data, Ipopt::IpoptCalculatedQuantities *ip_cq)
int GetNumberOfConstraints() const
VectorXd EvaluateConstraints(const double *x)
int GetNumberOfOptimizationVariables() const
static void Solve(Problem &nlp)
Creates an IpoptAdapter and solves the NLP.


ifopt_ipopt
Author(s): Alexander W. Winkler
autogenerated on Thu Apr 19 2018 02:47:38