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

Base class for export of NLP/OCP solvers. More...

#include <export_nlp_solver.hpp>

Inheritance diagram for ExportNLPSolver:
Inheritance graph
[legend]

Public Member Functions

 ExportNLPSolver (UserInteraction *_userInteraction=0, const std::string &_commonHeaderName="")
 
virtual returnValue getCode (ExportStatementBlock &code)=0
 
virtual returnValue getDataDeclarations (ExportStatementBlock &declarations, ExportStruct dataStruct=ACADO_ANY) const
 
virtual returnValue getFunctionDeclarations (ExportStatementBlock &declarations) const =0
 
unsigned getNumComplexConstraints (void)
 
unsigned getNumPathConstraints (void)
 
virtual unsigned getNumQPvars () const =0
 
bool initialStateFixed () const
 
bool performsSingleShooting () const
 
returnValue setConstraints (const OCP &_ocp)
 
returnValue setGeneralObjective (const Objective &_objective)
 
returnValue setIntegratorExport (IntegratorExportPtr const _integrator)
 
returnValue setLevenbergMarquardt (double _levenbergMarquardt)
 
returnValue setLSQObjective (const Objective &_objective)
 
returnValue setObjective (const Objective &_objective)
 
virtual returnValue setup ()=0
 
bool usingLinearTerms () const
 
unsigned weightingMatricesType (void) const
 
virtual ~ExportNLPSolver ()
 
- Public Member Functions inherited from ExportAlgorithm
 ExportAlgorithm (UserInteraction *_userInteraction=0, const std::string &_commonHeaderName=std::string())
 
uint getN () const
 
uint getNDX () const
 
uint getNOD () const
 
uint getNP () const
 
uint getNU () const
 
uint getNX () const
 
uint getNXA () const
 
uint getNY () const
 
uint getNYN () const
 
returnValue setDimensions (uint _NX=0, uint _NU=0, uint _NP=0, uint _NI=0, uint _NOD=0)
 
returnValue setDimensions (uint _NX, uint _NDX, uint _NXA, uint _NU, uint _NP, uint _NI, uint _NOD)
 
void setNY (uint NY_)
 
void setNYN (uint NYN_)
 
virtual ~ExportAlgorithm ()
 
- 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

returnValue setupArrivalCostCalculation ()
 
returnValue setupAuxiliaryFunctions ()
 
virtual returnValue setupConstraintsEvaluation ()=0
 
virtual returnValue setupEvaluation ()=0
 
virtual returnValue setupGetGeneralObjective ()
 
virtual returnValue setupGetLSQObjective ()
 
virtual returnValue setupGetObjective ()
 
virtual returnValue setupInitialization ()
 
virtual returnValue setupMultiplicationRoutines ()=0
 
virtual returnValue setupSimulation (void)
 
virtual returnValue setupVariables ()=0
 

Protected Attributes

Evaluation of model dynamics.
IntegratorExportPtr integrator
 
ExportFunction modelSimulation
 
ExportVariable state
 
ExportVariable x
 
ExportVariable z
 
ExportVariable u
 
ExportVariable od
 
ExportVariable d
 
ExportVariable evGx
 
ExportVariable evGu
 
Evaluation of objective
double levenbergMarquardt
 
ExportVariable y
 
ExportVariable yN
 
ExportVariable Dy
 
ExportVariable DyN
 
ExportVariable mu
 
ExportVariable objg
 
ExportVariable objS
 
ExportVariable objSEndTerm
 
ExportVariable objEvFx
 
ExportVariable objEvFu
 
ExportVariable objEvFxEnd
 
ExportVariable objEvFxx
 
ExportVariable objEvFxu
 
ExportVariable objEvFuu
 
ExportVariable objEvFxxEnd
 
ExportVariable objAuxVar
 
ExportVariable objValueIn
 
ExportVariable objValueOut
 
ExportAcadoFunction evaluateStageCost
 
ExportAcadoFunction evaluateTerminalCost
 
ExportVariable Q1
 
ExportVariable Q2
 
ExportVariable R1
 
ExportVariable R2
 
ExportVariable S1
 
ExportVariable QN1
 
ExportVariable QN2
 
ExportVariable objSlx
 
ExportVariable objSlu
 
bool diagonalH
 
bool diagonalHN
 
Evaluation of box constraints
VariablesGrid uBounds
 
VariablesGrid xBounds
 
Evaluation of path constraints
unsigned dimPacH
 
ExportAcadoFunction evaluatePathConstraints
 
ExportVariable conAuxVar
 
ExportVariable conValueIn
 
ExportVariable conValueOut
 
DVector lbPathConValues
 
DVector ubPathConValues
 
ExportVariable pacEvH
 
ExportVariable pacEvHx
 
ExportVariable pacEvHu
 
ExportVariable pacEvHxd
 
ExportVariable pacEvDDH
 
Evaluation of point constraints
unsigned dimPocH
 
std::vector< std::shared_ptr< ExportAcadoFunction > > evaluatePointConstraints
 
DVector lbPointConValues
 
DVector ubPointConValues
 
std::vector< DVectorpocLbStack
 
std::vector< DVectorpocUbStack
 
ExportVariable pocEvH
 
ExportVariable pocEvHx
 
ExportVariable pocEvHu
 
ExportVariable pocEvHxd
 
Auxiliary functions
ExportFunction initialize
 
ExportFunction shiftStates
 
ExportFunction shiftControls
 
ExportFunction getObjective
 
ExportFunction initializeNodes
 
Arrival cost related
ExportFunction updateArrivalCost
 
ExportCholeskyDecomposition cholObjS
 
ExportCholeskyDecomposition cholSAC
 
ExportHouseholderQR acSolver
 
ExportVariable acA
 
ExportVariable acb
 
ExportVariable acP
 
ExportVariable acTmp
 
ExportVariable acWL
 
ExportVariable acVL
 
ExportVariable acHx
 
ExportVariable acHu
 
ExportVariable acXx
 
ExportVariable acXu
 
ExportVariable acXTilde
 
ExportVariable acHTilde
 
ExportVariable SAC
 
ExportVariable xAC
 
ExportVariable DxAC
 
ExportFunction regularizeHessian
 
ExportFunction regularization
 
- Protected Attributes inherited from ExportAlgorithm
std::string commonHeaderName
 
uint N
 
uint NDX
 
uint NOD
 
uint NP
 
uint NU
 
uint NX
 
uint NXA
 
uint NY
 
uint NYN
 
- Protected Attributes inherited from AlgorithmicBase
int outputLoggingIdx
 
BooleanType useModuleStandalone
 
UserInteractionuserInteraction
 

Private Member Functions

returnValue setupObjectiveLinearTerms (const Objective &_objective)
 
returnValue setupResidualVariables ()
 

Detailed Description

Base class for export of NLP/OCP solvers.

This base class is basically used to extract information from an OCP object and prepare low level structures. Later, a derived class is actually building the solver to solve an OCP problem.

Author
Milan Vukov
Note
Based on code originally developed by Boris Houska and Hand Joachim Ferreau.

Definition at line 62 of file export_nlp_solver.hpp.

Constructor & Destructor Documentation

ExportNLPSolver::ExportNLPSolver ( UserInteraction _userInteraction = 0,
const std::string &  _commonHeaderName = "" 
)

Default constructor.

@param[in] _userInteraction         Pointer to corresponding user interface.
@param[in] _commonHeaderName        Name of common header file to be included.

Definition at line 41 of file export_nlp_solver.cpp.

virtual ExportNLPSolver::~ExportNLPSolver ( )
inlinevirtual

Destructor.

Definition at line 76 of file export_nlp_solver.hpp.

Member Function Documentation

virtual returnValue ExportNLPSolver::getCode ( ExportStatementBlock code)
pure virtual

Exports source code of the auto-generated condensing algorithm into the given directory.

@param[in] code                             Code block containing the auto-generated condensing algorithm.

\return SUCCESSFUL_RETURN

Implements ExportAlgorithm.

Implemented in ExportGaussNewtonForces, ExportGaussNewtonQpDunes, ExportGaussNewtonCondensed, ExportGaussNewtonHpmpc, ExportGaussNewtonBlockCN2, ExportGaussNewtonCn2Factorization, ExportGaussNewtonGeneric, ExportGaussNewtonCN2, ExportExactHessianQpDunes, ExportGaussNewtonBlockForces, and ExportGaussNewtonBlockQpDunes.

returnValue ExportNLPSolver::getDataDeclarations ( ExportStatementBlock declarations,
ExportStruct  dataStruct = ACADO_ANY 
) const
virtual

Adds all data declarations of the auto-generated condensing algorithm to given list of declarations.

Parameters
[in]declarationsList of declarations.
Returns
SUCCESSFUL_RETURN

Implements ExportAlgorithm.

Reimplemented in ExportGaussNewtonForces, ExportGaussNewtonQpDunes, ExportGaussNewtonCondensed, ExportGaussNewtonHpmpc, ExportGaussNewtonBlockCN2, ExportGaussNewtonCn2Factorization, ExportGaussNewtonGeneric, and ExportGaussNewtonCN2.

Definition at line 89 of file export_nlp_solver.cpp.

virtual returnValue ExportNLPSolver::getFunctionDeclarations ( ExportStatementBlock declarations) const
pure virtual

Adds all function (forward) declarations of the auto-generated condensing algorithm to given list of declarations.

Parameters
[in]declarationsList of declarations.
Returns
SUCCESSFUL_RETURN

Implements ExportAlgorithm.

Implemented in ExportGaussNewtonForces, ExportGaussNewtonQpDunes, ExportGaussNewtonCondensed, ExportGaussNewtonHpmpc, ExportGaussNewtonBlockCN2, ExportGaussNewtonCn2Factorization, ExportGaussNewtonGeneric, ExportGaussNewtonCN2, ExportExactHessianQpDunes, and ExportExactHessianCN2.

unsigned ExportNLPSolver::getNumComplexConstraints ( void  )

Get the number of complex constraints - path + point constraints.

Returns
Number of complex constraints

Definition at line 1579 of file export_nlp_solver.cpp.

unsigned ExportNLPSolver::getNumPathConstraints ( void  )

Get the number of path constraints.

Returns
Number of path constraints

Definition at line 1584 of file export_nlp_solver.cpp.

virtual unsigned ExportNLPSolver::getNumQPvars ( ) const
pure virtual
bool ExportNLPSolver::initialStateFixed ( ) const

Indicates whether initial state is fixed.

Definition at line 1589 of file export_nlp_solver.cpp.

bool ExportNLPSolver::performsSingleShooting ( ) const

Returns whether a single shooting state discretization is used.

\return true  iff single shooting state discretization is used, \n
        false otherwise

Definition at line 78 of file export_nlp_solver.cpp.

returnValue ExportNLPSolver::setConstraints ( const OCP _ocp)

Set the "complex" path and point constraints

Returns
SUCCESSFUL_RETURN

Definition at line 1227 of file export_nlp_solver.cpp.

returnValue ExportNLPSolver::setGeneralObjective ( const Objective _objective)

Definition at line 456 of file export_nlp_solver.cpp.

returnValue ExportNLPSolver::setIntegratorExport ( IntegratorExportPtr const  _integrator)

Assigns module for exporting a tailored integrator.

@param[in] _integrator      Integrator module.

\return SUCCESSFUL_RETURN

Definition at line 55 of file export_nlp_solver.cpp.

returnValue ExportNLPSolver::setLevenbergMarquardt ( double  _levenbergMarquardt)

Assigns new constant for Levenberg-Marquardt regularization.

@param[in] _levenbergMarquardt              Non-negative constant for Levenberg-Marquardt regularization.

\return SUCCESSFUL_RETURN

Definition at line 62 of file export_nlp_solver.cpp.

returnValue ExportNLPSolver::setLSQObjective ( const Objective _objective)

Definition at line 715 of file export_nlp_solver.cpp.

returnValue ExportNLPSolver::setObjective ( const Objective _objective)

Set objective function

Returns
SUCCESSFUL_RETURN,
RET_INITIALIZE_FIRST,
RET_INVALID_OBJECTIVE_FOR_CODE_EXPORT,
RET_INVALID_ARGUMENTS

Definition at line 445 of file export_nlp_solver.cpp.

virtual returnValue ExportNLPSolver::setup ( )
pure virtual
returnValue ExportNLPSolver::setupArrivalCostCalculation ( )
protected

Setup of functions and variables for evaluation of arrival cost.

Definition at line 1938 of file export_nlp_solver.cpp.

returnValue ExportNLPSolver::setupAuxiliaryFunctions ( )
protected

Setup of functions for evaluation of auxiliary functions.

Definition at line 1605 of file export_nlp_solver.cpp.

virtual returnValue ExportNLPSolver::setupConstraintsEvaluation ( )
protectedpure virtual
virtual returnValue ExportNLPSolver::setupEvaluation ( )
protectedpure virtual
returnValue ExportNLPSolver::setupGetGeneralObjective ( )
protectedvirtual

Setup the function for evaluating the actual objective value.

Definition at line 1876 of file export_nlp_solver.cpp.

returnValue ExportNLPSolver::setupGetLSQObjective ( )
protectedvirtual

Setup the function for evaluating the actual LSQ objective value.

Definition at line 1788 of file export_nlp_solver.cpp.

returnValue ExportNLPSolver::setupGetObjective ( )
protectedvirtual

Setup the function for evaluating the actual objective value.

Definition at line 1777 of file export_nlp_solver.cpp.

returnValue ExportNLPSolver::setupInitialization ( )
protectedvirtual

Setup main initialization code for the solver

Definition at line 165 of file export_nlp_solver.cpp.

virtual returnValue ExportNLPSolver::setupMultiplicationRoutines ( )
protectedpure virtual

Exports source code containing the multiplication routines of the algorithm.

\return SUCCESSFUL_RETURN

Implemented in ExportGaussNewtonCondensed, ExportGaussNewtonForces, ExportGaussNewtonCn2Factorization, ExportGaussNewtonCN2, ExportGaussNewtonQpDunes, ExportGaussNewtonBlockCN2, ExportGaussNewtonHpmpc, and ExportGaussNewtonGeneric.

returnValue ExportNLPSolver::setupObjectiveLinearTerms ( const Objective _objective)
private

Definition at line 1150 of file export_nlp_solver.cpp.

returnValue ExportNLPSolver::setupResidualVariables ( )
private

Definition at line 1214 of file export_nlp_solver.cpp.

returnValue ExportNLPSolver::setupSimulation ( void  )
protectedvirtual

Setting up of a model simulation:

  • model integration
  • sensitivity generation
Returns
SUCCESSFUL_RETURN

Definition at line 193 of file export_nlp_solver.cpp.

virtual returnValue ExportNLPSolver::setupVariables ( )
protectedpure virtual
bool ExportNLPSolver::usingLinearTerms ( ) const

Indicates whether linear terms in the objective are used.

Definition at line 1597 of file export_nlp_solver.cpp.

unsigned ExportNLPSolver::weightingMatricesType ( void  ) const

Return type of weighting matrices.

Returns
Type of weighting matrices.

Definition at line 1924 of file export_nlp_solver.cpp.

Member Data Documentation

ExportVariable ExportNLPSolver::acA
protected

Definition at line 338 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::acb
protected

Definition at line 338 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::acHTilde
protected

Definition at line 340 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::acHu
protected

Definition at line 340 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::acHx
protected

Definition at line 340 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::acP
protected

Definition at line 338 of file export_nlp_solver.hpp.

ExportHouseholderQR ExportNLPSolver::acSolver
protected

Definition at line 336 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::acTmp
protected

Definition at line 338 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::acVL
protected

Definition at line 340 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::acWL
protected

Definition at line 340 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::acXTilde
protected

Definition at line 340 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::acXu
protected

Definition at line 340 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::acXx
protected

Definition at line 340 of file export_nlp_solver.hpp.

ExportCholeskyDecomposition ExportNLPSolver::cholObjS
protected

Definition at line 333 of file export_nlp_solver.hpp.

ExportCholeskyDecomposition ExportNLPSolver::cholSAC
protected

Definition at line 334 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::conAuxVar
protected

Definition at line 294 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::conValueIn
protected

Definition at line 295 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::conValueOut
protected

Definition at line 296 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::d
protected

Definition at line 247 of file export_nlp_solver.hpp.

bool ExportNLPSolver::diagonalH
protected

Definition at line 280 of file export_nlp_solver.hpp.

bool ExportNLPSolver::diagonalHN
protected

Definition at line 280 of file export_nlp_solver.hpp.

unsigned ExportNLPSolver::dimPacH
protected

Definition at line 292 of file export_nlp_solver.hpp.

unsigned ExportNLPSolver::dimPocH
protected

Definition at line 307 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::DxAC
protected

Definition at line 343 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::Dy
protected

Definition at line 260 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::DyN
protected

Definition at line 260 of file export_nlp_solver.hpp.

ExportAcadoFunction ExportNLPSolver::evaluatePathConstraints
protected

Definition at line 293 of file export_nlp_solver.hpp.

std::vector< std::shared_ptr< ExportAcadoFunction > > ExportNLPSolver::evaluatePointConstraints
protected

Definition at line 308 of file export_nlp_solver.hpp.

ExportAcadoFunction ExportNLPSolver::evaluateStageCost
protected

Definition at line 270 of file export_nlp_solver.hpp.

ExportAcadoFunction ExportNLPSolver::evaluateTerminalCost
protected

Definition at line 271 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::evGu
protected

Definition at line 250 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::evGx
protected

Definition at line 249 of file export_nlp_solver.hpp.

ExportFunction ExportNLPSolver::getObjective
protected

Definition at line 325 of file export_nlp_solver.hpp.

ExportFunction ExportNLPSolver::initialize
protected

Main initialization function for the solver.

Definition at line 321 of file export_nlp_solver.hpp.

ExportFunction ExportNLPSolver::initializeNodes
protected

Definition at line 326 of file export_nlp_solver.hpp.

IntegratorExportPtr ExportNLPSolver::integrator
protected

Module for exporting a tailored integrator.

Definition at line 238 of file export_nlp_solver.hpp.

DVector ExportNLPSolver::lbPathConValues
protected

Definition at line 298 of file export_nlp_solver.hpp.

DVector ExportNLPSolver::lbPointConValues
protected

Definition at line 309 of file export_nlp_solver.hpp.

double ExportNLPSolver::levenbergMarquardt
protected

Non-negative constant for Levenberg-Marquardt regularization.

Definition at line 258 of file export_nlp_solver.hpp.

ExportFunction ExportNLPSolver::modelSimulation
protected

Definition at line 240 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::mu
protected

Definition at line 263 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::objAuxVar
protected

Definition at line 269 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::objEvFu
protected

Definition at line 266 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::objEvFuu
protected

Definition at line 267 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::objEvFx
protected

Definition at line 266 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::objEvFxEnd
protected

Definition at line 266 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::objEvFxu
protected

Definition at line 267 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::objEvFxx
protected

Definition at line 267 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::objEvFxxEnd
protected

Definition at line 267 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::objg
protected

Definition at line 265 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::objS
protected

Definition at line 265 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::objSEndTerm
protected

Definition at line 265 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::objSlu
protected

Definition at line 278 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::objSlx
protected

Definition at line 278 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::objValueIn
protected

Definition at line 269 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::objValueOut
protected

Definition at line 269 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::od
protected

Definition at line 246 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::pacEvDDH
protected

Definition at line 302 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::pacEvH
protected

Definition at line 300 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::pacEvHu
protected

Definition at line 301 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::pacEvHx
protected

Definition at line 301 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::pacEvHxd
protected

Definition at line 301 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::pocEvH
protected

Definition at line 313 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::pocEvHu
protected

Definition at line 314 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::pocEvHx
protected

Definition at line 314 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::pocEvHxd
protected

Definition at line 314 of file export_nlp_solver.hpp.

std::vector< DVector > ExportNLPSolver::pocLbStack
protected

Definition at line 311 of file export_nlp_solver.hpp.

std::vector< DVector > ExportNLPSolver::pocUbStack
protected

Definition at line 311 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::Q1
protected

Definition at line 273 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::Q2
protected

Definition at line 273 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::QN1
protected

Definition at line 276 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::QN2
protected

Definition at line 276 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::R1
protected

Definition at line 274 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::R2
protected

Definition at line 274 of file export_nlp_solver.hpp.

ExportFunction ExportNLPSolver::regularization
protected

Definition at line 346 of file export_nlp_solver.hpp.

ExportFunction ExportNLPSolver::regularizeHessian
protected

Definition at line 345 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::S1
protected

Definition at line 275 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::SAC
protected

Definition at line 343 of file export_nlp_solver.hpp.

ExportFunction ExportNLPSolver::shiftControls
protected

Definition at line 324 of file export_nlp_solver.hpp.

ExportFunction ExportNLPSolver::shiftStates
protected

Definition at line 323 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::state
protected

Definition at line 242 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::u
protected

Definition at line 245 of file export_nlp_solver.hpp.

VariablesGrid ExportNLPSolver::uBounds
protected

Definition at line 286 of file export_nlp_solver.hpp.

DVector ExportNLPSolver::ubPathConValues
protected

Definition at line 298 of file export_nlp_solver.hpp.

DVector ExportNLPSolver::ubPointConValues
protected

Definition at line 309 of file export_nlp_solver.hpp.

ExportFunction ExportNLPSolver::updateArrivalCost
protected

Definition at line 331 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::x
protected

Definition at line 243 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::xAC
protected

Definition at line 343 of file export_nlp_solver.hpp.

VariablesGrid ExportNLPSolver::xBounds
protected

Definition at line 287 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::y
protected

Definition at line 260 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::yN
protected

Definition at line 260 of file export_nlp_solver.hpp.

ExportVariable ExportNLPSolver::z
protected

Definition at line 244 of file export_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:24