00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027 #ifndef IFOPT_INCLUDE_OPT_IPOPT_ADAPTER_H_
00028 #define IFOPT_INCLUDE_OPT_IPOPT_ADAPTER_H_
00029
00030 #include <IpTNLP.hpp>
00031 #include <IpIpoptApplication.hpp>
00032 #include <IpSolveStatistics.hpp>
00033
00034 #include <ifopt/problem.h>
00035
00036 namespace ifopt {
00037
00050 class IpoptAdapter : public Ipopt::TNLP {
00051 public:
00052 using Index = Ipopt::Index;
00053 using VectorXd = Problem::VectorXd;
00054 using Jacobian = Problem::Jacobian;
00055
00063 static void Solve(Problem& nlp);
00064
00065 private:
00077 static void SetOptions(Ipopt::SmartPtr<Ipopt::IpoptApplication> app);
00078
00079 Problem* nlp_;
00080
00081 private:
00088 IpoptAdapter(Problem& nlp);
00089 virtual ~IpoptAdapter() = default;
00090
00092 virtual bool get_nlp_info(Index& n, Index& m, Index& nnz_jac_g,
00093 Index& nnz_h_lag, IndexStyleEnum& index_style);
00094
00096 virtual bool get_bounds_info(Index n, double* x_l, double* x_u,
00097 Index m, double* g_l, double* g_u);
00098
00100 virtual bool get_starting_point(Index n, bool init_x, double* x,
00101 bool init_z, double* z_L, double* z_U,
00102 Index m, bool init_lambda,
00103 double* lambda);
00104
00106 virtual bool eval_f(Index n, const double* x, bool new_x, double& obj_value);
00107
00109 virtual bool eval_grad_f(Index n, const double* x, bool new_x, double* grad_f);
00110
00112 virtual bool eval_g(Index n, const double* x, bool new_x, Index m, double* g);
00113
00118 virtual bool eval_jac_g(Index n, const double* x, bool new_x,
00119 Index m, Index nele_jac, Index* iRow, Index *jCol,
00120 double* values);
00121
00124 virtual bool intermediate_callback(Ipopt::AlgorithmMode mode,
00125 Index iter, double obj_value,
00126 double inf_pr, double inf_du,
00127 double mu, double d_norm,
00128 double regularization_size,
00129 double alpha_du, double alpha_pr,
00130 Index ls_trials,
00131 const Ipopt::IpoptData* ip_data,
00132 Ipopt::IpoptCalculatedQuantities* ip_cq);
00133
00136 virtual void finalize_solution(Ipopt::SolverReturn status,
00137 Index n, const double* x, const double* z_L, const double* z_U,
00138 Index m, const double* g, const double* lambda,
00139 double obj_value,
00140 const Ipopt::IpoptData* ip_data,
00141 Ipopt::IpoptCalculatedQuantities* ip_cq);
00142 };
00143
00144 }
00145
00146 #endif