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

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

#include <ipopt_adapter.h>

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

Public Types

using Index = Ipopt::Index
 
using Jacobian = Problem::Jacobian
 
using VectorXd = Problem::VectorXd
 

Static Public Member Functions

static void Solve (Problem &nlp)
 Creates an IpoptAdapter and solves the NLP. More...
 

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 (Ipopt::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 Ipopt::IpoptData *ip_data, Ipopt::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 (Ipopt::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 Ipopt::IpoptData *ip_data, Ipopt::IpoptCalculatedQuantities *ip_cq)
 
 IpoptAdapter (Problem &nlp)
 Creates an IpoptAdapter wrapping the nlp. More...
 
virtual ~IpoptAdapter ()=default
 

Static Private Member Functions

static void SetOptions (Ipopt::SmartPtr< Ipopt::IpoptApplication > app)
 Defines settings for the Ipopt solver app. More...
 

Private Attributes

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 50 of file ipopt_adapter.h.

Member Typedef Documentation

using ifopt::IpoptAdapter::Index = Ipopt::Index

Definition at line 52 of file ipopt_adapter.h.

Definition at line 54 of file ipopt_adapter.h.

Definition at line 53 of file ipopt_adapter.h.

Constructor & Destructor Documentation

ifopt::IpoptAdapter::IpoptAdapter ( Problem nlp)
private

Creates an IpoptAdapter wrapping the nlp.

Parameters
nlpThe specific nonlinear programming problem.

This constructor holds and modifies the passed nlp.

Definition at line 81 of file ipopt_adapter.cc.

virtual ifopt::IpoptAdapter::~IpoptAdapter ( )
privatevirtualdefault

Member Function Documentation

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

Method to return the objective value

Definition at line 136 of file ipopt_adapter.cc.

bool ifopt::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 149 of file ipopt_adapter.cc.

bool ifopt::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 142 of file ipopt_adapter.cc.

bool ifopt::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 156 of file ipopt_adapter.cc.

void ifopt::IpoptAdapter::finalize_solution ( Ipopt::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 Ipopt::IpoptData *  ip_data,
Ipopt::IpoptCalculatedQuantities *  ip_cq 
)
privatevirtual

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

Definition at line 197 of file ipopt_adapter.cc.

bool ifopt::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 101 of file ipopt_adapter.cc.

bool ifopt::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 86 of file ipopt_adapter.cc.

bool ifopt::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 120 of file ipopt_adapter.cc.

bool ifopt::IpoptAdapter::intermediate_callback ( Ipopt::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 Ipopt::IpoptData *  ip_data,
Ipopt::IpoptCalculatedQuantities *  ip_cq 
)
privatevirtual

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

Definition at line 183 of file ipopt_adapter.cc.

void ifopt::IpoptAdapter::SetOptions ( Ipopt::SmartPtr< Ipopt::IpoptApplication >  app)
staticprivate

Defines settings for the Ipopt solver app.

Parameters
appThe actual Ipopt solver.

These settings include which QP solver to use, if gradients should be approximated or the provided analytical ones used, when the iterations should be terminated,...

A complete list of options can be found at: https://www.coin-or.org/Ipopt/documentation/node40.html

Definition at line 60 of file ipopt_adapter.cc.

void ifopt::IpoptAdapter::Solve ( Problem nlp)
static

Creates an IpoptAdapter and solves the NLP.

Parameters
[in/out]nlp The specific problem.

This function creates the actual solver, sets the solver specific options (see SetOptions()) and passes the IpoptAdapter problem to it to be modified.

Definition at line 32 of file ipopt_adapter.cc.

Member Data Documentation

Problem* ifopt::IpoptAdapter::nlp_
private

The solver independent problem definition.

Definition at line 79 of file ipopt_adapter.h.


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


ifopt_ipopt
Author(s): Alexander W. Winkler
autogenerated on Fri Apr 20 2018 02:27:35