Go to the documentation of this file.
38 Index& nnz_h_lag, IndexStyleEnum& index_style)
51 index_style = C_STYLE;
57 Index m,
double* g_l,
double* g_u)
60 for (std::size_t 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 (std::size_t 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,
double* lambda)
80 assert(init_x ==
true);
81 assert(init_z ==
false);
82 assert(init_lambda ==
false);
85 Eigen::Map<VectorXd>(&x[0], x_all.rows()) = x_all;
101 Eigen::Map<Eigen::MatrixXd>(grad_f, n, 1) = grad;
109 Eigen::Map<VectorXd>(g, m) = g_eig;
114 Index nele_jac, Index* iRow, Index* jCol,
118 if (values == NULL) {
122 for (Index row = 0; row < m; row++) {
123 for (Index col = 0; col < n; col++) {
131 for (
int k = 0; k < jac.outerSize(); ++k) {
132 for (Jacobian::InnerIterator it(jac, k); it; ++it) {
133 iRow[nele] = it.row();
134 jCol[nele] = it.col();
151 AlgorithmMode mode, Index iter,
double obj_value,
double inf_pr,
152 double inf_du,
double mu,
double d_norm,
double regularization_size,
153 double alpha_du,
double alpha_pr, Index ls_trials,
const IpoptData* ip_data,
154 IpoptCalculatedQuantities* ip_cq)
161 const double* x,
const double* z_L,
162 const double* z_U, Index m,
163 const double* g,
const double* lambda,
164 double obj_value,
const IpoptData* ip_data,
165 IpoptCalculatedQuantities* ip_cq)
int GetNumberOfOptimizationVariables() const
The number of optimization variables.
double EvaluateCostFunction(const double *x)
The scalar cost for current optimization variables x.
void SetVariables(const double *x)
Updates the variables with the values of the raw pointer x.
VectorXd EvaluateCostFunctionGradient(const double *x, bool use_finite_difference_approximation=false, double epsilon=std::numeric_limits< double >::epsilon())
The column-vector of derivatives of the cost w.r.t. each variable.
VecBound GetBoundsOnConstraints() const
The upper and lower bound of each individual constraint.
void EvalNonzerosOfJacobian(const double *x, double *values)
Extracts those entries from constraint Jacobian that are not zero.
namespace defined by the Ipopt solver.
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)
int GetNumberOfConstraints() const
The number of individual constraints.
Jacobian GetJacobianOfConstraints() const
The sparse-matrix representation of Jacobian of the constraints.
VectorXd EvaluateConstraints(const double *x)
Each constraint value g(x) for current optimization variables x.
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)
VecBound GetBoundsOnOptimizationVariables() const
The maximum and minimum value each optimization variable is allowed to have.
virtual bool eval_f(Index n, const double *x, bool new_x, double &obj_value)
IpoptAdapter(Problem &nlp, bool finite_diff=false)
Creates an IpoptAdapter wrapping the nlp.
bool finite_diff_
Flag that indicates the "finite-difference-values" option is set.
void SaveCurrent()
Saves the current values of the optimization variables in x_prev.
virtual bool get_bounds_info(Index n, double *x_l, double *x_u, Index m, double *g_l, double *g_u)
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)
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)
Problem::VectorXd VectorXd
virtual bool eval_g(Index n, const double *x, bool new_x, Index m, double *g)
virtual bool eval_grad_f(Index n, const double *x, bool new_x, double *grad_f)
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)
ifopt
Author(s): Alexander W. Winkler
autogenerated on Mon Sep 18 2023 02:14:38