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

TBD. More...

#include <export_gauss_newton_cn2_factorization.hpp>

Inheritance diagram for ExportGaussNewtonCn2Factorization:
Inheritance graph
[legend]

Public Member Functions

 ExportGaussNewtonCn2Factorization (UserInteraction *_userInteraction=0, const std::string &_commonHeaderName="")
 
virtual returnValue getCode (ExportStatementBlock &code)
 
virtual returnValue getDataDeclarations (ExportStatementBlock &declarations, ExportStruct dataStruct=ACADO_ANY) const
 
virtual returnValue getFunctionDeclarations (ExportStatementBlock &declarations) const
 
unsigned getNumQPvars () const
 
virtual unsigned getNumStateBounds () const
 
virtual returnValue setup ()
 
virtual ~ExportGaussNewtonCn2Factorization ()
 
- 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

bool performFullCondensing () const
 
virtual returnValue setupCondensing ()
 
virtual returnValue setupConstraintsEvaluation (void)
 
virtual returnValue setupEvaluation ()
 
virtual returnValue setupMultiplicationRoutines ()
 
virtual returnValue setupObjectiveEvaluation (void)
 
virtual returnValue setupQPInterface ()
 
virtual returnValue setupVariables ()
 
- 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

ExportVariable A
 
ExportVariable A10
 
ExportVariable A20
 
ExportCholeskySolver cholSolver
 
ExportFunction condenseFdb
 
ExportFunction condensePrep
 
ExportFunction copyHTH
 
ExportVariable D
 
ExportVariable Dx0
 
ExportVariable E
 
ExportFunction evaluateObjective
 
ExportFunction expand
 
ExportFunction expansionStep
 
ExportVariable F
 
ExportFunction feedback
 
ExportVariable g
 
ExportVariable g0
 
ExportVariable g1
 
ExportFunction getKKT
 
ExportVariable H
 
ExportVariable H00
 
ExportVariable H10
 
ExportVariable H11
 
ExportVariable L
 
ExportVariable lb
 
ExportVariable lbA
 
ExportVariable lbAValues
 
ExportVariable lbValues
 
ExportFunction mac_H_W2T_W3_R
 
ExportFunction mac_R_BT_F_D
 
ExportFunction mac_R_T2_B_D
 
ExportFunction mac_W1_T1_E_F
 
ExportFunction mac_W3_G_W1T_G
 
ExportFunction macASbar
 
ExportFunction macASbarD2
 
ExportFunction macATw1QDy
 
ExportFunction macBTw1
 
ExportFunction macBTW1_R1
 
ExportFunction macCTSlx
 
ExportFunction macETSlu
 
ExportFunction macHxd
 
ExportFunction macQEW2
 
ExportFunction macQSbarW2
 
ExportFunction move_D_U
 
ExportFunction move_GxT_T3
 
ExportFunction moveGuE
 
ExportFunction moveGxT
 
ExportFunction mul_T2_A_L
 
ExportFunction mult_BT_T1_T2
 
ExportFunction mult_FT_A_L
 
ExportFunction mult_H_W2T_W3
 
ExportFunction mult_L_E_U
 
ExportFunction multBTW1
 
ExportFunction multCTQC
 
ExportFunction multEDu
 
ExportFunction multEQDy
 
ExportFunction multGxd
 
ExportFunction multGxGu
 
ExportFunction multGxGx
 
ExportFunction multGxTGu
 
ExportFunction multHxC
 
ExportFunction multHxE
 
ExportFunction multQ1d
 
ExportFunction multQ1Gu
 
ExportFunction multQ1Gx
 
ExportFunction multQDy
 
ExportFunction multQETGx
 
ExportFunction multQN1d
 
ExportFunction multQN1Gu
 
ExportFunction multQN1Gx
 
ExportFunction multRDy
 
ExportVariable pacA01Dx0
 
ExportVariable pocA02Dx0
 
ExportFunction preparation
 
ExportVariable Qd
 
ExportVariable QDy
 
ExportVariable QE
 
ExportVariable QGx
 
ExportVariable sbar
 
ExportFunction setBlockH11
 
ExportFunction setObjQ1Q2
 
ExportFunction setObjQN1QN2
 
ExportFunction setObjR1R2
 
ExportVariable T1
 
ExportVariable T2
 
ExportVariable T3
 
ExportVariable U
 
ExportVariable ub
 
ExportVariable ubA
 
ExportVariable ubAValues
 
ExportVariable ubValues
 
ExportFunction updateQ
 
ExportFunction updateQ2
 
ExportVariable W1
 
ExportVariable w1
 
ExportVariable W2
 
ExportVariable w2
 
ExportVariable x0
 
std::vector< unsigned > xBoundsIdx
 
std::vector< unsigned > xBoundsIdxRev
 
ExportVariable xVars
 
ExportVariable yVars
 
ExportFunction zeroBlockH00
 
ExportFunction zeroBlockH10
 
ExportFunction zeroBlockH11
 
- 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

TBD.

Authors
Milan Vukov
Note
Early experimental implementation

Definition at line 49 of file export_gauss_newton_cn2_factorization.hpp.

Constructor & Destructor Documentation

BEGIN_NAMESPACE_ACADO ExportGaussNewtonCn2Factorization::ExportGaussNewtonCn2Factorization ( 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 40 of file export_gauss_newton_cn2_factorization.cpp.

virtual ExportGaussNewtonCn2Factorization::~ExportGaussNewtonCn2Factorization ( )
inlinevirtual

Destructor.

Definition at line 63 of file export_gauss_newton_cn2_factorization.hpp.

Member Function Documentation

returnValue ExportGaussNewtonCn2Factorization::getCode ( ExportStatementBlock code)
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 ExportNLPSolver.

Definition at line 163 of file export_gauss_newton_cn2_factorization.cpp.

returnValue ExportGaussNewtonCn2Factorization::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 ExportNLPSolver.

Definition at line 91 of file export_gauss_newton_cn2_factorization.cpp.

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

Implements ExportNLPSolver.

Definition at line 144 of file export_gauss_newton_cn2_factorization.cpp.

unsigned ExportGaussNewtonCn2Factorization::getNumQPvars ( ) const
virtual

Returns number of variables in underlying QP.

Returns
Number of variables in underlying QP

Implements ExportNLPSolver.

Definition at line 288 of file export_gauss_newton_cn2_factorization.cpp.

unsigned ExportGaussNewtonCn2Factorization::getNumStateBounds ( ) const
virtual

Returns number of bounds on differential states.

Returns
Number of bounds on differential states

Definition at line 296 of file export_gauss_newton_cn2_factorization.cpp.

bool ExportGaussNewtonCn2Factorization::performFullCondensing ( ) const
protected

Definition at line 1956 of file export_gauss_newton_cn2_factorization.cpp.

returnValue ExportGaussNewtonCn2Factorization::setup ( )
virtual

Initializes export of an algorithm.

\return SUCCESSFUL_RETURN

Implements ExportNLPSolver.

Definition at line 45 of file export_gauss_newton_cn2_factorization.cpp.

returnValue ExportGaussNewtonCn2Factorization::setupCondensing ( void  )
protectedvirtual

Setup E matrix as in the N^3 implementation

Definition at line 742 of file export_gauss_newton_cn2_factorization.cpp.

returnValue ExportGaussNewtonCn2Factorization::setupConstraintsEvaluation ( void  )
protectedvirtual

Set-up evaluation of constraints

  • box constraints on states and controls
Returns
SUCCESSFUL_RETURN

Implements ExportNLPSolver.

Definition at line 512 of file export_gauss_newton_cn2_factorization.cpp.

returnValue ExportGaussNewtonCn2Factorization::setupEvaluation ( )
protectedvirtual

Exports source code containing the evaluation routines of the algorithm.

\return SUCCESSFUL_RETURN

Implements ExportNLPSolver.

Definition at line 1773 of file export_gauss_newton_cn2_factorization.cpp.

returnValue ExportGaussNewtonCn2Factorization::setupMultiplicationRoutines ( )
protectedvirtual

Exports source code containing the multiplication routines of the algorithm.

\return SUCCESSFUL_RETURN

Implements ExportNLPSolver.

Definition at line 1497 of file export_gauss_newton_cn2_factorization.cpp.

returnValue ExportGaussNewtonCn2Factorization::setupObjectiveEvaluation ( void  )
protectedvirtual

Setting up of an objective evaluation:

  • functions and derivatives evaulation
  • creating Hessians and gradients
Returns
SUCCESSFUL_RETURN

Definition at line 305 of file export_gauss_newton_cn2_factorization.cpp.

returnValue ExportGaussNewtonCn2Factorization::setupQPInterface ( )
protectedvirtual

Definition at line 1864 of file export_gauss_newton_cn2_factorization.cpp.

returnValue ExportGaussNewtonCn2Factorization::setupVariables ( )
protectedvirtual

Initialization of all member variables.

\return SUCCESSFUL_RETURN

Implements ExportNLPSolver.

Definition at line 1405 of file export_gauss_newton_cn2_factorization.cpp.

Member Data Documentation

ExportVariable ExportGaussNewtonCn2Factorization::A
protected

Variable containing the QP constraint matrix.

Definition at line 173 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::A10
protected

Definition at line 231 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::A20
protected

Definition at line 232 of file export_gauss_newton_cn2_factorization.hpp.

ExportCholeskySolver ExportGaussNewtonCn2Factorization::cholSolver
protected

Definition at line 257 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::condenseFdb
protected

Definition at line 203 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::condensePrep
protected

Definition at line 202 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::copyHTH
protected

Definition at line 215 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::D
protected

Definition at line 266 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::Dx0
protected

Definition at line 162 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::E
protected

Definition at line 206 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::evaluateObjective
protected

Definition at line 160 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::expand
protected

Definition at line 204 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::expansionStep
protected

Definition at line 255 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::F
protected

Definition at line 268 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::feedback
protected

Definition at line 243 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::g
protected

Variable containing the QP gradient.

Definition at line 176 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::g0
protected

Definition at line 176 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::g1
protected

Definition at line 176 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::getKKT
protected

Definition at line 245 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::H
protected

Variable containing the QP Hessian matrix.

Definition at line 169 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::H00
protected

Definition at line 169 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::H10
protected

Definition at line 169 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::H11
protected

Definition at line 169 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::L
protected

Definition at line 266 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::lb
protected

Variable containing the lower limits on QP variables.

Definition at line 179 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::lbA
protected

Variable containing lower limits on QP constraints.

Definition at line 185 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::lbAValues
protected

Definition at line 198 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::lbValues
protected

Definition at line 197 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::mac_H_W2T_W3_R
protected

Definition at line 251 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::mac_R_BT_F_D
protected

Definition at line 270 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::mac_R_T2_B_D
protected

Definition at line 259 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::mac_W1_T1_E_F
protected

Definition at line 272 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::mac_W3_G_W1T_G
protected

Definition at line 251 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::macASbar
protected

Definition at line 254 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::macASbarD2
protected

Definition at line 254 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::macATw1QDy
protected

Definition at line 254 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::macBTw1
protected

Definition at line 254 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::macBTW1_R1
protected

Definition at line 253 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::macCTSlx
protected

Definition at line 239 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::macETSlu
protected

Definition at line 240 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::macHxd
protected

Definition at line 237 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::macQEW2
protected

Definition at line 253 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::macQSbarW2
protected

Definition at line 254 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::move_D_U
protected

Definition at line 260 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::move_GxT_T3
protected

Definition at line 273 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::moveGuE
protected

Definition at line 212 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::moveGxT
protected

Definition at line 209 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::mul_T2_A_L
protected

Definition at line 263 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::mult_BT_T1_T2
protected

Definition at line 264 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::mult_FT_A_L
protected

Definition at line 270 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::mult_H_W2T_W3
protected

Definition at line 251 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::mult_L_E_U
protected

Definition at line 261 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::multBTW1
protected

Definition at line 253 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::multCTQC
protected

Definition at line 229 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::multEDu
protected

Definition at line 223 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::multEQDy
protected

Definition at line 220 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::multGxd
protected

Definition at line 208 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::multGxGu
protected

Definition at line 211 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::multGxGx
protected

Definition at line 210 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::multGxTGu
protected

Definition at line 253 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::multHxC
protected

Definition at line 235 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::multHxE
protected

Definition at line 236 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::multQ1d
protected

Definition at line 216 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::multQ1Gu
protected

Definition at line 226 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::multQ1Gx
protected

Definition at line 224 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::multQDy
protected

Definition at line 219 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::multQETGx
protected

Definition at line 221 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::multQN1d
protected

Definition at line 217 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::multQN1Gu
protected

Definition at line 227 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::multQN1Gx
protected

Definition at line 225 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::multRDy
protected

Definition at line 218 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::pacA01Dx0
protected

Definition at line 233 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::pocA02Dx0
protected

Definition at line 234 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::preparation
protected

Definition at line 242 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::Qd
protected

Definition at line 200 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::QDy
protected

Definition at line 206 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::QE
protected

Definition at line 206 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::QGx
protected

Definition at line 206 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::sbar
protected

Definition at line 249 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::setBlockH11
protected

Definition at line 213 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::setObjQ1Q2
protected

Definition at line 164 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::setObjQN1QN2
protected

Definition at line 166 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::setObjR1R2
protected

Definition at line 165 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::T1
protected

Definition at line 268 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::T2
protected

Definition at line 268 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::T3
protected

Definition at line 268 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::U
protected

Variable containing factorization of the QP Hessian matrix; R' * R = H.

Definition at line 171 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::ub
protected

Variable containing the upper limits on QP variables.

Definition at line 182 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::ubA
protected

Variable containing upper limits on QP constraints.

Definition at line 188 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::ubAValues
protected

Definition at line 198 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::ubValues
protected

Definition at line 197 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::updateQ
protected

Definition at line 262 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::updateQ2
protected

Definition at line 271 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::W1
protected

Definition at line 248 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::w1
protected

Definition at line 249 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::W2
protected

Definition at line 248 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::w2
protected

Definition at line 249 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::x0
protected

Definition at line 162 of file export_gauss_newton_cn2_factorization.hpp.

std::vector< unsigned > ExportGaussNewtonCn2Factorization::xBoundsIdx
protected

Definition at line 196 of file export_gauss_newton_cn2_factorization.hpp.

std::vector< unsigned > ExportGaussNewtonCn2Factorization::xBoundsIdxRev
protected

Definition at line 196 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::xVars
protected

Variable containing the primal QP variables.

Definition at line 191 of file export_gauss_newton_cn2_factorization.hpp.

ExportVariable ExportGaussNewtonCn2Factorization::yVars
protected

Variable containing the dual QP variables.

Definition at line 194 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::zeroBlockH00
protected

Definition at line 228 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::zeroBlockH10
protected

Definition at line 222 of file export_gauss_newton_cn2_factorization.hpp.

ExportFunction ExportGaussNewtonCn2Factorization::zeroBlockH11
protected

Definition at line 214 of file export_gauss_newton_cn2_factorization.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