Public Member Functions | Protected Member Functions | Private Member Functions

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

#include <export_nlp_solver.hpp>

Inheritance diagram for ExportNLPSolver:
Inheritance graph
[legend]

List of all members.

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)
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 ()

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 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
Evaluation of point constraints
unsigned dimPocH
std::vector
< std::tr1::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

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.

Parameters:
[in]_userInteractionPointer to corresponding user interface.
[in]_commonHeaderNameName of common header file to be included.

Definition at line 41 of file export_nlp_solver.cpp.

virtual ExportNLPSolver::~ExportNLPSolver ( ) [inline, virtual]

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.

Parameters:
[in]codeCode block containing the auto-generated condensing algorithm.
Returns:
SUCCESSFUL_RETURN

Implements ExportAlgorithm.

Implemented in ExportGaussNewtonForces, ExportGaussNewtonQpDunes, ExportGaussNewtonCondensed, ExportGaussNewtonQpDunes2, ExportGaussNewtonHpmpc, ExportGaussNewtonCn2Factorization, ExportGaussNewtonCN2, and ExportExactHessianQpDunes.

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, ExportGaussNewtonQpDunes2, ExportGaussNewtonHpmpc, ExportGaussNewtonCn2Factorization, 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, ExportGaussNewtonQpDunes2, ExportGaussNewtonHpmpc, ExportGaussNewtonCn2Factorization, ExportGaussNewtonCN2, ExportExactHessianQpDunes, and ExportExactHessianCN2.

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

Returns:
Number of complex constraints

Definition at line 1420 of file export_nlp_solver.cpp.

virtual unsigned ExportNLPSolver::getNumQPvars ( ) const [pure virtual]

Returns number of variables in underlying QP.

Returns:
Number of variables in underlying QP

Implemented in ExportGaussNewtonForces, ExportGaussNewtonCondensed, ExportGaussNewtonQpDunes, ExportGaussNewtonHpmpc, ExportGaussNewtonQpDunes2, ExportGaussNewtonCn2Factorization, and ExportGaussNewtonCN2.

Indicates whether initial state is fixed.

Definition at line 1425 of file export_nlp_solver.cpp.

Returns whether a single shooting state discretization is used.

Returns:
true iff single shooting state discretization is used,
false otherwise

Definition at line 78 of file export_nlp_solver.cpp.

Set the "complex" path and point constraints

Returns:
SUCCESSFUL_RETURN

Definition at line 1126 of file export_nlp_solver.cpp.

Definition at line 382 of file export_nlp_solver.cpp.

Assigns module for exporting a tailored integrator.

Parameters:
[in]_integratorIntegrator module.
Returns:
SUCCESSFUL_RETURN

Definition at line 55 of file export_nlp_solver.cpp.

returnValue ExportNLPSolver::setLevenbergMarquardt ( double  _levenbergMarquardt)

Assigns new constant for Levenberg-Marquardt regularization.

Parameters:
[in]_levenbergMarquardtNon-negative constant for Levenberg-Marquardt regularization.
Returns:
SUCCESSFUL_RETURN

Definition at line 62 of file export_nlp_solver.cpp.

Definition at line 635 of file export_nlp_solver.cpp.

Set objective function

Returns:
SUCCESSFUL_RETURN,
RET_INITIALIZE_FIRST,
RET_INVALID_OBJECTIVE_FOR_CODE_EXPORT,
RET_INVALID_ARGUMENTS

Definition at line 371 of file export_nlp_solver.cpp.

virtual returnValue ExportNLPSolver::setup ( ) [pure virtual]

Setup of functions and variables for evaluation of arrival cost.

Definition at line 1758 of file export_nlp_solver.cpp.

Setup of functions for evaluation of auxiliary functions.

Definition at line 1441 of file export_nlp_solver.cpp.

virtual returnValue ExportNLPSolver::setupConstraintsEvaluation ( ) [protected, pure virtual]
virtual returnValue ExportNLPSolver::setupEvaluation ( ) [protected, pure virtual]

Setup the function for evaluating the actual objective value.

Definition at line 1696 of file export_nlp_solver.cpp.

Setup the function for evaluating the actual LSQ objective value.

Definition at line 1608 of file export_nlp_solver.cpp.

Setup the function for evaluating the actual objective value.

Definition at line 1597 of file export_nlp_solver.cpp.

Setup main initialization code for the solver

Definition at line 163 of file export_nlp_solver.cpp.

virtual returnValue ExportNLPSolver::setupMultiplicationRoutines ( ) [protected, pure virtual]

Exports source code containing the multiplication routines of the algorithm.

Returns:
SUCCESSFUL_RETURN

Implemented in ExportGaussNewtonCondensed, ExportGaussNewtonCn2Factorization, ExportGaussNewtonCN2, ExportGaussNewtonForces, ExportGaussNewtonQpDunes, ExportGaussNewtonHpmpc, and ExportGaussNewtonQpDunes2.

Definition at line 1061 of file export_nlp_solver.cpp.

Definition at line 1113 of file export_nlp_solver.cpp.

returnValue ExportNLPSolver::setupSimulation ( void  ) [protected, virtual]

Setting up of a model simulation:

  • model integration
  • sensitivity generation
Returns:
SUCCESSFUL_RETURN

Definition at line 188 of file export_nlp_solver.cpp.

virtual returnValue ExportNLPSolver::setupVariables ( ) [protected, pure virtual]

Indicates whether linear terms in the objective are used.

Definition at line 1433 of file export_nlp_solver.cpp.

unsigned ExportNLPSolver::weightingMatricesType ( void  ) const

Return type of weighting matrices.

Returns:
Type of weighting matrices.

Definition at line 1744 of file export_nlp_solver.cpp.


Member Data Documentation

Definition at line 332 of file export_nlp_solver.hpp.

Definition at line 332 of file export_nlp_solver.hpp.

Definition at line 334 of file export_nlp_solver.hpp.

Definition at line 334 of file export_nlp_solver.hpp.

Definition at line 334 of file export_nlp_solver.hpp.

Definition at line 332 of file export_nlp_solver.hpp.

Definition at line 330 of file export_nlp_solver.hpp.

Definition at line 332 of file export_nlp_solver.hpp.

Definition at line 334 of file export_nlp_solver.hpp.

Definition at line 334 of file export_nlp_solver.hpp.

Definition at line 334 of file export_nlp_solver.hpp.

Definition at line 334 of file export_nlp_solver.hpp.

Definition at line 334 of file export_nlp_solver.hpp.

Definition at line 327 of file export_nlp_solver.hpp.

Definition at line 328 of file export_nlp_solver.hpp.

Definition at line 289 of file export_nlp_solver.hpp.

Definition at line 290 of file export_nlp_solver.hpp.

Definition at line 291 of file export_nlp_solver.hpp.

Definition at line 242 of file export_nlp_solver.hpp.

bool ExportNLPSolver::diagonalH [protected]

Definition at line 275 of file export_nlp_solver.hpp.

bool ExportNLPSolver::diagonalHN [protected]

Definition at line 275 of file export_nlp_solver.hpp.

unsigned ExportNLPSolver::dimPacH [protected]

Definition at line 287 of file export_nlp_solver.hpp.

unsigned ExportNLPSolver::dimPocH [protected]

Definition at line 301 of file export_nlp_solver.hpp.

Definition at line 337 of file export_nlp_solver.hpp.

Definition at line 255 of file export_nlp_solver.hpp.

Definition at line 255 of file export_nlp_solver.hpp.

Definition at line 288 of file export_nlp_solver.hpp.

std::vector< std::tr1::shared_ptr< ExportAcadoFunction > > ExportNLPSolver::evaluatePointConstraints [protected]

Definition at line 302 of file export_nlp_solver.hpp.

Definition at line 265 of file export_nlp_solver.hpp.

Definition at line 266 of file export_nlp_solver.hpp.

Definition at line 245 of file export_nlp_solver.hpp.

Definition at line 244 of file export_nlp_solver.hpp.

Definition at line 319 of file export_nlp_solver.hpp.

Main initialization function for the solver.

Definition at line 315 of file export_nlp_solver.hpp.

Definition at line 320 of file export_nlp_solver.hpp.

Module for exporting a tailored integrator.

Definition at line 233 of file export_nlp_solver.hpp.

Definition at line 293 of file export_nlp_solver.hpp.

Definition at line 303 of file export_nlp_solver.hpp.

Non-negative constant for Levenberg-Marquardt regularization.

Definition at line 253 of file export_nlp_solver.hpp.

Definition at line 235 of file export_nlp_solver.hpp.

Definition at line 258 of file export_nlp_solver.hpp.

Definition at line 264 of file export_nlp_solver.hpp.

Definition at line 261 of file export_nlp_solver.hpp.

Definition at line 262 of file export_nlp_solver.hpp.

Definition at line 261 of file export_nlp_solver.hpp.

Definition at line 261 of file export_nlp_solver.hpp.

Definition at line 262 of file export_nlp_solver.hpp.

Definition at line 262 of file export_nlp_solver.hpp.

Definition at line 262 of file export_nlp_solver.hpp.

Definition at line 260 of file export_nlp_solver.hpp.

Definition at line 260 of file export_nlp_solver.hpp.

Definition at line 273 of file export_nlp_solver.hpp.

Definition at line 273 of file export_nlp_solver.hpp.

Definition at line 264 of file export_nlp_solver.hpp.

Definition at line 264 of file export_nlp_solver.hpp.

Definition at line 241 of file export_nlp_solver.hpp.

Definition at line 295 of file export_nlp_solver.hpp.

Definition at line 296 of file export_nlp_solver.hpp.

Definition at line 296 of file export_nlp_solver.hpp.

Definition at line 296 of file export_nlp_solver.hpp.

Definition at line 307 of file export_nlp_solver.hpp.

Definition at line 308 of file export_nlp_solver.hpp.

Definition at line 308 of file export_nlp_solver.hpp.

Definition at line 308 of file export_nlp_solver.hpp.

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

Definition at line 305 of file export_nlp_solver.hpp.

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

Definition at line 305 of file export_nlp_solver.hpp.

Definition at line 268 of file export_nlp_solver.hpp.

Definition at line 268 of file export_nlp_solver.hpp.

Definition at line 271 of file export_nlp_solver.hpp.

Definition at line 271 of file export_nlp_solver.hpp.

Definition at line 269 of file export_nlp_solver.hpp.

Definition at line 269 of file export_nlp_solver.hpp.

Definition at line 340 of file export_nlp_solver.hpp.

Definition at line 339 of file export_nlp_solver.hpp.

Definition at line 270 of file export_nlp_solver.hpp.

Definition at line 337 of file export_nlp_solver.hpp.

Definition at line 318 of file export_nlp_solver.hpp.

Definition at line 317 of file export_nlp_solver.hpp.

Definition at line 237 of file export_nlp_solver.hpp.

Definition at line 240 of file export_nlp_solver.hpp.

Definition at line 281 of file export_nlp_solver.hpp.

Definition at line 293 of file export_nlp_solver.hpp.

Definition at line 303 of file export_nlp_solver.hpp.

Definition at line 325 of file export_nlp_solver.hpp.

Definition at line 238 of file export_nlp_solver.hpp.

Definition at line 337 of file export_nlp_solver.hpp.

Definition at line 282 of file export_nlp_solver.hpp.

Definition at line 255 of file export_nlp_solver.hpp.

Definition at line 255 of file export_nlp_solver.hpp.

Definition at line 239 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 Thu Aug 27 2015 12:01:38