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

A class for export of an OCP solver using sparse QP solver FORCES. More...

#include <export_gauss_newton_forces.hpp>

Inheritance diagram for ExportGaussNewtonForces:
Inheritance graph
[legend]

Public Member Functions

 ExportGaussNewtonForces (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 getNumLowerBounds () const
 
unsigned getNumQPvars () const
 
unsigned getNumUpperBounds () const
 
virtual returnValue setup ()
 
virtual ~ExportGaussNewtonForces ()
 
- 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 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)
 

Private Attributes

ExportVariable x0
 
Objective evaluation
ExportFunction evaluateObjective
 
std::vector< ExportVariableobjHessians
 
std::vector< ExportVariableobjGradients
 
ExportFunction setStageH
 
ExportFunction setStagef
 
ExportFunction setObjQ1Q2
 
ExportFunction setObjR1R2
 
ExportFunction setObjQN1QN2
 
ExportFunction setObjS1
 
bool diagH
 
bool diagHN
 
Constraint evaluation
std::vector< ExportVariableconLB
 
std::vector< ExportVariableconUB
 
ExportVariable lbValues
 
ExportVariable ubValues
 
unsigned numLB
 
unsigned numUB
 
std::vector< std::vector< unsigned > > conLBIndices
 
std::vector< std::vector< unsigned > > conUBIndices
 
std::vector< unsigned > conABDimensions
 
std::vector< std::vector< double > > conLBValues
 
std::vector< std::vector< double > > conUBValues
 
ExportFunction evaluateConstraints
 
ExportFunction conSetGxGu
 
ExportVariable conStageC
 
std::vector< ExportVariableconC
 
std::vector< ExportVariablecond
 
ExportFunction conSetd
 
RTI related
ExportFunction preparation
 
ExportFunction feedback
 
ExportFunction getKKT
 
Helper functions
ExportFunction acc
 
QP interface
std::string qpModuleName
 
std::string qpObjPrefix
 
std::shared_ptr< ExportForcesInterfaceqpInterface
 
std::shared_ptr< ExportForcesGeneratorqpGenerator
 

Additional Inherited Members

- 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

A class for export of an OCP solver using sparse QP solver FORCES.

The class ExportGaussNewtonForces allows export of and OCP solver using the generalized Gauss-Newton method. The underlying QP is solved using the structured sparse QP solver FORCES.

Author
Milan Vukov

Definition at line 53 of file export_gauss_newton_forces.hpp.

Constructor & Destructor Documentation

ExportGaussNewtonForces::ExportGaussNewtonForces ( 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 44 of file export_gauss_newton_forces.cpp.

virtual ExportGaussNewtonForces::~ExportGaussNewtonForces ( )
inlinevirtual

Destructor.

Definition at line 68 of file export_gauss_newton_forces.hpp.

Member Function Documentation

returnValue ExportGaussNewtonForces::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 118 of file export_gauss_newton_forces.cpp.

returnValue ExportGaussNewtonForces::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 82 of file export_gauss_newton_forces.cpp.

returnValue ExportGaussNewtonForces::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 99 of file export_gauss_newton_forces.cpp.

unsigned ExportGaussNewtonForces::getNumLowerBounds ( ) const

Definition at line 176 of file export_gauss_newton_forces.cpp.

unsigned ExportGaussNewtonForces::getNumQPvars ( ) const
virtual

Returns number of variables in underlying QP.

Returns
Number of variables in underlying QP

Implements ExportNLPSolver.

Definition at line 171 of file export_gauss_newton_forces.cpp.

unsigned ExportGaussNewtonForces::getNumUpperBounds ( ) const

Definition at line 181 of file export_gauss_newton_forces.cpp.

returnValue ExportGaussNewtonForces::setup ( )
virtual

Initializes export of an algorithm.

\return SUCCESSFUL_RETURN

Implements ExportNLPSolver.

Definition at line 56 of file export_gauss_newton_forces.cpp.

returnValue ExportGaussNewtonForces::setupConstraintsEvaluation ( void  )
protectedvirtual

Set-up evaluation of constraints

  • box constraints on states and controls
Returns
SUCCESSFUL_RETURN

Implements ExportNLPSolver.

Definition at line 647 of file export_gauss_newton_forces.cpp.

returnValue ExportGaussNewtonForces::setupEvaluation ( )
protectedvirtual

Exports source code containing the evaluation routines of the algorithm.

\return SUCCESSFUL_RETURN

Implements ExportNLPSolver.

Definition at line 914 of file export_gauss_newton_forces.cpp.

returnValue ExportGaussNewtonForces::setupMultiplicationRoutines ( )
protectedvirtual

Exports source code containing the multiplication routines of the algorithm.

\return SUCCESSFUL_RETURN

Implements ExportNLPSolver.

Definition at line 909 of file export_gauss_newton_forces.cpp.

returnValue ExportGaussNewtonForces::setupObjectiveEvaluation ( void  )
protectedvirtual

Setting up of an objective evaluation:

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

Definition at line 190 of file export_gauss_newton_forces.cpp.

returnValue ExportGaussNewtonForces::setupQPInterface ( )
protectedvirtual

Definition at line 1067 of file export_gauss_newton_forces.cpp.

returnValue ExportGaussNewtonForces::setupVariables ( )
protectedvirtual

Initialization of all member variables.

\return SUCCESSFUL_RETURN

Implements ExportNLPSolver.

Definition at line 898 of file export_gauss_newton_forces.cpp.

Member Data Documentation

ExportFunction ExportGaussNewtonForces::acc
private

Definition at line 212 of file export_gauss_newton_forces.hpp.

std::vector< unsigned > ExportGaussNewtonForces::conABDimensions
private

Definition at line 190 of file export_gauss_newton_forces.hpp.

std::vector< ExportVariable > ExportGaussNewtonForces::conC
private

Definition at line 197 of file export_gauss_newton_forces.hpp.

std::vector< ExportVariable > ExportGaussNewtonForces::cond
private

Definition at line 198 of file export_gauss_newton_forces.hpp.

std::vector< ExportVariable > ExportGaussNewtonForces::conLB
private

Definition at line 182 of file export_gauss_newton_forces.hpp.

std::vector< std::vector< unsigned > > ExportGaussNewtonForces::conLBIndices
private

Definition at line 189 of file export_gauss_newton_forces.hpp.

std::vector< std::vector< double > > ExportGaussNewtonForces::conLBValues
private

Definition at line 191 of file export_gauss_newton_forces.hpp.

ExportFunction ExportGaussNewtonForces::conSetd
private

Definition at line 199 of file export_gauss_newton_forces.hpp.

ExportFunction ExportGaussNewtonForces::conSetGxGu
private

Definition at line 194 of file export_gauss_newton_forces.hpp.

ExportVariable ExportGaussNewtonForces::conStageC
private

Definition at line 195 of file export_gauss_newton_forces.hpp.

std::vector< ExportVariable > ExportGaussNewtonForces::conUB
private

Definition at line 183 of file export_gauss_newton_forces.hpp.

std::vector< std::vector< unsigned > > ExportGaussNewtonForces::conUBIndices
private

Definition at line 189 of file export_gauss_newton_forces.hpp.

std::vector< std::vector< double > > ExportGaussNewtonForces::conUBValues
private

Definition at line 191 of file export_gauss_newton_forces.hpp.

bool ExportGaussNewtonForces::diagH
private

Definition at line 176 of file export_gauss_newton_forces.hpp.

bool ExportGaussNewtonForces::diagHN
private

Definition at line 177 of file export_gauss_newton_forces.hpp.

ExportFunction ExportGaussNewtonForces::evaluateConstraints
private

Definition at line 193 of file export_gauss_newton_forces.hpp.

ExportFunction ExportGaussNewtonForces::evaluateObjective
private

Definition at line 163 of file export_gauss_newton_forces.hpp.

ExportFunction ExportGaussNewtonForces::feedback
private

Definition at line 205 of file export_gauss_newton_forces.hpp.

ExportFunction ExportGaussNewtonForces::getKKT
private

Definition at line 207 of file export_gauss_newton_forces.hpp.

ExportVariable ExportGaussNewtonForces::lbValues
private

Definition at line 184 of file export_gauss_newton_forces.hpp.

unsigned ExportGaussNewtonForces::numLB
private

Definition at line 186 of file export_gauss_newton_forces.hpp.

unsigned ExportGaussNewtonForces::numUB
private

Definition at line 187 of file export_gauss_newton_forces.hpp.

std::vector< ExportVariable > ExportGaussNewtonForces::objGradients
private

Definition at line 166 of file export_gauss_newton_forces.hpp.

std::vector< ExportVariable > ExportGaussNewtonForces::objHessians
private

Definition at line 165 of file export_gauss_newton_forces.hpp.

ExportFunction ExportGaussNewtonForces::preparation
private

Definition at line 204 of file export_gauss_newton_forces.hpp.

std::shared_ptr< ExportForcesGenerator > ExportGaussNewtonForces::qpGenerator
private

Definition at line 221 of file export_gauss_newton_forces.hpp.

std::shared_ptr< ExportForcesInterface > ExportGaussNewtonForces::qpInterface
private

Definition at line 220 of file export_gauss_newton_forces.hpp.

std::string ExportGaussNewtonForces::qpModuleName
private

Definition at line 217 of file export_gauss_newton_forces.hpp.

std::string ExportGaussNewtonForces::qpObjPrefix
private

Definition at line 218 of file export_gauss_newton_forces.hpp.

ExportFunction ExportGaussNewtonForces::setObjQ1Q2
private

Definition at line 171 of file export_gauss_newton_forces.hpp.

ExportFunction ExportGaussNewtonForces::setObjQN1QN2
private

Definition at line 173 of file export_gauss_newton_forces.hpp.

ExportFunction ExportGaussNewtonForces::setObjR1R2
private

Definition at line 172 of file export_gauss_newton_forces.hpp.

ExportFunction ExportGaussNewtonForces::setObjS1
private

Definition at line 174 of file export_gauss_newton_forces.hpp.

ExportFunction ExportGaussNewtonForces::setStagef
private

Definition at line 169 of file export_gauss_newton_forces.hpp.

ExportFunction ExportGaussNewtonForces::setStageH
private

Definition at line 168 of file export_gauss_newton_forces.hpp.

ExportVariable ExportGaussNewtonForces::ubValues
private

Definition at line 184 of file export_gauss_newton_forces.hpp.

ExportVariable ExportGaussNewtonForces::x0
private

Current state feedback.

Definition at line 159 of file export_gauss_newton_forces.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