34 using namespace Ipopt;
35 using IpoptPtr = SmartPtr<TNLP>;
36 using IpoptApplicationPtr = SmartPtr<IpoptApplication>;
39 IpoptApplicationPtr ipopt_app_ =
new IpoptApplication();
40 ipopt_app_->RethrowNonIpoptException(
true);
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");
51 status_ = ipopt_app_->OptimizeTNLP(nlp_ptr);
53 if (status_ != Solve_Succeeded) {
54 std::string msg =
"Ipopt failed to find a solution. ReturnCode: " + std::to_string(status_);
66 ipopt_app_->Options()->SetStringValue(
"linear_solver",
"ma27");
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");
87 Index& nnz_h_lag, IndexStyleEnum& index_style)
96 index_style = C_STYLE;
102 Index m,
double* g_l,
double* g_u)
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_;
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_;
121 bool init_z,
double* z_L,
double* z_U,
122 Index m,
bool init_lambda,
126 assert(init_x ==
true);
127 assert(init_z ==
false);
128 assert(init_lambda ==
false);
131 Eigen::Map<VectorXd>(&x[0], x_all.rows()) = x_all;
145 Eigen::Map<Eigen::MatrixXd>(grad_f,n,1) = grad;
152 Eigen::Map<VectorXd>(g,m) = g_eig;
161 if (values == NULL) {
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();
173 assert(nele == nele_jac);
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,
190 const Ipopt::IpoptData* ip_data,
191 Ipopt::IpoptCalculatedQuantities* ip_cq)
198 Index n,
const double* x,
const double* z_L,
const double* z_U,
199 Index m,
const double* g,
const double* lambda,
201 const Ipopt::IpoptData* ip_data,
202 Ipopt::IpoptCalculatedQuantities* ip_cq)
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
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
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.
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.
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.