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
00042 namespace Ipopt {
00043
00054 class IpoptAdapter : public TNLP {
00055 public:
00056 using Problem = ifopt::Problem;
00057 using VectorXd = Problem::VectorXd;
00058 using Jacobian = Problem::Jacobian;
00059
00066 IpoptAdapter(Problem& nlp, bool finite_diff = false);
00067 virtual ~IpoptAdapter() = default;
00068
00069 private:
00070 Problem* nlp_;
00071 bool finite_diff_;
00072
00074 virtual bool get_nlp_info(Index& n, Index& m, Index& nnz_jac_g,
00075 Index& nnz_h_lag, IndexStyleEnum& index_style);
00076
00078 virtual bool get_bounds_info(Index n, double* x_l, double* x_u,
00079 Index m, double* g_l, double* g_u);
00080
00082 virtual bool get_starting_point(Index n, bool init_x, double* x,
00083 bool init_z, double* z_L, double* z_U,
00084 Index m, bool init_lambda,
00085 double* lambda);
00086
00088 virtual bool eval_f(Index n, const double* x, bool new_x, double& obj_value);
00089
00091 virtual bool eval_grad_f(Index n, const double* x, bool new_x, double* grad_f);
00092
00094 virtual bool eval_g(Index n, const double* x, bool new_x, Index m, double* g);
00095
00100 virtual bool eval_jac_g(Index n, const double* x, bool new_x,
00101 Index m, Index nele_jac, Index* iRow, Index *jCol,
00102 double* values);
00103
00106 virtual bool intermediate_callback(AlgorithmMode mode,
00107 Index iter, double obj_value,
00108 double inf_pr, double inf_du,
00109 double mu, double d_norm,
00110 double regularization_size,
00111 double alpha_du, double alpha_pr,
00112 Index ls_trials,
00113 const IpoptData* ip_data,
00114 IpoptCalculatedQuantities* ip_cq);
00115
00118 virtual void finalize_solution(SolverReturn status,
00119 Index n, const double* x, const double* z_L, const double* z_U,
00120 Index m, const double* g, const double* lambda,
00121 double obj_value,
00122 const IpoptData* ip_data,
00123 IpoptCalculatedQuantities* ip_cq);
00124 };
00125
00126 }
00127
00128 #endif