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

Solves the optimization problem with the new SNOPT 7.6 version. More...

#include <snopt76_adapter.h>

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

Public Types

using Jacobian = Problem::Jacobian
 
using Jacobian = Problem::Jacobian
 
using NLPPtr = Problem *
 
using NLPPtr = Problem *
 
using VectorXd = Problem::VectorXd
 
using VectorXd = Problem::VectorXd
 

Public Member Functions

 SnoptAdapter (Problem &nlp)
 Creates an Adapter Object around the problem to conform to the Snopt interface. More...
 
 SnoptAdapter (Problem &nlp)
 Creates an Adapter Object around the problem to conform to the Snopt interface. More...
 
virtual ~SnoptAdapter ()=default
 
virtual ~SnoptAdapter ()=default
 

Static Public Member Functions

static void Solve (Problem &nlp)
 Creates a snoptProblemA from nlp and solves it. More...
 
static void Solve (Problem &nlp)
 Creates a snoptProblemA from nlp and solves it. More...
 

Protected Attributes

double * A
 
double * F
 
double * Flow
 
double * Fmul
 
int * Fstate
 
double * Fupp
 
int * iAfun
 
int * iGfun
 
int jacComputed = 0
 
int * jAvar
 
int * jGvar
 
int lenA
 
int lenG
 
int n = 0
 
int neA
 
int neF = 0
 
int neG
 
double ObjAdd
 
int ObjRow
 
double * x
 
double * xlow
 
double * xmul
 
int * xstate
 
double * xupp
 

Private Member Functions

void Init ()
 
void Init ()
 
void SetVariables ()
 
void SetVariables ()
 

Static Private Member Functions

static void ObjectiveAndConstraintFct (int *Status, int *n, double x[], int *needF, int *neF, double F[], int *needG, int *neG, double G[], char *cu, int *lencu, int iu[], int *leniu, double ru[], int *lenru)
 
static void ObjectiveAndConstraintFct (int *Status, int *n, double x[], int *needF, int *neF, double F[], int *needG, int *neG, double G[], char *cu, int *lencu, int iu[], int *leniu, double ru[], int *lenru)
 
static void SetOptions (SnoptAdapter &)
 Sets solver settings for Snopt. More...
 
static void SetOptions (SnoptAdapter &)
 Sets solver settings for Snopt. More...
 

Static Private Attributes

static NLPPtr nlp_
 

Detailed Description

Solves the optimization problem with the new SNOPT 7.6 version.

Solves the optimization problem with SNOPT version 7.5 and below.

If you have an older of version of SNOPT installed, use snopt_adapter.h.

Given an optimization Problem with variables, costs and constraints, this class wraps it and makes it conform with the interface defined by SNOPT http://web.stanford.edu/group/SOL/guides/sndoc7.pdf

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

If you have a newer version of SNOPT installed, use snopt_adapter_76.h.

Given an optimization Problem with variables, costs and constraints, this class wraps it and makes it conform with the interface defined by SNOPT http://web.stanford.edu/group/SOL/guides/sndoc7.pdf

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 snopt76_adapter.h.

Member Typedef Documentation

Definition at line 54 of file snopt76_adapter.h.

Definition at line 54 of file snopt_adapter.h.

Definition at line 52 of file snopt_adapter.h.

Definition at line 52 of file snopt76_adapter.h.

Definition at line 53 of file snopt76_adapter.h.

Definition at line 53 of file snopt_adapter.h.

Constructor & Destructor Documentation

ifopt::SnoptAdapter::SnoptAdapter ( Problem nlp)

Creates an Adapter Object around the problem to conform to the Snopt interface.

Definition at line 84 of file snopt76_adapter.cc.

virtual ifopt::SnoptAdapter::~SnoptAdapter ( )
virtualdefault
ifopt::SnoptAdapter::SnoptAdapter ( Problem nlp)

Creates an Adapter Object around the problem to conform to the Snopt interface.

virtual ifopt::SnoptAdapter::~SnoptAdapter ( )
virtualdefault

Member Function Documentation

void ifopt::SnoptAdapter::Init ( )
private

Definition at line 90 of file snopt76_adapter.cc.

void ifopt::SnoptAdapter::Init ( )
private
void ifopt::SnoptAdapter::ObjectiveAndConstraintFct ( int *  Status,
int *  n,
double  x[],
int *  needF,
int *  neF,
double  F[],
int *  needG,
int *  neG,
double  G[],
char *  cu,
int *  lencu,
int  iu[],
int *  leniu,
double  ru[],
int *  lenru 
)
staticprivate

Definition at line 181 of file snopt76_adapter.cc.

static void ifopt::SnoptAdapter::ObjectiveAndConstraintFct ( int *  Status,
int *  n,
double  x[],
int *  needF,
int *  neF,
double  F[],
int *  needG,
int *  neG,
double  G[],
char *  cu,
int *  lencu,
int  iu[],
int *  leniu,
double  ru[],
int *  lenru 
)
staticprivate
static void ifopt::SnoptAdapter::SetOptions ( SnoptAdapter )
staticprivate

Sets solver settings for Snopt.

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://web.stanford.edu/group/SOL/guides/sndoc7.pdf

void ifopt::SnoptAdapter::SetOptions ( SnoptAdapter solver)
staticprivate

Sets solver settings for Snopt.

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://web.stanford.edu/group/SOL/guides/sndoc7.pdf

Definition at line 67 of file snopt76_adapter.cc.

void ifopt::SnoptAdapter::SetVariables ( )
private

Definition at line 217 of file snopt76_adapter.cc.

void ifopt::SnoptAdapter::SetVariables ( )
private
static void ifopt::SnoptAdapter::Solve ( Problem nlp)
static

Creates a snoptProblemA from nlp and solves it.

Parameters
[in/out]nlp The specific problem to be used and modified.
void ifopt::SnoptAdapter::Solve ( Problem nlp)
static

Creates a snoptProblemA from nlp and solves it.

Parameters
[in/out]nlp The specific problem to be used and modified.

Definition at line 34 of file snopt76_adapter.cc.

Member Data Documentation

double* ifopt::SnoptAdapter::A
protected

Definition at line 113 of file snopt76_adapter.h.

double* ifopt::SnoptAdapter::F
protected

Definition at line 107 of file snopt76_adapter.h.

double * ifopt::SnoptAdapter::Flow
protected

Definition at line 107 of file snopt76_adapter.h.

double * ifopt::SnoptAdapter::Fmul
protected

Definition at line 107 of file snopt76_adapter.h.

int * ifopt::SnoptAdapter::Fstate
protected

Definition at line 109 of file snopt76_adapter.h.

double * ifopt::SnoptAdapter::Fupp
protected

Definition at line 107 of file snopt76_adapter.h.

int* ifopt::SnoptAdapter::iAfun
protected

Definition at line 112 of file snopt76_adapter.h.

int * ifopt::SnoptAdapter::iGfun
protected

Definition at line 112 of file snopt76_adapter.h.

int ifopt::SnoptAdapter::jacComputed = 0
protected

Definition at line 100 of file snopt76_adapter.h.

int * ifopt::SnoptAdapter::jAvar
protected

Definition at line 112 of file snopt76_adapter.h.

int * ifopt::SnoptAdapter::jGvar
protected

Definition at line 112 of file snopt76_adapter.h.

int ifopt::SnoptAdapter::lenA
protected

Definition at line 111 of file snopt76_adapter.h.

int ifopt::SnoptAdapter::lenG
protected

Definition at line 111 of file snopt76_adapter.h.

int ifopt::SnoptAdapter::n = 0
protected

Definition at line 101 of file snopt76_adapter.h.

int ifopt::SnoptAdapter::neA
protected

Definition at line 111 of file snopt76_adapter.h.

int ifopt::SnoptAdapter::neF = 0
protected

Definition at line 102 of file snopt76_adapter.h.

int ifopt::SnoptAdapter::neG
protected

Definition at line 111 of file snopt76_adapter.h.

SnoptAdapter::NLPPtr ifopt::SnoptAdapter::nlp_
staticprivate

Definition at line 93 of file snopt76_adapter.h.

double ifopt::SnoptAdapter::ObjAdd
protected

Definition at line 104 of file snopt76_adapter.h.

int ifopt::SnoptAdapter::ObjRow
protected

Definition at line 103 of file snopt76_adapter.h.

double* ifopt::SnoptAdapter::x
protected

Definition at line 106 of file snopt76_adapter.h.

double * ifopt::SnoptAdapter::xlow
protected

Definition at line 106 of file snopt76_adapter.h.

double * ifopt::SnoptAdapter::xmul
protected

Definition at line 106 of file snopt76_adapter.h.

int* ifopt::SnoptAdapter::xstate
protected

Definition at line 109 of file snopt76_adapter.h.

double * ifopt::SnoptAdapter::xupp
protected

Definition at line 106 of file snopt76_adapter.h.


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


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