Public Member Functions | Protected Member Functions | Protected Attributes | List of all members

Base class for different algorithms for solving nonlinear programming (NLP) problems. More...

#include <nlp_solver.hpp>

Inheritance diagram for NLPsolver:
Inheritance graph
[legend]

Public Member Functions

virtual NLPsolverclone () const =0
 
virtual returnValue feedbackStep (const DVector &x0_, const DVector &p_=emptyConstVector)
 
virtual returnValue getAlgebraicStates (VariablesGrid &xa_) const
 
virtual returnValue getControls (VariablesGrid &u_) const
 
virtual returnValue getDifferentialStates (VariablesGrid &xd_) const
 
virtual returnValue getDisturbances (VariablesGrid &w_) const
 
virtual returnValue getFirstControl (DVector &u0_) const
 
int getNumberOfSteps () const
 
virtual double getObjectiveValue () const
 
virtual returnValue getParameters (VariablesGrid &p_) const
 
virtual returnValue getParameters (DVector &p_) const
 
virtual returnValue getSensitivitiesP (BlockMatrix &_sens) const
 
virtual returnValue getSensitivitiesU (BlockMatrix &_sens) const
 
virtual returnValue getSensitivitiesW (BlockMatrix &_sens) const
 
virtual returnValue getSensitivitiesX (BlockMatrix &_sens) const
 
virtual returnValue getSensitivitiesXA (BlockMatrix &_sens) const
 
virtual returnValue getVarianceCovariance (DMatrix &var)=0
 
virtual returnValue init (VariablesGrid *xd, VariablesGrid *xa, VariablesGrid *p, VariablesGrid *u, VariablesGrid *w)=0
 
 NLPsolver (UserInteraction *_userInteraction=0)
 
 NLPsolver (const NLPsolver &rhs)
 
NLPsolveroperator= (const NLPsolver &rhs)
 
virtual returnValue performCurrentStep ()
 
virtual returnValue prepareNextStep ()
 
returnValue resetNumberOfSteps ()
 
virtual returnValue setReference (const VariablesGrid &ref)
 
virtual returnValue shiftVariables (double timeShift, DVector lastX=emptyVector, DVector lastXA=emptyVector, DVector lastP=emptyVector, DVector lastU=emptyVector, DVector lastW=emptyVector)
 
virtual returnValue solve (const DVector &x0_=emptyConstVector, const DVector &p_=emptyConstVector)
 
virtual returnValue step (const DVector &x0_=emptyConstVector, const DVector &p_=emptyConstVector)
 
virtual ~NLPsolver ()
 
- Public Member Functions inherited from AlgorithmicBase
int addLogRecord (LogRecord &_record)
 
returnValue addOption (OptionsName name, int value)
 
returnValue addOption (OptionsName name, double value)
 
returnValue addOption (uint idx, OptionsName name, int value)
 
returnValue addOption (uint idx, OptionsName name, double value)
 
returnValue addOptionsList ()
 
 AlgorithmicBase ()
 
 AlgorithmicBase (UserInteraction *_userInteraction)
 
 AlgorithmicBase (const AlgorithmicBase &rhs)
 
returnValue get (OptionsName name, int &value) const
 
returnValue get (OptionsName name, double &value) const
 
returnValue get (OptionsName name, std::string &value) const
 
returnValue get (uint idx, OptionsName name, int &value) const
 
returnValue get (uint idx, OptionsName name, double &value) const
 
returnValue getAll (LogName _name, MatrixVariablesGrid &values) const
 
returnValue getFirst (LogName _name, DMatrix &firstValue) const
 
returnValue getFirst (LogName _name, VariablesGrid &firstValue) const
 
returnValue getLast (LogName _name, DMatrix &lastValue) const
 
returnValue getLast (LogName _name, VariablesGrid &lastValue) const
 
Options getOptions (uint idx) const
 
BooleanType haveOptionsChanged () const
 
BooleanType haveOptionsChanged (uint idx) const
 
AlgorithmicBaseoperator= (const AlgorithmicBase &rhs)
 
returnValue plot (PlotFrequency _frequency=PLOT_IN_ANY_CASE)
 
returnValue printLogRecord (std::ostream &_stream, int idx, LogPrintMode _mode=PRINT_ITEM_BY_ITEM) const
 
returnValue replot (PlotFrequency _frequency=PLOT_IN_ANY_CASE)
 
returnValue set (OptionsName name, int value)
 
returnValue set (OptionsName name, double value)
 
returnValue set (OptionsName name, const std::string &value)
 
returnValue set (uint idx, OptionsName name, int value)
 
returnValue set (uint idx, OptionsName name, double value)
 
returnValue setAll (LogName _name, const MatrixVariablesGrid &values)
 
returnValue setLast (LogName _name, int lastValue, double time=-INFTY)
 
returnValue setLast (LogName _name, double lastValue, double time=-INFTY)
 
returnValue setLast (LogName _name, const DVector &lastValue, double time=-INFTY)
 
returnValue setLast (LogName _name, const DMatrix &lastValue, double time=-INFTY)
 
returnValue setLast (LogName _name, const VariablesGrid &lastValue, double time=-INFTY)
 
returnValue setOptions (const Options &arg)
 
returnValue setOptions (uint idx, const Options &arg)
 
virtual ~AlgorithmicBase ()
 

Protected Member Functions

virtual returnValue setupLogging ()
 
virtual returnValue setupOptions ()
 

Protected Attributes

int numberOfSteps
 
- Protected Attributes inherited from AlgorithmicBase
int outputLoggingIdx
 
BooleanType useModuleStandalone
 
UserInteractionuserInteraction
 

Detailed Description

Base class for different algorithms for solving nonlinear programming (NLP) problems.

The class NLPsolver serves as a base class for all kind of different algorithms for solving nonlinear programming (NLP) problems.

Author
Boris Houska, Hans Joachim Ferreau

Definition at line 59 of file nlp_solver.hpp.

Constructor & Destructor Documentation

BEGIN_NAMESPACE_ACADO NLPsolver::NLPsolver ( UserInteraction _userInteraction = 0)

Default constructor.

Definition at line 46 of file nlp_solver.cpp.

NLPsolver::NLPsolver ( const NLPsolver rhs)

Copy constructor (deep copy).

Definition at line 59 of file nlp_solver.cpp.

NLPsolver::~NLPsolver ( )
virtual

Destructor.

Definition at line 65 of file nlp_solver.cpp.

Member Function Documentation

virtual NLPsolver* NLPsolver::clone ( ) const
pure virtual

Implemented in SCPmethod.

returnValue NLPsolver::feedbackStep ( const DVector x0_,
const DVector p_ = emptyConstVector 
)
virtual

Executes a real-time feedback step

Reimplemented in SCPmethod.

Definition at line 89 of file nlp_solver.cpp.

returnValue NLPsolver::getAlgebraicStates ( VariablesGrid xa_) const
virtual

Reimplemented in SCPmethod.

Definition at line 137 of file nlp_solver.cpp.

returnValue NLPsolver::getControls ( VariablesGrid u_) const
virtual

Reimplemented in SCPmethod.

Definition at line 154 of file nlp_solver.cpp.

returnValue NLPsolver::getDifferentialStates ( VariablesGrid xd_) const
virtual

Reimplemented in SCPmethod.

Definition at line 131 of file nlp_solver.cpp.

returnValue NLPsolver::getDisturbances ( VariablesGrid w_) const
virtual

Reimplemented in SCPmethod.

Definition at line 166 of file nlp_solver.cpp.

returnValue NLPsolver::getFirstControl ( DVector u0_) const
virtual

Reimplemented in SCPmethod.

Definition at line 160 of file nlp_solver.cpp.

int NLPsolver::getNumberOfSteps ( ) const
inline
double NLPsolver::getObjectiveValue ( ) const
virtual

Reimplemented in SCPmethod.

Definition at line 172 of file nlp_solver.cpp.

returnValue NLPsolver::getParameters ( VariablesGrid p_) const
virtual

Reimplemented in SCPmethod.

Definition at line 143 of file nlp_solver.cpp.

returnValue NLPsolver::getParameters ( DVector p_) const
virtual

Reimplemented in SCPmethod.

Definition at line 148 of file nlp_solver.cpp.

returnValue NLPsolver::getSensitivitiesP ( BlockMatrix _sens) const
virtual

Reimplemented in SCPmethod.

Definition at line 191 of file nlp_solver.cpp.

returnValue NLPsolver::getSensitivitiesU ( BlockMatrix _sens) const
virtual

Reimplemented in SCPmethod.

Definition at line 198 of file nlp_solver.cpp.

returnValue NLPsolver::getSensitivitiesW ( BlockMatrix _sens) const
virtual

Reimplemented in SCPmethod.

Definition at line 205 of file nlp_solver.cpp.

returnValue NLPsolver::getSensitivitiesX ( BlockMatrix _sens) const
virtual

Reimplemented in SCPmethod.

Definition at line 178 of file nlp_solver.cpp.

returnValue NLPsolver::getSensitivitiesXA ( BlockMatrix _sens) const
virtual

Reimplemented in SCPmethod.

Definition at line 185 of file nlp_solver.cpp.

virtual returnValue NLPsolver::getVarianceCovariance ( DMatrix var)
pure virtual

Returns a variance-covariance estimate if possible or an error message otherwise.

Returns
SUCCESSFUL_RETURN RET_MEMBER_NOT_INITIALISED

Implemented in SCPmethod.

virtual returnValue NLPsolver::init ( VariablesGrid xd,
VariablesGrid xa,
VariablesGrid p,
VariablesGrid u,
VariablesGrid w 
)
pure virtual

Initializes the problem.

Implemented in SCPmethod, and IPmethod.

NLPsolver & NLPsolver::operator= ( const NLPsolver rhs)

Assignment operator (deep copy).

Definition at line 70 of file nlp_solver.cpp.

returnValue NLPsolver::performCurrentStep ( )
virtual

Executes a real-time preparation step

Reimplemented in SCPmethod.

Definition at line 95 of file nlp_solver.cpp.

returnValue NLPsolver::prepareNextStep ( )
virtual

Executes a real-time preparation step

Reimplemented in SCPmethod.

Definition at line 101 of file nlp_solver.cpp.

returnValue NLPsolver::resetNumberOfSteps ( )
inline
returnValue NLPsolver::setReference ( const VariablesGrid ref)
virtual

Sets the reference to be used in the LSQ tracking terms. If the objective
has also non-LSQ terms a error message will be returned (cf. objective.hpp).
This routine has been designed for real-time applications where the reference
is explicitly time-dependent.

Returns
SUCCESSFUL_RETURN

Reimplemented in SCPmethod.

Definition at line 125 of file nlp_solver.cpp.

returnValue NLPsolver::setupLogging ( )
protectedvirtual

Reimplemented in SCPmethod.

Definition at line 248 of file nlp_solver.cpp.

returnValue NLPsolver::setupOptions ( )
protectedvirtual

Definition at line 217 of file nlp_solver.cpp.

returnValue NLPsolver::shiftVariables ( double  timeShift,
DVector  lastX = emptyVector,
DVector  lastXA = emptyVector,
DVector  lastP = emptyVector,
DVector  lastU = emptyVector,
DVector  lastW = emptyVector 
)
virtual

Applies a shift of the SQP data (for moving horizons)

Reimplemented in SCPmethod.

Definition at line 114 of file nlp_solver.cpp.

returnValue NLPsolver::solve ( const DVector x0_ = emptyConstVector,
const DVector p_ = emptyConstVector 
)
virtual

Solves current real-time optimization problem.

Reimplemented in SCPmethod.

Definition at line 82 of file nlp_solver.cpp.

returnValue NLPsolver::step ( const DVector x0_ = emptyConstVector,
const DVector p_ = emptyConstVector 
)
virtual

Executes a complete real-time step.

Reimplemented in SCPmethod.

Definition at line 107 of file nlp_solver.cpp.

Member Data Documentation

int NLPsolver::numberOfSteps
protected

Definition at line 185 of file nlp_solver.hpp.


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


acado
Author(s): Milan Vukov, Rien Quirynen
autogenerated on Mon Jun 10 2019 12:35:25