Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
Ipopt::IpoptAdapter Class Reference

Solves the optimization problem using the IPOPT solver. More...

#include <ipopt_adapter.h>

Inheritance diagram for Ipopt::IpoptAdapter:
Inheritance graph
[legend]

Public Types

using Jacobian = Problem::Jacobian
 
using Problem = ifopt::Problem
 
using VectorXd = Problem::VectorXd
 

Public Member Functions

 IpoptAdapter (Problem &nlp, bool finite_diff=false)
 Creates an IpoptAdapter wrapping the nlp. More...
 
virtual ~IpoptAdapter ()=default
 

Private Member Functions

virtual bool eval_f (Index n, const double *x, bool new_x, double &obj_value)
 
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 eval_jac_g (Index n, const double *x, bool new_x, Index m, Index nele_jac, Index *iRow, Index *jCol, double *values)
 
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_bounds_info (Index n, double *x_l, double *x_u, Index m, double *g_l, double *g_u)
 
virtual bool get_nlp_info (Index &n, Index &m, Index &nnz_jac_g, Index &nnz_h_lag, IndexStyleEnum &index_style)
 
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 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)
 

Private Attributes

bool finite_diff_
 Flag that indicates the "finite-difference-values" option is set. More...
 
Problemnlp_
 The solver independent problem definition. More...
 

Detailed Description

Solves the optimization problem using the IPOPT solver.

Given an optimization Problem with variables, costs and constraints, this class wraps it and makes it conform with the interface defined by IPOPT https://projects.coin-or.org/Ipopt

This implements the Adapter pattern. This class should not add any functionality, but merely delegate it to the Adaptee (the Problem object).

Definition at line 54 of file ipopt_adapter.h.

Member Typedef Documentation

Definition at line 58 of file ipopt_adapter.h.

Definition at line 56 of file ipopt_adapter.h.

Definition at line 57 of file ipopt_adapter.h.

Constructor & Destructor Documentation

Ipopt::IpoptAdapter::IpoptAdapter ( Problem nlp,
bool  finite_diff = false 
)

Creates an IpoptAdapter wrapping the nlp.

Parameters
nlpThe specific nonlinear programming problem.

This constructor holds and modifies the passed nlp.

Definition at line 31 of file ipopt_adapter.cc.

virtual Ipopt::IpoptAdapter::~IpoptAdapter ( )
virtualdefault

Member Function Documentation

bool Ipopt::IpoptAdapter::eval_f ( Index  n,
const double *  x,
bool  new_x,
double &  obj_value 
)
privatevirtual

Method to return the objective value

Definition at line 91 of file ipopt_adapter.cc.

bool Ipopt::IpoptAdapter::eval_g ( Index  n,
const double *  x,
bool  new_x,
Index  m,
double *  g 
)
privatevirtual

Method to return the constraint residuals

Definition at line 104 of file ipopt_adapter.cc.

bool Ipopt::IpoptAdapter::eval_grad_f ( Index  n,
const double *  x,
bool  new_x,
double *  grad_f 
)
privatevirtual

Method to return the gradient of the objective

Definition at line 97 of file ipopt_adapter.cc.

bool Ipopt::IpoptAdapter::eval_jac_g ( Index  n,
const double *  x,
bool  new_x,
Index  m,
Index  nele_jac,
Index *  iRow,
Index *  jCol,
double *  values 
)
privatevirtual

Method to return: 1) The structure of the jacobian (if "values" is NULL) 2) The values of the jacobian (if "values" is not NULL)

Definition at line 111 of file ipopt_adapter.cc.

void Ipopt::IpoptAdapter::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 
)
privatevirtual

This method is called when the algorithm is complete so the TNLP can store/write the solution

Definition at line 163 of file ipopt_adapter.cc.

bool Ipopt::IpoptAdapter::get_bounds_info ( Index  n,
double *  x_l,
double *  x_u,
Index  m,
double *  g_l,
double *  g_u 
)
privatevirtual

Method to return the bounds for my problem

Definition at line 56 of file ipopt_adapter.cc.

bool Ipopt::IpoptAdapter::get_nlp_info ( Index &  n,
Index &  m,
Index &  nnz_jac_g,
Index &  nnz_h_lag,
IndexStyleEnum &  index_style 
)
privatevirtual

Method to return some info about the nlp

Definition at line 37 of file ipopt_adapter.cc.

bool Ipopt::IpoptAdapter::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 
)
privatevirtual

Method to return the starting point for the algorithm

Definition at line 75 of file ipopt_adapter.cc.

bool Ipopt::IpoptAdapter::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 
)
privatevirtual

This is called after every iteration and is used to save intermediate solutions in the nlp

Definition at line 149 of file ipopt_adapter.cc.

Member Data Documentation

bool Ipopt::IpoptAdapter::finite_diff_
private

Flag that indicates the "finite-difference-values" option is set.

Definition at line 71 of file ipopt_adapter.h.

Problem* Ipopt::IpoptAdapter::nlp_
private

The solver independent problem definition.

Definition at line 70 of file ipopt_adapter.h.


The documentation for this class was generated from the following files:


ifopt
Author(s): Alexander W. Winkler
autogenerated on Fri Jan 22 2021 03:47:32