Allows to export a tailored lifted implicit Runge-Kutta integrator with forward sensitivity generation for extra fast model predictive control. More...
#include <irk_lifted_forward_export.hpp>

Public Member Functions | |
| ForwardLiftedIRKExport (UserInteraction *_userInteraction=0, const std::string &_commonHeaderName="") | |
| ForwardLiftedIRKExport (const ForwardLiftedIRKExport &arg) | |
| virtual returnValue | getCode (ExportStatementBlock &code) |
| virtual returnValue | getDataDeclarations (ExportStatementBlock &declarations, ExportStruct dataStruct=ACADO_ANY) const |
| virtual returnValue | getFunctionDeclarations (ExportStatementBlock &declarations) const |
| ForwardLiftedIRKExport & | operator= (const ForwardLiftedIRKExport &arg) |
| virtual returnValue | setDifferentialEquation (const Expression &rhs) |
| virtual returnValue | setup () |
| virtual | ~ForwardLiftedIRKExport () |
Public Member Functions inherited from ForwardIRKExport | |
| ForwardIRKExport (UserInteraction *_userInteraction=0, const std::string &_commonHeaderName="") | |
| ForwardIRKExport (const ForwardIRKExport &arg) | |
| ForwardIRKExport & | operator= (const ForwardIRKExport &arg) |
| virtual | ~ForwardIRKExport () |
Public Member Functions inherited from ImplicitRungeKuttaExport | |
| ImplicitRungeKuttaExport (UserInteraction *_userInteraction=0, const std::string &_commonHeaderName="") | |
| ImplicitRungeKuttaExport (const ImplicitRungeKuttaExport &arg) | |
| ImplicitRungeKuttaExport & | operator= (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) |
| RungeKuttaExport & | operator= (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) | |
| IntegratorExport & | operator= (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 |
| AlgorithmicBase & | operator= (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 () |
Allows to export a tailored lifted implicit Runge-Kutta integrator with forward sensitivity generation for extra fast model predictive control.
The class ForwardLiftedIRKExport allows to export a tailored lifted implicit Runge-Kutta integrator with forward sensitivity generation for extra fast model predictive control.
Definition at line 53 of file irk_lifted_forward_export.hpp.
| BEGIN_NAMESPACE_ACADO ForwardLiftedIRKExport::ForwardLiftedIRKExport | ( | 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_forward_export.cpp.
| ForwardLiftedIRKExport::ForwardLiftedIRKExport | ( | const ForwardLiftedIRKExport & | arg | ) |
Copy constructor (deep copy).
@param[in] arg Right-hand side object.
Definition at line 51 of file irk_lifted_forward_export.cpp.
|
virtual |
Destructor.
Definition at line 56 of file irk_lifted_forward_export.cpp.
|
protectedvirtual |
Reimplemented in ForwardBackwardLiftedIRKExport.
Definition at line 1127 of file irk_lifted_forward_export.cpp.
|
protectedvirtual |
Exports the evaluation of the states at all stages.
@param[in] block The block to which the code will be exported. @param[in] Ah The matrix A of the IRK method, multiplied by the step size h. @param[in] index The loop index, defining the stage. \return SUCCESSFUL_RETURN
Reimplemented in ForwardBackwardLiftedIRKExport.
Definition at line 977 of file irk_lifted_forward_export.cpp.
|
protectedvirtual |
Exports the evaluation of the inexact matrix for the linear system.
@param[in] block The block to which the code will be exported. @param[in] index1 The loop index of the outer loop. @param[in] index2 The loop index of the inner loop. @param[in] tmp_index A temporary index to be used. @param[in] Ah The matrix A of the IRK method, multiplied by the step size h. @param[in] evaluateB True if the right-hand side of the linear system should also be evaluated, false otherwise. \return SUCCESSFUL_RETURN
Definition at line 904 of file irk_lifted_forward_export.cpp.
|
protectedvirtual |
Exports the evaluation of the right-hand side of the linear system at a specific stage.
@param[in] block The block to which the code will be exported. @param[in] index The loop index, defining the stage. \return SUCCESSFUL_RETURN
Reimplemented from ImplicitRungeKuttaExport.
Definition at line 1017 of file irk_lifted_forward_export.cpp.
|
protectedvirtual |
Exports the code needed to compute the sensitivities of the states defined by the nonlinear, fully implicit system.
@param[in] block The block to which the code will be exported. @param[in] Ah The variable containing the internal coefficients of the RK method, multiplied with the step size. @param[in] Bh The variable containing the weights of the RK method, multiplied with the step size. @param[in] det The variable that holds the determinant of the matrix in the linear system. @param[in] STATES True if the sensitivities with respect to a state are needed, false otherwise. @param[in] number This number defines the stage of the state with respect to which the sensitivities are computed. \return SUCCESSFUL_RETURN
Reimplemented in ForwardBackwardLiftedIRKExport.
Definition at line 1041 of file irk_lifted_forward_export.cpp.
|
protectedvirtual |
Reimplemented in AdjointLiftedIRKExport.
Definition at line 1272 of file irk_lifted_forward_export.cpp.
|
protectedvirtual |
Exports the evaluation of the states at a specific stage.
@param[in] block The block to which the code will be exported. @param[in] Ah The matrix A of the IRK method, multiplied by the step size h. @param[in] index The loop index, defining the stage. \return SUCCESSFUL_RETURN
Reimplemented from ImplicitRungeKuttaExport.
Definition at line 998 of file irk_lifted_forward_export.cpp.
|
protectedvirtual |
Returns the largest global export variable.
\return SUCCESSFUL_RETURN
Reimplemented from ForwardIRKExport.
Reimplemented in SymmetricLiftedIRKExport.
Definition at line 77 of file irk_lifted_forward_export.cpp.
|
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 ForwardIRKExport.
Reimplemented in AdjointLiftedIRKExport, ForwardBackwardLiftedIRKExport, and SymmetricLiftedIRKExport.
Definition at line 252 of file irk_lifted_forward_export.cpp.
|
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 ForwardIRKExport.
Reimplemented in AdjointLiftedIRKExport, ForwardBackwardLiftedIRKExport, and SymmetricLiftedIRKExport.
Definition at line 118 of file irk_lifted_forward_export.cpp.
|
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 ForwardIRKExport.
Reimplemented in AdjointLiftedIRKExport, ForwardBackwardLiftedIRKExport, and SymmetricLiftedIRKExport.
Definition at line 151 of file irk_lifted_forward_export.cpp.
| ForwardLiftedIRKExport & ForwardLiftedIRKExport::operator= | ( | const ForwardLiftedIRKExport & | arg | ) |
Assignment operator (deep copy).
@param[in] arg Right-hand side object.
Definition at line 66 of file irk_lifted_forward_export.cpp.
|
protectedvirtual |
Precompute as much as possible for the linear input system and export the resulting definitions.
@param[in] code The block to which the code will be exported. \return SUCCESSFUL_RETURN
Reimplemented from ForwardIRKExport.
Definition at line 956 of file irk_lifted_forward_export.cpp.
|
protectedvirtual |
Precompute as much as possible for the linear output system and export the resulting definitions.
@param[in] code The block to which the code will be exported. \return SUCCESSFUL_RETURN
Reimplemented from ForwardIRKExport.
Definition at line 963 of file irk_lifted_forward_export.cpp.
|
protectedvirtual |
Exports the propagation of the sensitivities for the continuous output.
@param[in] block The block to which the code will be exported. @param[in] tmp_meas The number of measurements in the current integration step (in case of an online grid). \return SUCCESSFUL_RETURN
Reimplemented from ForwardIRKExport.
Definition at line 947 of file irk_lifted_forward_export.cpp.
|
protectedvirtual |
Exports the code needed to compute the sensitivities of the states, defined by the linear input system.
@param[in] block The block to which the code will be exported. @param[in] Bh The variable containing the weights of the RK method, multiplied with the step size. @param[in] STATES True if the sensitivities with respect to a state are needed, false otherwise. \return SUCCESSFUL_RETURN
Reimplemented from ForwardIRKExport.
Definition at line 970 of file irk_lifted_forward_export.cpp.
|
protectedvirtual |
Exports the computation of the sensitivities for the continuous output.
@param[in] block The block to which the code will be exported. @param[in] tmp_meas The number of measurements in the current integration step (in case of an online grid). @param[in] rk_tPrev The time point, defining the beginning of the current integration step (in case of an online grid). @param[in] time_tmp A variable used for time transformations (in case of an online grid). @param[in] STATES True if the sensitivities with respect to a state are needed, false otherwise. @param[in] base The number of states in stages with respect to which the sensitivities have already been computed. \return SUCCESSFUL_RETURN
Reimplemented from ForwardIRKExport.
Definition at line 1346 of file irk_lifted_forward_export.cpp.
|
protectedvirtual |
Exports the code needed to compute the sensitivities of the states, defined by the linear output system.
@param[in] block The block to which the code will be exported. @param[in] Ah The variable containing the internal coefficients of the RK method, multiplied with the step size. @param[in] Bh The variable containing the weights of the RK method, multiplied with the step size. @param[in] STATES True if the sensitivities with respect to a state are needed, false otherwise. @param[in] number This number defines the stage of the state with respect to which the sensitivities are computed. \return SUCCESSFUL_RETURN
Reimplemented from ForwardIRKExport.
Definition at line 1339 of file irk_lifted_forward_export.cpp.
|
virtual |
Assigns Differential Equation to be used by the integrator.
@param[in] rhs Right-hand side expression. \return SUCCESSFUL_RETURN
Reimplemented from ImplicitRungeKuttaExport.
Reimplemented in AdjointLiftedIRKExport, ForwardBackwardLiftedIRKExport, and SymmetricLiftedIRKExport.
Definition at line 162 of file irk_lifted_forward_export.cpp.
|
virtual |
Initializes export of a tailored integrator.
\return SUCCESSFUL_RETURN
Reimplemented from ForwardIRKExport.
Reimplemented in AdjointLiftedIRKExport, ForwardBackwardLiftedIRKExport, and SymmetricLiftedIRKExport.
Definition at line 1355 of file irk_lifted_forward_export.cpp.
|
protectedvirtual |
Exports the code needed to solve the system of collocation equations for the nonlinear, fully implicit system.
@param[in] block The block to which the code will be exported. @param[in] Ah The variable containing the internal coefficients of the RK method, multiplied with the step size. @param[in] det The variable that holds the determinant of the matrix in the linear system. \return SUCCESSFUL_RETURN
Reimplemented from ImplicitRungeKuttaExport.
Definition at line 815 of file irk_lifted_forward_export.cpp.
|
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 IntegratorExport.
Reimplemented in ForwardBackwardLiftedIRKExport, AdjointLiftedIRKExport, and SymmetricLiftedIRKExport.
Definition at line 1295 of file irk_lifted_forward_export.cpp.
|
protected |
Module to export the evaluation of an adjoint sweep of the derivatives of the ordinary differential equations.
Definition at line 394 of file irk_lifted_forward_export.hpp.
|
protected |
Module to export the evaluation of a forward sweep of the derivatives of the ordinary differential equations.
Definition at line 393 of file irk_lifted_forward_export.hpp.
|
protected |
Definition at line 397 of file irk_lifted_forward_export.hpp.
|
protected |
Variable containing the adjoint trajectory of the lambda_hat values.
Definition at line 396 of file irk_lifted_forward_export.hpp.
|
protected |
Definition at line 395 of file irk_lifted_forward_export.hpp.
|
protected |
Variable containing the update on the optimization variables.
Definition at line 410 of file irk_lifted_forward_export.hpp.
|
protected |
Definition at line 416 of file irk_lifted_forward_export.hpp.
|
protected |
Definition at line 401 of file irk_lifted_forward_export.hpp.
|
protected |
Definition at line 402 of file irk_lifted_forward_export.hpp.
|
protected |
Definition at line 413 of file irk_lifted_forward_export.hpp.
|
protected |
Variable containing the forward seed.
Definition at line 404 of file irk_lifted_forward_export.hpp.
|
protected |
Definition at line 398 of file irk_lifted_forward_export.hpp.
|
protected |
Variable containing the evaluated stage values.
Definition at line 405 of file irk_lifted_forward_export.hpp.
|
protected |
Variable containing the previous control trajectory.
Definition at line 408 of file irk_lifted_forward_export.hpp.
|
protected |
Definition at line 414 of file irk_lifted_forward_export.hpp.
|
protected |
Variable containing the full previous state trajectory.
Definition at line 407 of file irk_lifted_forward_export.hpp.
|
protected |
Definition at line 412 of file irk_lifted_forward_export.hpp.
|
protected |
Variable containing the forward trajectory of the state values.
Definition at line 399 of file irk_lifted_forward_export.hpp.