nlp_solver_ipopt_wrapper.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 
30 
31 #include <cassert>
32 #include <iostream>
33 
34 namespace corbo {
35 
36 // constructor
37 IpoptWrapper::IpoptWrapper(SolverIpopt* solver) : _solver(solver) {}
38 
39 // destructor
41 
42 // returns the size of the problem
43 bool IpoptWrapper::get_nlp_info(Index& n, Index& m, Index& nnz_jac_g, Index& nnz_h_lag, IndexStyleEnum& index_style)
44 {
45  // Number of optimization variables
47 
48  // Number of equality and inequality constraints (not bounds)
50 
51  // Number of nonzeros of the jacobian
52  nnz_jac_g = _solver->_nnz_jac_constraints;
53 
54  if (_solver->_cache_first_order_derivatives)
55  {
56  _solver->_grad_f_cache.resize(n);
57  _solver->_jac_constr_cache.resize(nnz_jac_g);
58  }
59 
60  // Number of nonzeros of the hessian of the lagrangian, but we
61  // only need the lower left corner (since it is symmetric)
62  // nnz_h_lag = 0.5 * n * (n+1);
63  // assert(_solver_interface->_h_lag_i_row.size() == _solver_interface->_h_lag_j_col.size());
64  nnz_h_lag = _solver->_nnz_h_lagrangian;
65 
66  // use the C style indexing (0-based)
67  index_style = TNLP::C_STYLE;
68 
69  return true;
70 }
71 
72 // returns the variable bounds
73 bool IpoptWrapper::get_bounds_info(Index n, Number* x_l, Number* x_u, Index m, Number* g_l, Number* g_u)
74 {
75  // here, the n and m we gave IPOPT in get_nlp_info are passed back to us.
76  // If desired, we could assert to make sure they are what we think they are.
77  assert(n == _problem->getParameterDimension());
79 
80  // apply bounds
81  Eigen::Map<Eigen::VectorXd> x_l_map(x_l, n);
82  Eigen::Map<Eigen::VectorXd> x_u_map(x_u, n);
83  _problem->getBounds(x_l_map, x_u_map);
84 
85  // equality and inequality constraints are in the form g_l <= g(x) <= g_u
86  if (m > 0)
87  {
88  Eigen::Map<Eigen::VectorXd> g_l_map(g_l, m);
89  Eigen::Map<Eigen::VectorXd> g_u_map(g_u, m);
90  g_l_map.head(_problem->getEqualityDimension()).fill(0);
91  g_u_map.head(_problem->getEqualityDimension()).fill(0);
92  g_l_map.tail(_problem->getInequalityDimension()).fill(-CORBO_INF_DBL);
93  g_u_map.tail(_problem->getInequalityDimension()).fill(0);
94  }
95 
96  return true;
97 }
98 
99 // returns the initial point for the problem
100 bool IpoptWrapper::get_starting_point(Index n, bool init_x, Number* x, bool init_z, Number* z_L, Number* z_U, Index m, bool init_lambda,
101  Number* lambda)
102 {
103  // Here, we assume we always have starting values for x
104  assert(init_x == true);
105 
106  // initialize to the given starting point
109 
110  if (init_lambda) // is true if warmstart is enabled
111  {
112  Eigen::Map<Eigen::VectorXd> lambda_map(lambda, m);
113  lambda_map = _solver->_lambda_cache;
114  }
115 
116  if (init_z) // is true if warmstart is enabled
117  {
118  Eigen::Map<Eigen::VectorXd> zl_map(z_L, n);
119  zl_map = _solver->_zl_cache;
120  Eigen::Map<Eigen::VectorXd> zu_map(z_U, n);
121  zu_map = _solver->_zu_cache;
122  }
123 
124  return true;
125 }
126 
127 // returns the value of the objective function
128 bool IpoptWrapper::eval_f(Index n, const Number* x, bool new_x, Number& obj_value)
129 {
130  assert(n == _problem->getParameterDimension());
131 
132  if (new_x)
133  {
134  // in the current solver implementation, we must copy the optim vector back
135  // which is not really efficient. This could be changed in the future...
138 
139  if (_solver->_cache_first_order_derivatives) precompute1stOrderDerivatives();
140  }
141 
142  obj_value = _problem->computeValueObjective();
143  return true;
144 }
145 
146 // return the gradient of the objective function grad_{x} f(x)
147 bool IpoptWrapper::eval_grad_f(Index n, const Number* x, bool new_x, Number* grad_f)
148 {
149  assert(n == _problem->getParameterDimension());
150 
151  if (new_x)
152  {
153  // in the current solver implementation, we must copy the optim vector back
154  // which is not really efficient. This could be changed in the future...
157 
158  if (_solver->_cache_first_order_derivatives) precompute1stOrderDerivatives();
159  }
160 
161  Eigen::Map<Eigen::VectorXd> grad_f_map(grad_f, n);
162  if (_solver->_cache_first_order_derivatives)
163  grad_f_map = _solver->_grad_f_cache;
164  else
165  _problem->computeGradientObjective(grad_f_map);
166 
167  return true;
168 }
169 
170 // return the value of the constraints: g(x)
171 bool IpoptWrapper::eval_g(Index n, const Number* x, bool new_x, Index m, Number* g)
172 {
173  assert(n == _problem->getParameterDimension());
175 
176  if (new_x)
177  {
178  // in the current solver implementation, we must copy the optim vector back
179  // which is not really efficient. This could be changed in the future...
182 
183  if (_solver->_cache_first_order_derivatives) precompute1stOrderDerivatives();
184  }
185 
186  Eigen::Map<Eigen::VectorXd> g_map(g, m);
189 
190  return true;
191 }
192 
193 // return the structure or values of the jacobian
194 bool IpoptWrapper::eval_jac_g(Index n, const Number* x, bool new_x, Index m, Index nele_jac, Index* iRow, Index* jCol, Number* values)
195 {
196  assert(nele_jac == _solver->_nnz_jac_constraints);
197 
198  if (values == NULL)
199  {
200  // return the structure of the jacobian
201  Eigen::Map<Eigen::VectorXi> i_row_map(iRow, nele_jac);
202  Eigen::Map<Eigen::VectorXi> j_col_map(jCol, nele_jac);
203  _problem->computeCombinedSparseJacobiansStructure(i_row_map, j_col_map, false, true, true);
204  // std::copy(_solver_interface->_jac_constr_i_row.begin(), _solver_interface->_jac_constr_i_row.end(), iRow);
205  // std::copy(_solver_interface->_jac_constr_j_col.begin(), _solver_interface->_jac_constr_j_col.end(), jCol);
206  }
207  else
208  {
209  if (new_x)
210  {
211  // in the current solver implementation, we must copy the optim vector back
212  // which is not really efficient. This could be changed in the future...
215 
216  if (_solver->_cache_first_order_derivatives) precompute1stOrderDerivatives();
217  }
218  Eigen::Map<Eigen::VectorXd> values_map(values, nele_jac);
219  if (_solver->_cache_first_order_derivatives)
220  values_map = _solver->_jac_constr_cache;
221  else
222  _problem->computeCombinedSparseJacobiansValues(values_map, false, true, true);
223 
224  // return the values of the jacobian of the constraints
225  // std::copy(_solver_interface->_jac_constr_values.begin(), _solver_interface->_jac_constr_values.end(), values);
226  }
227 
228  return true;
229 }
230 
231 // return the structure or values of the hessian
232 bool IpoptWrapper::eval_h(Index n, const Number* x, bool new_x, Number obj_factor, Index m, const Number* lambda, bool new_lambda, Index nele_hess,
233  Index* iRow, Index* jCol, Number* values)
234 {
235  assert(nele_hess == _solver->_nnz_h_lagrangian);
236  assert(nele_hess = _solver->_nnz_hes_obj + _solver->_nnz_hes_eq + _solver->_nnz_hes_ineq);
237 
238  if (values == NULL)
239  {
240  // return the structure. This is a symmetric matrix, fill the lower left triangle only.
241  // std::copy(_solver_interface->_h_lag_i_row.begin(), _solver_interface->_h_lag_i_row.end(), iRow);
242  // std::copy(_solver_interface->_h_lag_j_col.begin(), _solver_interface->_h_lag_j_col.end(), jCol);
243  Eigen::Map<Eigen::VectorXi> i_row_map_obj(iRow, _solver->_nnz_hes_obj);
244  Eigen::Map<Eigen::VectorXi> j_col_map_obj(jCol, _solver->_nnz_hes_obj);
245  Eigen::Map<Eigen::VectorXi> i_row_map_eq(iRow + _solver->_nnz_hes_obj, _solver->_nnz_hes_eq);
246  Eigen::Map<Eigen::VectorXi> j_col_map_eq(jCol + _solver->_nnz_hes_obj, _solver->_nnz_hes_eq);
247  Eigen::Map<Eigen::VectorXi> i_row_map_ineq(iRow + _solver->_nnz_hes_obj + _solver->_nnz_hes_eq, _solver->_nnz_hes_ineq);
248  Eigen::Map<Eigen::VectorXi> j_col_map_ineq(jCol + _solver->_nnz_hes_obj + _solver->_nnz_hes_eq, _solver->_nnz_hes_ineq);
249  _problem->computeSparseHessiansStructure(i_row_map_obj, j_col_map_obj, i_row_map_eq, j_col_map_eq, i_row_map_ineq, j_col_map_ineq, true);
250  }
251  else
252  {
253  // // return the values. This is a symmetric matrix, fill the lower left
254  // // triangle only
255 
256  if (new_x)
257  {
258  // // in the current solver implementation, we must copy the optim vector back
259  // // which is not really efficient. This could be changed in the future...
262 
263  if (_solver->_cache_first_order_derivatives) precompute1stOrderDerivatives();
264  }
265 
266  // _solver_interface->computeHessianLagrangianValues(obj_factor, lambda);
267  Eigen::Map<Eigen::VectorXd> values_obj_map(values, _solver->_nnz_hes_obj);
268  Eigen::Map<Eigen::VectorXd> values_eq_map(values + _solver->_nnz_hes_obj, _solver->_nnz_hes_eq);
269  Eigen::Map<Eigen::VectorXd> values_ineq_map(values + _solver->_nnz_hes_obj + _solver->_nnz_hes_eq, _solver->_nnz_hes_ineq);
270  _problem->computeSparseHessiansValues(values_obj_map, values_eq_map, values_ineq_map, obj_factor, lambda,
271  lambda + _problem->getEqualityDimension(), true);
272  // std::copy(_solver_interface->_h_lag_values.begin(), _solver_interface->_h_lag_values.end(), values);
273  }
274 
275  return true;
276 }
277 
278 void IpoptWrapper::finalize_solution(SolverReturn status, Index n, const Number* x, const Number* z_L, const Number* z_U, Index m, const Number* g,
279  const Number* lambda, Number obj_value, const IpoptData* ip_data, IpoptCalculatedQuantities* ip_cq)
280 {
283 
284  _solver->_last_obj_value = obj_value;
285 
286  Eigen::Map<const Eigen::VectorXd> lambda_map(lambda, m);
287  _solver->_lambda_cache = lambda_map;
288 
290  _solver->_zl_cache = zl_map;
291 
293  _solver->_zu_cache = zu_map;
294 }
295 
297 {
298  _problem->computeGradientObjectiveAndCombinedSparseJacobiansValues(_solver->_grad_f_cache, _solver->_jac_constr_cache, true, true);
299 }
300 
301 } // namespace corbo
302 
303 #endif // IPOPT
corbo::IpoptWrapper::_problem
OptimizationProblemInterface * _problem
Definition: nlp_solver_ipopt_wrapper.h:107
corbo::IpoptWrapper::precompute1stOrderDerivatives
void precompute1stOrderDerivatives()
corbo::OptimizationProblemInterface::computeSparseHessiansStructure
virtual void computeSparseHessiansStructure(Eigen::Ref< Eigen::VectorXi > i_row_obj, Eigen::Ref< Eigen::VectorXi > j_col_obj, Eigen::Ref< Eigen::VectorXi > i_row_eq, Eigen::Ref< Eigen::VectorXi > j_col_eq, Eigen::Ref< Eigen::VectorXi > i_row_ineq, Eigen::Ref< Eigen::VectorXi > j_col_ineq, bool lower_part_only=false)
Definition: optimization_problem_interface.cpp:1564
corbo::IpoptWrapper::eval_g
bool eval_g(Index n, const Number *x, bool new_x, Index m, Number *g) override
nlp_solver_ipopt.h
corbo::IpoptWrapper::eval_f
bool eval_f(Index n, const Number *x, bool new_x, Number &obj_value) override
corbo::IpoptWrapper::get_bounds_info
bool get_bounds_info(Index n, Number *x_l, Number *x_u, Index m, Number *g_l, Number *g_u) override
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::OptimizationProblemInterface::computeValueObjective
virtual double computeValueObjective()
Definition: optimization_problem_interface.cpp:53
corbo::IpoptWrapper::~IpoptWrapper
virtual ~IpoptWrapper()
corbo::OptimizationProblemInterface::getInequalityDimension
virtual int getInequalityDimension()=0
Total dimension of general inequality constraints.
corbo::CORBO_INF_DBL
constexpr const double CORBO_INF_DBL
Representation for infinity (double version)
Definition: core/include/corbo-core/types.h:75
corbo::IpoptWrapper::get_starting_point
bool get_starting_point(Index n, bool init_x, Number *x, bool init_z, Number *z_L, Number *z_U, Index m, bool init_lambda, Number *lambda) override
corbo::OptimizationProblemInterface::computeValuesEquality
virtual void computeValuesEquality(Eigen::Ref< Eigen::VectorXd > values)=0
Compute the equality constraint values ceq(x) for the current parameter set.
corbo::OptimizationProblemInterface::computeCombinedSparseJacobiansValues
virtual void computeCombinedSparseJacobiansValues(Eigen::Ref< Eigen::VectorXd > values, bool objective_lsq=true, bool equality=true, bool inequality=true, const double *multipliers_obj=nullptr, const double *multipliers_eq=nullptr, const double *multipliers_ineq=nullptr)
Definition: optimization_problem_interface.cpp:894
corbo::IpoptWrapper::_solver
SolverIpopt * _solver
Definition: nlp_solver_ipopt_wrapper.h:108
corbo::OptimizationProblemInterface::getBounds
virtual void getBounds(Eigen::Ref< Eigen::VectorXd > lb, Eigen::Ref< Eigen::VectorXd > ub)
Get lower and upper bound vector.
Definition: optimization_problem_interface.cpp:103
corbo::OptimizationProblemInterface::getEqualityDimension
virtual int getEqualityDimension()=0
Total dimension of equality constraints.
corbo::OptimizationProblemInterface::computeValuesInequality
virtual void computeValuesInequality(Eigen::Ref< Eigen::VectorXd > values)=0
Compute the inequality constraint values c(x) for the current parameter set.
x
Scalar * x
Definition: level1_cplx_impl.h:89
corbo::OptimizationProblemInterface::setParameterVector
virtual void setParameterVector(const Eigen::Ref< const Eigen::VectorXd > &x)
Set complete parameter vector.
Definition: optimization_problem_interface.cpp:72
corbo::IpoptWrapper::eval_jac_g
bool eval_jac_g(Index n, const Number *x, bool new_x, Index m, Index nele_jac, Index *iRow, Index *jCol, Number *values) override
Eigen::Map
A matrix or vector expression mapping an existing array of data.
Definition: Map.h:94
corbo::OptimizationProblemInterface::computeSparseHessiansValues
virtual void computeSparseHessiansValues(Eigen::Ref< Eigen::VectorXd > values_obj, Eigen::Ref< Eigen::VectorXd > values_eq, Eigen::Ref< Eigen::VectorXd > values_ineq, double multiplier_obj=1.0, const double *multipliers_eq=nullptr, const double *multipliers_ineq=nullptr, bool lower_part_only=false)
Definition: optimization_problem_interface.cpp:1576
nlp_solver_ipopt_wrapper.h
corbo::IpoptWrapper::eval_h
bool eval_h(Index n, const Number *x, bool new_x, Number obj_factor, Index m, const Number *lambda, bool new_lambda, Index nele_hess, Index *iRow, Index *jCol, Number *values) override
corbo::OptimizationProblemInterface::getParameterVector
virtual void getParameterVector(Eigen::Ref< Eigen::VectorXd > x)
Return deep copy of the complete parameter vector.
Definition: optimization_problem_interface.cpp:65
corbo::IpoptWrapper::finalize_solution
void finalize_solution(SolverReturn status, Index n, const Number *x, const Number *z_L, const Number *z_U, Index m, const Number *g, const Number *lambda, Number obj_value, const IpoptData *ip_data, IpoptCalculatedQuantities *ip_cq) override
corbo::IpoptWrapper::get_nlp_info
bool get_nlp_info(Index &n, Index &m, Index &nnz_jac_g, Index &nnz_h_lag, IndexStyleEnum &index_style) override
corbo::OptimizationProblemInterface::computeGradientObjectiveAndCombinedSparseJacobiansValues
virtual void computeGradientObjectiveAndCombinedSparseJacobiansValues(Eigen::Ref< Eigen::VectorXd > gradient, Eigen::Ref< Eigen::VectorXd > jac_values, bool equality=true, bool inequality=true, const double *multipliers_eq=nullptr, const double *multipliers_ineq=nullptr)
Definition: optimization_problem_interface.cpp:954
corbo::OptimizationProblemInterface::computeGradientObjective
virtual void computeGradientObjective(Eigen::Ref< Eigen::VectorXd > gradient)
Definition: optimization_problem_interface.cpp:211
corbo::IpoptWrapper::IpoptWrapper
IpoptWrapper(SolverIpopt *solver)
n
PlainMatrixType mat * n
Definition: eigenvalues.cpp:41
corbo::OptimizationProblemInterface::computeCombinedSparseJacobiansStructure
virtual void computeCombinedSparseJacobiansStructure(Eigen::Ref< Eigen::VectorXi > i_row, Eigen::Ref< Eigen::VectorXi > j_col, bool objective_lsq=true, bool equality=true, bool inequality=true)
Definition: optimization_problem_interface.cpp:846
corbo::OptimizationProblemInterface::getParameterDimension
virtual int getParameterDimension()=0
Effictive dimension of the optimization parameter set (changeable, non-fixed part)
corbo::IpoptWrapper::eval_grad_f
bool eval_grad_f(Index n, const Number *x, bool new_x, Number *grad_f) override
Eigen::Index
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Definition: Meta.h:33


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