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

An OCP solver based on the block N^2 condensing algorithm. More...

#include <export_gauss_newton_block_cn2.hpp>

Inheritance diagram for ExportGaussNewtonBlockCN2:
Inheritance graph
[legend]

Public Member Functions

 ExportGaussNewtonBlockCN2 (UserInteraction *_userInteraction=0, const std::string &_commonHeaderName="")
 
uint getBlockSize () const
 
virtual returnValue getCode (ExportStatementBlock &code)=0
 
virtual returnValue getDataDeclarations (ExportStatementBlock &declarations, ExportStruct dataStruct=ACADO_ANY) const
 
virtual returnValue getFunctionDeclarations (ExportStatementBlock &declarations) const
 
uint getNumberOfBlocks () const
 
uint getNumBlockVariables () const
 
unsigned getNumQPvars () const
 
virtual unsigned getNumStateBoundsPerBlock () const
 
virtual returnValue setup ()
 
virtual ~ExportGaussNewtonBlockCN2 ()
 
- Public Member Functions inherited from ExportGaussNewtonCN2
 ExportGaussNewtonCN2 (UserInteraction *_userInteraction=0, const std::string &_commonHeaderName="")
 
unsigned getNumQPvars () const
 
virtual unsigned getNumStateBounds () const
 
virtual ~ExportGaussNewtonCN2 ()
 
- Public Member Functions inherited from ExportNLPSolver
 ExportNLPSolver (UserInteraction *_userInteraction=0, const std::string &_commonHeaderName="")
 
unsigned getNumComplexConstraints (void)
 
unsigned getNumPathConstraints (void)
 
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)
 
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

virtual returnValue setupCondensing ()
 
virtual returnValue setupConstraintsEvaluation (void)
 
virtual returnValue setupEvaluation ()=0
 
virtual returnValue setupMultiplicationRoutines ()
 
virtual returnValue setupQPInterface ()=0
 
virtual returnValue setupVariables ()
 
- Protected Member Functions inherited from ExportGaussNewtonCN2
bool performFullCondensing () const
 
virtual returnValue setupObjectiveEvaluation (void)
 
- Protected Member Functions inherited from ExportNLPSolver
returnValue setupArrivalCostCalculation ()
 
returnValue setupAuxiliaryFunctions ()
 
virtual returnValue setupGetGeneralObjective ()
 
virtual returnValue setupGetLSQObjective ()
 
virtual returnValue setupGetObjective ()
 
virtual returnValue setupInitialization ()
 
virtual returnValue setupSimulation (void)
 

Protected Attributes

ExportIndex blockI
 
ExportFunction cleanup
 
ExportFunction evaluateConstraints
 
ExportVariable qpC
 
ExportVariable qpc
 
std::vector< unsigned > qpConDim
 
ExportVariable qpgN
 
ExportVariable qpH
 
ExportVariable qpLambda
 
ExportVariable qpLb0
 
ExportVariable qpMu
 
ExportVariable qpUb0
 
ExportFunction shiftQpData
 
- Protected Attributes inherited from ExportGaussNewtonCN2
ExportVariable A
 
ExportVariable C
 
ExportFunction condenseFdb
 
ExportFunction condensePrep
 
ExportFunction copyHTH
 
ExportFunction copyHTH1
 
ExportVariable Dx0
 
ExportVariable E
 
ExportFunction evaluateObjective
 
ExportFunction expand
 
ExportFunction expansionStep
 
ExportFunction expansionStep2
 
ExportFunction feedback
 
ExportVariable g
 
ExportFunction getKKT
 
ExportVariable H
 
ExportVariable lb
 
ExportVariable lbA
 
ExportVariable lbAValues
 
ExportVariable lbValues
 
ExportFunction mac_S1T_E
 
ExportFunction mac_ST_C
 
ExportFunction macASbar
 
ExportFunction macATw1QDy
 
ExportFunction macBTw1
 
ExportFunction macBTW1_R1
 
ExportFunction macGxTGx
 
ExportFunction macHxd
 
ExportFunction macQEW2
 
ExportFunction macQSbarW2
 
ExportFunction macS1TSbar
 
ExportFunction moveGuE
 
ExportFunction moveGxT
 
ExportFunction mult_BT_T1
 
ExportFunction multBTW1
 
ExportFunction multEDu
 
ExportFunction multEQDy
 
ExportFunction multGxd
 
ExportFunction multGxGu
 
ExportFunction multGxGx
 
ExportFunction multGxTGu
 
ExportFunction multGxTGx
 
ExportFunction multHxC
 
ExportFunction multHxE
 
ExportFunction multQ1d
 
ExportFunction multQ1Gu
 
ExportFunction multQ1Gx
 
ExportFunction multQDy
 
ExportFunction multQETGx
 
ExportFunction multQN1d
 
ExportFunction multQN1Gu
 
ExportFunction multQN1Gx
 
ExportFunction multRDy
 
ExportFunction preparation
 
ExportVariable Qd
 
ExportVariable QDy
 
ExportVariable sbar
 
ExportFunction setObjQ1Q2
 
ExportFunction setObjQN1QN2
 
ExportFunction setObjR1R2
 
ExportFunction setObjS1
 
ExportVariable T1
 
ExportVariable T2
 
ExportVariable ub
 
ExportVariable ubA
 
ExportVariable ubAValues
 
ExportVariable ubValues
 
ExportVariable W1
 
ExportVariable w1
 
ExportVariable W2
 
ExportVariable w2
 
ExportVariable x0
 
std::vector< unsigned > xBoundsIdx
 
ExportVariable xVars
 
ExportVariable yVars
 
ExportVariable A10
 
ExportVariable A20
 
ExportVariable pacA01Dx0
 
ExportVariable pocA02Dx0
 
- Protected Attributes inherited from ExportNLPSolver
IntegratorExportPtr integrator
 
ExportFunction modelSimulation
 
ExportVariable state
 
ExportVariable x
 
ExportVariable z
 
ExportVariable u
 
ExportVariable od
 
ExportVariable d
 
ExportVariable evGx
 
ExportVariable evGu
 
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
 
VariablesGrid uBounds
 
VariablesGrid xBounds
 
unsigned dimPacH
 
ExportAcadoFunction evaluatePathConstraints
 
ExportVariable conAuxVar
 
ExportVariable conValueIn
 
ExportVariable conValueOut
 
DVector lbPathConValues
 
DVector ubPathConValues
 
ExportVariable pacEvH
 
ExportVariable pacEvHx
 
ExportVariable pacEvHu
 
ExportVariable pacEvHxd
 
ExportVariable pacEvDDH
 
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
 
ExportFunction initialize
 
ExportFunction shiftStates
 
ExportFunction shiftControls
 
ExportFunction getObjective
 
ExportFunction initializeNodes
 
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
 

Detailed Description

An OCP solver based on the block N^2 condensing algorithm.

Authors
Rien Quirynen
Note
Still a limited experimental version

Definition at line 50 of file export_gauss_newton_block_cn2.hpp.

Constructor & Destructor Documentation

BEGIN_NAMESPACE_ACADO ExportGaussNewtonBlockCN2::ExportGaussNewtonBlockCN2 ( 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 38 of file export_gauss_newton_block_cn2.cpp.

virtual ExportGaussNewtonBlockCN2::~ExportGaussNewtonBlockCN2 ( )
inlinevirtual

Destructor.

Definition at line 64 of file export_gauss_newton_block_cn2.hpp.

Member Function Documentation

uint ExportGaussNewtonBlockCN2::getBlockSize ( ) const

Definition at line 1089 of file export_gauss_newton_block_cn2.cpp.

virtual returnValue ExportGaussNewtonBlockCN2::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

Reimplemented from ExportGaussNewtonCN2.

Implemented in ExportGaussNewtonBlockForces, and ExportGaussNewtonBlockQpDunes.

returnValue ExportGaussNewtonBlockCN2::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

Reimplemented from ExportGaussNewtonCN2.

Definition at line 103 of file export_gauss_newton_block_cn2.cpp.

returnValue ExportGaussNewtonBlockCN2::getFunctionDeclarations ( ExportStatementBlock declarations) const
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

Reimplemented from ExportGaussNewtonCN2.

Definition at line 125 of file export_gauss_newton_block_cn2.cpp.

uint ExportGaussNewtonBlockCN2::getNumberOfBlocks ( ) const

Definition at line 1097 of file export_gauss_newton_block_cn2.cpp.

uint ExportGaussNewtonBlockCN2::getNumBlockVariables ( ) const

Definition at line 1105 of file export_gauss_newton_block_cn2.cpp.

unsigned ExportGaussNewtonBlockCN2::getNumQPvars ( ) const
virtual

Returns number of variables in underlying QP.

Returns
Number of variables in underlying QP

Implements ExportNLPSolver.

Definition at line 140 of file export_gauss_newton_block_cn2.cpp.

unsigned ExportGaussNewtonBlockCN2::getNumStateBoundsPerBlock ( ) const
virtual

Definition at line 1110 of file export_gauss_newton_block_cn2.cpp.

returnValue ExportGaussNewtonBlockCN2::setup ( )
virtual

Initializes export of an algorithm.

\return SUCCESSFUL_RETURN

Reimplemented from ExportGaussNewtonCN2.

Reimplemented in ExportGaussNewtonBlockForces, and ExportGaussNewtonBlockQpDunes.

Definition at line 43 of file export_gauss_newton_block_cn2.cpp.

returnValue ExportGaussNewtonBlockCN2::setupCondensing ( void  )
protectedvirtual

NEW CODE END

Reimplemented from ExportGaussNewtonCN2.

Reimplemented in ExportGaussNewtonBlockForces.

Definition at line 457 of file export_gauss_newton_block_cn2.cpp.

returnValue ExportGaussNewtonBlockCN2::setupConstraintsEvaluation ( void  )
protectedvirtual

Set-up evaluation of constraints

  • box constraints on states and controls
Returns
SUCCESSFUL_RETURN

Reimplemented from ExportGaussNewtonCN2.

Reimplemented in ExportGaussNewtonBlockForces.

Definition at line 151 of file export_gauss_newton_block_cn2.cpp.

virtual returnValue ExportGaussNewtonBlockCN2::setupEvaluation ( )
protectedpure virtual

Exports source code containing the evaluation routines of the algorithm.

\return SUCCESSFUL_RETURN

Reimplemented from ExportGaussNewtonCN2.

Implemented in ExportGaussNewtonBlockForces, and ExportGaussNewtonBlockQpDunes.

returnValue ExportGaussNewtonBlockCN2::setupMultiplicationRoutines ( )
protectedvirtual

Exports source code containing the multiplication routines of the algorithm.

\return SUCCESSFUL_RETURN

Reimplemented from ExportGaussNewtonCN2.

Definition at line 1084 of file export_gauss_newton_block_cn2.cpp.

virtual returnValue ExportGaussNewtonBlockCN2::setupQPInterface ( )
protectedpure virtual
returnValue ExportGaussNewtonBlockCN2::setupVariables ( )
protectedvirtual

Initialization of all member variables.

\return SUCCESSFUL_RETURN

Reimplemented from ExportGaussNewtonCN2.

Reimplemented in ExportGaussNewtonBlockForces.

Definition at line 1047 of file export_gauss_newton_block_cn2.cpp.

Member Data Documentation

ExportIndex ExportGaussNewtonBlockCN2::blockI
protected

Definition at line 154 of file export_gauss_newton_block_cn2.hpp.

ExportFunction ExportGaussNewtonBlockCN2::cleanup
protected

Definition at line 167 of file export_gauss_newton_block_cn2.hpp.

ExportFunction ExportGaussNewtonBlockCN2::evaluateConstraints
protected

Definition at line 170 of file export_gauss_newton_block_cn2.hpp.

ExportVariable ExportGaussNewtonBlockCN2::qpC
protected

Definition at line 161 of file export_gauss_newton_block_cn2.hpp.

ExportVariable ExportGaussNewtonBlockCN2::qpc
protected

Definition at line 162 of file export_gauss_newton_block_cn2.hpp.

std::vector< unsigned > ExportGaussNewtonBlockCN2::qpConDim
protected

Definition at line 156 of file export_gauss_newton_block_cn2.hpp.

ExportVariable ExportGaussNewtonBlockCN2::qpgN
protected

Definition at line 158 of file export_gauss_newton_block_cn2.hpp.

ExportVariable ExportGaussNewtonBlockCN2::qpH
protected

Definition at line 160 of file export_gauss_newton_block_cn2.hpp.

ExportVariable ExportGaussNewtonBlockCN2::qpLambda
protected

Definition at line 165 of file export_gauss_newton_block_cn2.hpp.

ExportVariable ExportGaussNewtonBlockCN2::qpLb0
protected

Definition at line 163 of file export_gauss_newton_block_cn2.hpp.

ExportVariable ExportGaussNewtonBlockCN2::qpMu
protected

Definition at line 165 of file export_gauss_newton_block_cn2.hpp.

ExportVariable ExportGaussNewtonBlockCN2::qpUb0
protected

Definition at line 163 of file export_gauss_newton_block_cn2.hpp.

ExportFunction ExportGaussNewtonBlockCN2::shiftQpData
protected

Definition at line 168 of file export_gauss_newton_block_cn2.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:23