ipopt_adapter.cc
Go to the documentation of this file.
00001 /******************************************************************************
00002 Copyright (c) 2017, Alexander W. Winkler, ETH Zurich. All rights reserved.
00003 
00004 Redistribution and use in source and binary forms, with or without modification,
00005 are permitted provided that the following conditions are met:
00006     * Redistributions of source code must retain the above copyright notice,
00007       this list of conditions and the following disclaimer.
00008     * Redistributions in binary form must reproduce the above copyright notice,
00009       this list of conditions and the following disclaimer in the documentation
00010       and/or other materials provided with the distribution.
00011     * Neither the name of ETH ZURICH nor the names of its contributors may be
00012       used to endorse or promote products derived from this software without
00013       specific prior written permission.
00014 
00015 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00016 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00017 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00018 DISCLAIMED. IN NO EVENT SHALL ETH ZURICH BE LIABLE FOR ANY DIRECT, INDIRECT,
00019 INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
00020 LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
00021 PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
00022 LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
00023 OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
00024 ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00025 ******************************************************************************/
00026 
00027 #include <ifopt_ipopt/ipopt_adapter.h>
00028 
00029 namespace ifopt {
00030 
00031 void
00032 IpoptAdapter::Solve (Problem& nlp)
00033 {
00034   using namespace Ipopt;
00035   using IpoptPtr            = SmartPtr<TNLP>;
00036   using IpoptApplicationPtr = SmartPtr<IpoptApplication>;
00037 
00038   // initialize the Ipopt solver
00039   IpoptApplicationPtr ipopt_app_ = new IpoptApplication();
00040   ipopt_app_->RethrowNonIpoptException(true);
00041   SetOptions(ipopt_app_);
00042 
00043   ApplicationReturnStatus status_ = ipopt_app_->Initialize();
00044   if (status_ != Solve_Succeeded) {
00045     std::cout << std::endl << std::endl << "*** Error during initialization!" << std::endl;
00046     throw std::length_error("Ipopt could not initialize correctly");
00047   }
00048 
00049   // convert the NLP problem to Ipopt
00050   IpoptPtr nlp_ptr = new IpoptAdapter(nlp);
00051   status_ = ipopt_app_->OptimizeTNLP(nlp_ptr);
00052 
00053   if (status_ != Solve_Succeeded) {
00054     std::string msg = "Ipopt failed to find a solution. ReturnCode: " + std::to_string(status_);
00055     std::cerr << msg;
00056   }
00057 }
00058 
00059 void
00060 IpoptAdapter::SetOptions (Ipopt::SmartPtr<Ipopt::IpoptApplication> ipopt_app_)
00061 {
00062   // A complete list of options can be found here
00063   // https://www.coin-or.org/Ipopt/documentation/node40.html
00064 
00065   // Download and use additional solvers here: http://www.hsl.rl.ac.uk/ipopt/
00066   ipopt_app_->Options()->SetStringValue("linear_solver", "ma27"); // 27, 57, 77, 86, 97
00067 
00068   ipopt_app_->Options()->SetStringValue("hessian_approximation", "limited-memory");
00069   ipopt_app_->Options()->SetNumericValue("tol", 0.001);
00070   ipopt_app_->Options()->SetNumericValue("max_cpu_time", 40.0);
00071   ipopt_app_->Options()->SetIntegerValue("print_level", 5);
00072   ipopt_app_->Options()->SetStringValue("print_user_options", "yes");
00073   ipopt_app_->Options()->SetStringValue("print_timing_statistics", "no");
00074 
00075 //   ipopt_app_->Options()->SetIntegerValue("max_iter", 1);
00076   // ipopt_app_->Options()->SetNumericValue("derivative_test_tol", 1e-3);
00077 //   ipopt_app_->Options()->SetStringValue("jacobian_approximation", "finite-difference-values");
00078 //   ipopt_app_->Options()->SetStringValue("derivative_test", "first-order"); // "second-order"
00079 }
00080 
00081 IpoptAdapter::IpoptAdapter(Problem& nlp)
00082 {
00083   nlp_ = &nlp;
00084 }
00085 
00086 bool IpoptAdapter::get_nlp_info(Index& n, Index& m, Index& nnz_jac_g,
00087                          Index& nnz_h_lag, IndexStyleEnum& index_style)
00088 {
00089   n = nlp_->GetNumberOfOptimizationVariables();
00090   m = nlp_->GetNumberOfConstraints();
00091 
00092   nnz_jac_g = nlp_->GetJacobianOfConstraints().nonZeros();
00093   nnz_h_lag = n*n;
00094 
00095   // start index at 0 for row/col entries
00096   index_style = C_STYLE;
00097 
00098   return true;
00099 }
00100 
00101 bool IpoptAdapter::get_bounds_info(Index n, double* x_lower, double* x_upper,
00102                             Index m, double* g_l, double* g_u)
00103 {
00104   auto bounds_x = nlp_->GetBoundsOnOptimizationVariables();
00105   for (uint c=0; c<bounds_x.size(); ++c) {
00106     x_lower[c] = bounds_x.at(c).lower_;
00107     x_upper[c] = bounds_x.at(c).upper_;
00108   }
00109 
00110   // specific bounds depending on equality and inequality constraints
00111   auto bounds_g = nlp_->GetBoundsOnConstraints();
00112   for (uint c=0; c<bounds_g.size(); ++c) {
00113     g_l[c] = bounds_g.at(c).lower_;
00114     g_u[c] = bounds_g.at(c).upper_;
00115   }
00116 
00117   return true;
00118 }
00119 
00120 bool IpoptAdapter::get_starting_point(Index n, bool init_x, double* x,
00121                                bool init_z, double* z_L, double* z_U,
00122                                Index m, bool init_lambda,
00123                                double* lambda)
00124 {
00125   // Here, we assume we only have starting values for x
00126   assert(init_x == true);
00127   assert(init_z == false);
00128   assert(init_lambda == false);
00129 
00130   VectorXd x_all = nlp_->GetVariableValues();
00131   Eigen::Map<VectorXd>(&x[0], x_all.rows()) = x_all;
00132 
00133   return true;
00134 }
00135 
00136 bool IpoptAdapter::eval_f(Index n, const double* x, bool new_x, double& obj_value)
00137 {
00138   obj_value = nlp_->EvaluateCostFunction(x);
00139   return true;
00140 }
00141 
00142 bool IpoptAdapter::eval_grad_f(Index n, const double* x, bool new_x, double* grad_f)
00143 {
00144   Eigen::VectorXd grad = nlp_->EvaluateCostFunctionGradient(x);
00145   Eigen::Map<Eigen::MatrixXd>(grad_f,n,1) = grad;
00146   return true;
00147 }
00148 
00149 bool IpoptAdapter::eval_g(Index n, const double* x, bool new_x, Index m, double* g)
00150 {
00151   VectorXd g_eig = nlp_->EvaluateConstraints(x);
00152   Eigen::Map<VectorXd>(g,m) = g_eig;
00153   return true;
00154 }
00155 
00156 bool IpoptAdapter::eval_jac_g(Index n, const double* x, bool new_x,
00157                        Index m, Index nele_jac, Index* iRow, Index *jCol,
00158                        double* values)
00159 {
00160   // defines the positions of the nonzero elements of the jacobian
00161   if (values == NULL) {
00162 
00163     auto jac = nlp_->GetJacobianOfConstraints();
00164     int nele=0; // nonzero cells in jacobian
00165     for (int k=0; k<jac.outerSize(); ++k) {
00166       for (Jacobian::InnerIterator it(jac,k); it; ++it) {
00167         iRow[nele] = it.row();
00168         jCol[nele] = it.col();
00169         nele++;
00170       }
00171     }
00172 
00173     assert(nele == nele_jac); // initial sparsity structure is never allowed to change
00174   }
00175   else {
00176     // only gets used if "jacobian_approximation finite-difference-values" is not set
00177     nlp_->EvalNonzerosOfJacobian(x, values);
00178   }
00179 
00180   return true;
00181 }
00182 
00183 bool IpoptAdapter::intermediate_callback(Ipopt::AlgorithmMode mode,
00184                                          Index iter, double obj_value,
00185                                          double inf_pr, double inf_du,
00186                                          double mu, double d_norm,
00187                                          double regularization_size,
00188                                          double alpha_du, double alpha_pr,
00189                                          Index ls_trials,
00190                                          const Ipopt::IpoptData* ip_data,
00191                                          Ipopt::IpoptCalculatedQuantities* ip_cq)
00192 {
00193   nlp_->SaveCurrent();
00194   return true;
00195 }
00196 
00197 void IpoptAdapter::finalize_solution(Ipopt::SolverReturn status,
00198                                      Index n, const double* x, const double* z_L, const double* z_U,
00199                                      Index m, const double* g, const double* lambda,
00200                                      double obj_value,
00201                                      const Ipopt::IpoptData* ip_data,
00202                                      Ipopt::IpoptCalculatedQuantities* ip_cq)
00203 {
00204   nlp_->SetVariables(x);
00205   nlp_->SaveCurrent();
00206 }
00207 
00208 } // namespace opt


ifopt_ipopt
Author(s): Alexander W. Winkler
autogenerated on Sat Apr 21 2018 03:01:50