38 Index& nnz_h_lag, IndexStyleEnum& index_style)
51 index_style = C_STYLE;
57 Index m,
double* g_l,
double* g_u)
60 for (uint c=0; c<bounds_x.size(); ++c) {
61 x_lower[c] = bounds_x.at(c).lower_;
62 x_upper[c] = bounds_x.at(c).upper_;
67 for (uint c=0; c<bounds_g.size(); ++c) {
68 g_l[c] = bounds_g.at(c).lower_;
69 g_u[c] = bounds_g.at(c).upper_;
76 bool init_z,
double* z_L,
double* z_U,
77 Index m,
bool init_lambda,
81 assert(init_x ==
true);
82 assert(init_z ==
false);
83 assert(init_lambda ==
false);
86 Eigen::Map<VectorXd>(&x[0], x_all.rows()) = x_all;
100 Eigen::Map<Eigen::MatrixXd>(grad_f,n,1) = grad;
107 Eigen::Map<VectorXd>(g,m) = g_eig;
112 Index m, Index nele_jac, Index* iRow, Index *jCol,
116 if (values == NULL) {
120 for (Index row = 0; row < m; row++) {
121 for (Index col = 0; col < n; col++) {
130 for (
int k=0; k<jac.outerSize(); ++k) {
131 for (Jacobian::InnerIterator it(jac,k); it; ++it) {
132 iRow[nele] = it.row();
133 jCol[nele] = it.col();
139 assert(nele == nele_jac);
150 Index iter,
double obj_value,
151 double inf_pr,
double inf_du,
152 double mu,
double d_norm,
153 double regularization_size,
154 double alpha_du,
double alpha_pr,
156 const IpoptData* ip_data,
157 IpoptCalculatedQuantities* ip_cq)
164 Index n,
const double* x,
const double* z_L,
const double* z_U,
165 Index m,
const double* g,
const double* lambda,
167 const IpoptData* ip_data,
168 IpoptCalculatedQuantities* ip_cq)
A generic optimization problem with variables, costs and constraints.
virtual bool eval_grad_f(Index n, const double *x, bool new_x, double *grad_f)
VecBound GetBoundsOnConstraints() const
The upper and lower bound of each individual constraint.
double EvaluateCostFunction(const double *x)
The scalar cost for current optimization variables x.
IpoptAdapter(Problem &nlp, bool finite_diff=false)
Creates an IpoptAdapter wrapping the nlp.
virtual bool get_bounds_info(Index n, double *x_l, double *x_u, Index m, double *g_l, double *g_u)
VectorXd GetVariableValues() const
The current value of the optimization variables.
virtual bool get_nlp_info(Index &n, Index &m, Index &nnz_jac_g, Index &nnz_h_lag, IndexStyleEnum &index_style)
namespace defined by the Ipopt solver.
VectorXd EvaluateCostFunctionGradient(const double *x)
The column-vector of derivatives of the cost w.r.t. each variable.
void SaveCurrent()
Saves the current values of the optimization variables in x_prev.
VecBound GetBoundsOnOptimizationVariables() const
The maximum and minimum value each optimization variable is allowed to have.
void SetVariables(const double *x)
Updates the variables with the values of the raw pointer x.
Jacobian GetJacobianOfConstraints() const
The sparse-matrix representation of Jacobian of the constraints.
virtual bool eval_f(Index n, const double *x, bool new_x, double &obj_value)
virtual void finalize_solution(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 IpoptData *ip_data, IpoptCalculatedQuantities *ip_cq)
Problem * nlp_
The solver independent problem definition.
virtual bool eval_jac_g(Index n, const double *x, bool new_x, Index m, Index nele_jac, Index *iRow, Index *jCol, double *values)
Problem::VectorXd VectorXd
void EvalNonzerosOfJacobian(const double *x, double *values)
Extracts those entries from constraint Jacobian that are not zero.
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)
int GetNumberOfConstraints() const
The number of individual constraints.
virtual bool eval_g(Index n, const double *x, bool new_x, Index m, double *g)
virtual bool intermediate_callback(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 IpoptData *ip_data, IpoptCalculatedQuantities *ip_cq)
VectorXd EvaluateConstraints(const double *x)
Each constraint value g(x) for current optimization variables x.
bool finite_diff_
Flag that indicates the "finite-difference-values" option is set.
int GetNumberOfOptimizationVariables() const
The number of optimization variables.