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

Allows to export a tailored lifted implicit Runge-Kutta integrator with symmetric second order sensitivity generation for extra fast model predictive control. More...

#include <irk_lifted_symmetric_export.hpp>

Inheritance diagram for SymmetricLiftedIRKExport:
Inheritance graph
[legend]

Public Member Functions

virtual returnValue getCode (ExportStatementBlock &code)
 
virtual returnValue getDataDeclarations (ExportStatementBlock &declarations, ExportStruct dataStruct=ACADO_ANY) const
 
virtual returnValue getFunctionDeclarations (ExportStatementBlock &declarations) const
 
SymmetricLiftedIRKExportoperator= (const SymmetricLiftedIRKExport &arg)
 
virtual returnValue setDifferentialEquation (const Expression &rhs)
 
virtual returnValue setup ()
 
 SymmetricLiftedIRKExport (UserInteraction *_userInteraction=0, const std::string &_commonHeaderName="")
 
 SymmetricLiftedIRKExport (const SymmetricLiftedIRKExport &arg)
 
virtual ~SymmetricLiftedIRKExport ()
 
- Public Member Functions inherited from ForwardLiftedIRKExport
 ForwardLiftedIRKExport (UserInteraction *_userInteraction=0, const std::string &_commonHeaderName="")
 
 ForwardLiftedIRKExport (const ForwardLiftedIRKExport &arg)
 
ForwardLiftedIRKExportoperator= (const ForwardLiftedIRKExport &arg)
 
virtual ~ForwardLiftedIRKExport ()
 
- Public Member Functions inherited from ForwardIRKExport
 ForwardIRKExport (UserInteraction *_userInteraction=0, const std::string &_commonHeaderName="")
 
 ForwardIRKExport (const ForwardIRKExport &arg)
 
ForwardIRKExportoperator= (const ForwardIRKExport &arg)
 
virtual ~ForwardIRKExport ()
 
- Public Member Functions inherited from ImplicitRungeKuttaExport
 ImplicitRungeKuttaExport (UserInteraction *_userInteraction=0, const std::string &_commonHeaderName="")
 
 ImplicitRungeKuttaExport (const ImplicitRungeKuttaExport &arg)
 
ImplicitRungeKuttaExportoperator= (const ImplicitRungeKuttaExport &arg)
 
returnValue setEigenvalues (const DMatrix &_eig)
 
returnValue setModel (const std::string &_rhs, const std::string &_diffs_rhs)
 
returnValue setSimplifiedTransformations (const DMatrix &_transf1, const DMatrix &_transf2)
 
returnValue setSimplifiedTransformations (const DMatrix &_transf1, const DMatrix &_transf2, const DMatrix &_transf1_T, const DMatrix &_transf2_T)
 
returnValue setSingleTransformations (const double _tau, const DVector &_low_tria, const DMatrix &_transf1, const DMatrix &_transf2)
 
returnValue setSingleTransformations (const double _tau, const DVector &_low_tria, const DMatrix &_transf1, const DMatrix &_transf2, const DMatrix &_transf1_T, const DMatrix &_transf2_T)
 
virtual returnValue setupOutput (const std::vector< Grid > outputGrids_, const std::vector< Expression > rhs)
 
virtual returnValue setupOutput (const std::vector< Grid > outputGrids_, const std::vector< std::string > _outputNames, const std::vector< std::string > _diffs_outputNames, const std::vector< uint > _dims_output)
 
virtual returnValue setupOutput (const std::vector< Grid > outputGrids_, const std::vector< std::string > _outputNames, const std::vector< std::string > _diffs_outputNames, const std::vector< uint > _dims_output, const std::vector< DMatrix > _outputDependencies)
 
virtual ~ImplicitRungeKuttaExport ()
 
- Public Member Functions inherited from RungeKuttaExport
BooleanType checkSymmetry (const DVector &_cc)
 
uint getNumStages ()
 
returnValue initializeButcherTableau (const DMatrix &_AA, const DVector &_bb, const DVector &_cc)
 
RungeKuttaExportoperator= (const RungeKuttaExport &arg)
 
 RungeKuttaExport (UserInteraction *_userInteraction=0, const std::string &_commonHeaderName="")
 
 RungeKuttaExport (const RungeKuttaExport &arg)
 
returnValue setNARXmodel (const uint delay, const DMatrix &parms)
 
virtual ~RungeKuttaExport ()
 
- Public Member Functions inherited from IntegratorExport
virtual bool equidistantControlGrid () const
 
uint getDimOUTPUT (uint index) const
 
virtual returnValue getGrid (Grid &grid_) const
 
const std::string getNameDiffsOUTPUT (uint index) const
 
const std::string getNameDiffsRHS () const
 
virtual const std::string getNameFullRHS () const
 
const std::string getNameOUTPUT (uint index) const
 
const std::string getNameOutputDiffs () const
 
const std::string getNameOutputRHS () const
 
const std::string getNameRHS () const
 
virtual returnValue getNumSteps (DVector &_numSteps) const
 
virtual returnValue getOutputExpressions (std::vector< Expression > &outputExpressions_) const
 
virtual returnValue getOutputGrids (std::vector< Grid > &outputGrids_) const
 
 IntegratorExport (UserInteraction *_userInteraction=0, const std::string &_commonHeaderName="")
 
 IntegratorExport (const IntegratorExport &arg)
 
IntegratorExportoperator= (const IntegratorExport &arg)
 
virtual returnValue propagateImplicitSystem (ExportStatementBlock *block, const ExportIndex &index1, const ExportIndex &index2, const ExportIndex &_index3, const ExportIndex &tmp_index)
 
virtual returnValue propagateInputSystem (ExportStatementBlock *block, const ExportIndex &index1, const ExportIndex &index2, const ExportIndex &index3, const ExportIndex &tmp_index)
 
virtual returnValue propagateOutputSystem (ExportStatementBlock *block, const ExportIndex &index1, const ExportIndex &index2, const ExportIndex &index3, const ExportIndex &tmp_index)
 
virtual returnValue setGrid (const Grid &_grid)
 
virtual returnValue setLinearInput (const DMatrix &M1, const DMatrix &A1, const DMatrix &B1)
 
virtual returnValue setLinearOutput (const DMatrix &M3, const DMatrix &A3, const Expression &rhs)
 
virtual returnValue setLinearOutput (const DMatrix &M3, const DMatrix &A3, const std::string &_rhs3, const std::string &_diffs_rhs3)
 
virtual returnValue setModelData (const ModelData &data)
 
virtual returnValue setNonlinearFeedback (const DMatrix &C, const Expression &feedb)
 
virtual returnValue updateInputSystem (ExportStatementBlock *block, const ExportIndex &index1, const ExportIndex &index2, const ExportIndex &tmp_index)
 
virtual returnValue updateOutputSystem (ExportStatementBlock *block, const ExportIndex &index1, const ExportIndex &index2, const ExportIndex &tmp_index)
 
virtual ~IntegratorExport ()
 
- 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

ExportVariable getAuxVariable () const
 
Expression returnLowerTriangular (const Expression &expr)
 
virtual returnValue updateImplicitSystem (ExportStatementBlock *block, const ExportIndex &index1, const ExportIndex &index2, const ExportIndex &tmp_index)
 
- Protected Member Functions inherited from ForwardLiftedIRKExport
virtual returnValue allSensitivitiesImplicitSystem (ExportStatementBlock *block, const ExportIndex &index1, const ExportIndex &index2, const ExportIndex &index3, const ExportIndex &tmp_index1, const ExportIndex &tmp_index2, const ExportIndex &tmp_index3, const ExportIndex &k_index, const ExportVariable &Bh, bool update)
 
virtual returnValue evaluateAllStatesImplicitSystem (ExportStatementBlock *block, const ExportIndex &k_index, const ExportVariable &Ah, const ExportVariable &C, const ExportIndex &stage, const ExportIndex &i, const ExportIndex &tmp_index)
 
virtual returnValue evaluateInexactMatrix (ExportStatementBlock *block, const ExportIndex &index1, const ExportIndex &index2, const ExportIndex &tmp_index, const ExportIndex &k_index, const ExportVariable &_rk_A, const ExportVariable &Ah, const ExportVariable &C, bool evaluateB, bool DERIVATIVES)
 
virtual returnValue evaluateRhsImplicitSystem (ExportStatementBlock *block, const ExportIndex &k_index, const ExportIndex &stage)
 
virtual returnValue evaluateRhsInexactSensitivities (ExportStatementBlock *block, const ExportIndex &index1, const ExportIndex &index2, const ExportIndex &index3, const ExportIndex &tmp_index1, const ExportIndex &tmp_index2, const ExportIndex &tmp_index3, const ExportIndex &k_index, const ExportVariable &Ah)
 
virtual returnValue evaluateRhsSensitivities (ExportStatementBlock *block, const ExportIndex &index1, const ExportIndex &index2, const ExportIndex &index3, const ExportIndex &tmp_index1, const ExportIndex &tmp_index2)
 
virtual returnValue evaluateStatesImplicitSystem (ExportStatementBlock *block, const ExportIndex &k_index, const ExportVariable &Ah, const ExportVariable &C, const ExportIndex &stage, const ExportIndex &i, const ExportIndex &tmp_index)
 
virtual returnValue prepareInputSystem (ExportStatementBlock &code)
 
virtual returnValue prepareOutputSystem (ExportStatementBlock &code)
 
virtual returnValue propagateOutputs (ExportStatementBlock *block, const ExportIndex &index, const ExportIndex &index0, const ExportIndex &index1, const ExportIndex &index2, const ExportIndex &index3, const ExportIndex &tmp_index1, const ExportIndex &tmp_index2, const ExportIndex &tmp_index3, const ExportIndex &tmp_index4, const ExportVariable &tmp_meas)
 
virtual returnValue sensitivitiesInputSystem (ExportStatementBlock *block, const ExportIndex &index1, const ExportIndex &index2, const ExportVariable &Bh, bool STATES)
 
returnValue sensitivitiesOutputs (ExportStatementBlock *block, const ExportIndex &index0, const ExportIndex &index1, const ExportIndex &index2, const ExportIndex &tmp_index1, const ExportIndex &tmp_index2, const ExportIndex &tmp_index3, const ExportVariable &tmp_meas, const ExportVariable &time_tmp, bool STATES, uint base)
 
virtual returnValue sensitivitiesOutputSystem (ExportStatementBlock *block, const ExportIndex &index1, const ExportIndex &index2, const ExportIndex &index3, const ExportIndex &index4, const ExportIndex &tmp_index1, const ExportIndex &tmp_index2, const ExportVariable &Ah, const ExportVariable &Bh, bool STATES, uint number)
 
virtual returnValue solveImplicitSystem (ExportStatementBlock *block, const ExportIndex &index1, const ExportIndex &index2, const ExportIndex &index3, const ExportIndex &tmp_index, const ExportIndex &k_index, const ExportVariable &Ah, const ExportVariable &C, const ExportVariable &det, bool DERIVATIVES=false)
 
- Protected Member Functions inherited from ForwardIRKExport
returnValue getCRSIndex (uint output, ExportIndex row, ExportIndex col)
 
virtual returnValue sensitivitiesImplicitSystem (ExportStatementBlock *block, const ExportIndex &index1, const ExportIndex &index2, const ExportIndex &index3, const ExportIndex &tmp_index1, const ExportIndex &tmp_index2, const ExportVariable &Ah, const ExportVariable &Bh, const ExportVariable &det, bool STATES, uint number)
 
- Protected Member Functions inherited from ImplicitRungeKuttaExport
DVector computeCombinations (const DVector &cVec, uint index, uint numEls)
 
virtual returnValue copy (const ImplicitRungeKuttaExport &arg)
 
DVector divideMeasurements (uint index)
 
DVector evaluateDerivedPolynomial (double time)
 
returnValue evaluateDerivedPolynomial (ExportStatementBlock &block, const ExportVariable &variable, const ExportVariable &grid)
 
DMatrix evaluateDerivedPolynomial (uint index)
 
virtual returnValue evaluateMatrix (ExportStatementBlock *block, const ExportIndex &index1, const ExportIndex &index2, const ExportIndex &tmp_index, const ExportIndex &k_index, const ExportVariable &_rk_A, const ExportVariable &Ah, const ExportVariable &C, bool evaluateB, bool DERIVATIVES)
 
DVector evaluatePolynomial (double time)
 
returnValue evaluatePolynomial (ExportStatementBlock &block, const ExportVariable &variable, const ExportVariable &grid, const std::string &h)
 
DMatrix evaluatePolynomial (uint index)
 
returnValue evaluateStatesOutputSystem (ExportStatementBlock *block, const ExportVariable &Ah, const ExportIndex &stage)
 
virtual DMatrix formMatrix (const DMatrix &mass, const DMatrix &jacobian)
 
returnValue generateOutput (ExportStatementBlock *block, const ExportIndex &index0, const ExportIndex &index1, const ExportIndex &tmp_index1, const ExportIndex &tmp_index2, const ExportVariable &tmp_meas, const ExportVariable &time_tmp, const uint directions)
 
uint getNumIts () const
 
uint getNumItsInit () const
 
returnValue initializeCoefficients ()
 
returnValue initializeDDMatrix ()
 
returnValue prepareOutputEvaluation (ExportStatementBlock &code)
 
virtual returnValue solveInputSystem (ExportStatementBlock *block, const ExportIndex &index1, const ExportIndex &index2, const ExportIndex &index3, const ExportIndex &tmp_index, const ExportVariable &Ah)
 
virtual returnValue solveOutputSystem (ExportStatementBlock *block, const ExportIndex &index1, const ExportIndex &index2, const ExportIndex &index3, const ExportIndex &tmp_index, const ExportVariable &Ah, bool DERIVATIVES=false)
 
- Protected Member Functions inherited from RungeKuttaExport
virtual returnValue copy (const RungeKuttaExport &arg)
 
- Protected Member Functions inherited from IntegratorExport
virtual returnValue clear ()
 
virtual returnValue copy (const IntegratorExport &arg)
 
DMatrix expandOutputMatrix (const DMatrix &A3)
 
uint getIntegrationInterval (double time)
 

Protected Attributes

ExportAcadoFunction diffs_sweep
 
ExportVariable rk_A_traj
 
ExportVariable rk_aux_traj
 
ExportVariable rk_b_mu
 
ExportVariable rk_delta_full
 
ExportVariable rk_diff_lam
 
ExportVariable rk_diff_mu
 
ExportVariable rk_kkk_delta
 
ExportVariable rk_kkk_prev
 
ExportVariable rk_lambda
 
ExportVariable rk_S_traj
 
- Protected Attributes inherited from ForwardLiftedIRKExport
ExportAcadoFunction adjoint_sweep
 
ExportAcadoFunction forward_sweep
 
ExportVariable rk_adj_diffs_tmp
 
ExportVariable rk_adj_traj
 
ExportVariable rk_b_trans
 
ExportVariable rk_delta
 
ExportVariable rk_diffK_local
 
ExportVariable rk_diffSweep
 
ExportVariable rk_I
 
ExportVariable rk_Khat_traj
 
ExportVariable rk_seed
 
ExportVariable rk_seed2
 
ExportVariable rk_stageValues
 
ExportVariable rk_Uprev
 
ExportVariable rk_Xhat_traj
 
ExportVariable rk_Xprev
 
ExportVariable rk_xxx_lin
 
ExportVariable rk_xxx_traj
 
- Protected Attributes inherited from ImplicitRungeKuttaExport
DMatrix coeffs
 
bool CONTINUOUS_OUTPUT
 
DMatrix DD
 
ExportVariable debug_mat
 
DMatrix eig
 
std::vector< ExportVariablegridVariables
 
ExportAcadoFunction lin_output
 
DVector low_tria
 
uint NDX2
 
DVector numDX_output
 
uint numIts
 
uint numItsInit
 
std::vector< ExportIndexnumMeas
 
std::vector< ExportVariablenumMeasVariables
 
DVector numVARS_output
 
DVector numXA_output
 
uint NVARS2
 
uint NVARS3
 
std::vector< ExportVariablepolynDerVariables
 
ExportVariable polynEvalVar
 
std::vector< ExportVariablepolynVariables
 
bool REUSE
 
ExportVariable rk_A
 
ExportVariable rk_auxSolver
 
ExportVariable rk_b
 
ExportVariable rk_diffK
 
ExportVariable rk_diffsOutputTemp
 
ExportVariable rk_diffsTemp3
 
ExportVariable rk_dk1
 
ExportVariable rk_dk3
 
ExportVariable rk_mat1
 
ExportVariable rk_mat3
 
ExportVariable rk_out
 
ExportVariable rk_outH
 
std::vector< ExportVariablerk_outputs
 
ExportVariable rk_rhsOutputTemp
 
ExportVariable rk_rhsTemp
 
DMatrix simplified_transf1
 
DMatrix simplified_transf1_T
 
DMatrix simplified_transf2
 
DMatrix simplified_transf2_T
 
DMatrix single_transf1
 
DMatrix single_transf1_T
 
DMatrix single_transf2
 
DMatrix single_transf2_T
 
ExportLinearSolversolver
 
ExportVariable stepsH
 
double tau
 
std::vector< uinttotalMeas
 
- Protected Attributes inherited from RungeKuttaExport
DMatrix AA
 
DVector bb
 
DVector cc
 
BooleanType is_symmetric
 
uint numStages
 
ExportVariable rk_kkk
 
- Protected Attributes inherited from IntegratorExport
DMatrix A11
 
DMatrix A33
 
DMatrix B11
 
bool crsFormat
 
std::vector< ExportAcadoFunctiondiffs_outputs
 
ExportAcadoFunction diffs_rhs
 
ExportAcadoFunction diffs_rhs3
 
uint diffsDim
 
DifferentialStateDerivative dx
 
ExportVariable error_code
 
bool exportRhs
 
ExportFunction fullRhs
 
Grid grid
 
uint inputDim
 
ExportFunction integrate
 
ExportAcadoFunction lin_input
 
DMatrix M11
 
DMatrix M33
 
uint NDX3
 
std::vector< uintnum_outputs
 
DVector numSteps
 
uint NX1
 
uint NX2
 
uint NX3
 
uint NXA3
 
OnlineData od
 
std::vector< DMatrixoutputDependencies
 
std::vector< ExpressionoutputExpressions
 
std::vector< GridoutputGrids
 
std::vector< ExportAcadoFunctionoutputs
 
ExportVariable reset_int
 
ExportAcadoFunction rhs
 
ExportAcadoFunction rhs3
 
ExportVariable rhs_in
 
ExportVariable rhs_out
 
ExportVariable rk_diffsNew1
 
ExportVariable rk_diffsNew2
 
ExportVariable rk_diffsNew3
 
ExportVariable rk_diffsPrev1
 
ExportVariable rk_diffsPrev2
 
ExportVariable rk_diffsPrev3
 
ExportVariable rk_diffsTemp2
 
ExportVariable rk_eta
 
ExportVariable rk_index
 
ExportVariable rk_ttt
 
ExportVariable rk_xxx
 
bool timeDependant
 
Control u
 
DifferentialState x
 
AlgebraicState z
 
- 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

Allows to export a tailored lifted implicit Runge-Kutta integrator with symmetric second order sensitivity generation for extra fast model predictive control.

The class SymmetricLiftedIRKExport allows to export a tailored lifted implicit Runge-Kutta integrator with symmetric second order sensitivity generation for extra fast model predictive control.

Author
Rien Quirynen

Definition at line 53 of file irk_lifted_symmetric_export.hpp.

Constructor & Destructor Documentation

BEGIN_NAMESPACE_ACADO SymmetricLiftedIRKExport::SymmetricLiftedIRKExport ( 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 45 of file irk_lifted_symmetric_export.cpp.

SymmetricLiftedIRKExport::SymmetricLiftedIRKExport ( const SymmetricLiftedIRKExport arg)

Copy constructor (deep copy).

@param[in] arg              Right-hand side object.

Definition at line 51 of file irk_lifted_symmetric_export.cpp.

SymmetricLiftedIRKExport::~SymmetricLiftedIRKExport ( )
virtual

Destructor.

Definition at line 56 of file irk_lifted_symmetric_export.cpp.

Member Function Documentation

ExportVariable SymmetricLiftedIRKExport::getAuxVariable ( ) const
protectedvirtual

Returns the largest global export variable.

\return SUCCESSFUL_RETURN

Reimplemented from ForwardLiftedIRKExport.

Definition at line 77 of file irk_lifted_symmetric_export.cpp.

returnValue SymmetricLiftedIRKExport::getCode ( ExportStatementBlock code)
virtual

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

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

\return SUCCESSFUL_RETURN

Reimplemented from ForwardLiftedIRKExport.

Definition at line 272 of file irk_lifted_symmetric_export.cpp.

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

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

@param[in] declarations             List of declarations.

\return SUCCESSFUL_RETURN

Reimplemented from ForwardLiftedIRKExport.

Definition at line 121 of file irk_lifted_symmetric_export.cpp.

returnValue SymmetricLiftedIRKExport::getFunctionDeclarations ( ExportStatementBlock declarations) const
virtual

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

@param[in] declarations             List of declarations.

\return SUCCESSFUL_RETURN

Reimplemented from ForwardLiftedIRKExport.

Definition at line 144 of file irk_lifted_symmetric_export.cpp.

SymmetricLiftedIRKExport & SymmetricLiftedIRKExport::operator= ( const SymmetricLiftedIRKExport arg)

Assignment operator (deep copy).

@param[in] arg              Right-hand side object.

Definition at line 66 of file irk_lifted_symmetric_export.cpp.

Expression SymmetricLiftedIRKExport::returnLowerTriangular ( const Expression expr)
protected

Definition at line 258 of file irk_lifted_symmetric_export.cpp.

returnValue SymmetricLiftedIRKExport::setDifferentialEquation ( const Expression rhs)
virtual

Assigns Differential Equation to be used by the integrator.

@param[in] rhs              Right-hand side expression.

\return SUCCESSFUL_RETURN

Reimplemented from ForwardLiftedIRKExport.

Definition at line 153 of file irk_lifted_symmetric_export.cpp.

returnValue SymmetricLiftedIRKExport::setup ( )
virtual

Initializes export of a tailored integrator.

\return SUCCESSFUL_RETURN

Reimplemented from ForwardLiftedIRKExport.

Definition at line 829 of file irk_lifted_symmetric_export.cpp.

returnValue SymmetricLiftedIRKExport::updateImplicitSystem ( ExportStatementBlock block,
const ExportIndex index1,
const ExportIndex index2,
const ExportIndex tmp_index 
)
protectedvirtual

Exports the code needed to update the sensitivities of the states defined by the nonlinear, fully implicit system.

@param[in] block                    The block to which the code will be exported.

\return SUCCESSFUL_RETURN

Reimplemented from ForwardLiftedIRKExport.

Definition at line 803 of file irk_lifted_symmetric_export.cpp.

Member Data Documentation

ExportAcadoFunction SymmetricLiftedIRKExport::diffs_sweep
protected

Module to export the evaluation of a forward sweep of the derivatives of the ordinary differential equations.

Definition at line 160 of file irk_lifted_symmetric_export.hpp.

ExportVariable SymmetricLiftedIRKExport::rk_A_traj
protected

Variable containing the factorized matrix of the linear system over the forward trajectory.

Definition at line 163 of file irk_lifted_symmetric_export.hpp.

ExportVariable SymmetricLiftedIRKExport::rk_aux_traj
protected

Variable containing the factorized matrix of the linear system over the forward trajectory.

Definition at line 164 of file irk_lifted_symmetric_export.hpp.

ExportVariable SymmetricLiftedIRKExport::rk_b_mu
protected

The lambda variables over the shooting interval.

Definition at line 173 of file irk_lifted_symmetric_export.hpp.

ExportVariable SymmetricLiftedIRKExport::rk_delta_full
protected

Variable containing the FULL update on all the variables.

Definition at line 168 of file irk_lifted_symmetric_export.hpp.

ExportVariable SymmetricLiftedIRKExport::rk_diff_lam
protected

Sensitivities to propagate the lambda variables.

Definition at line 170 of file irk_lifted_symmetric_export.hpp.

ExportVariable SymmetricLiftedIRKExport::rk_diff_mu
protected

Sensitivities to update the mu variables.

Definition at line 169 of file irk_lifted_symmetric_export.hpp.

ExportVariable SymmetricLiftedIRKExport::rk_kkk_delta
protected

TODO.

Definition at line 167 of file irk_lifted_symmetric_export.hpp.

ExportVariable SymmetricLiftedIRKExport::rk_kkk_prev
protected

TODO.

Definition at line 166 of file irk_lifted_symmetric_export.hpp.

ExportVariable SymmetricLiftedIRKExport::rk_lambda
protected

The lambda variables over the shooting interval.

Definition at line 172 of file irk_lifted_symmetric_export.hpp.

ExportVariable SymmetricLiftedIRKExport::rk_S_traj
protected

Variable containing the forward trajectory of the first order sensitivities.

Definition at line 162 of file irk_lifted_symmetric_export.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:27