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

Allows to export a tailored Runge-Kutta integrator for fast model predictive control. More...

#include <rk_export.hpp>

Inheritance diagram for RungeKuttaExport:
Inheritance graph
[legend]

Public Member Functions

BooleanType checkSymmetry (const DVector &_cc)
 
virtual returnValue getCode (ExportStatementBlock &code)=0
 
virtual returnValue getDataDeclarations (ExportStatementBlock &declarations, ExportStruct dataStruct=ACADO_ANY) const =0
 
virtual returnValue getFunctionDeclarations (ExportStatementBlock &declarations) const =0
 
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)
 
virtual returnValue setDifferentialEquation (const Expression &rhs)=0
 
returnValue setNARXmodel (const uint delay, const DMatrix &parms)
 
virtual returnValue setup ()=0
 
virtual returnValue setupOutput (const std::vector< Grid > outputGrids_, const std::vector< Expression > rhs)=0
 
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 setModel (const std::string &_name_ODE, const std::string &_name_diffs_ODE)
 
virtual returnValue setModelData (const ModelData &data)
 
virtual returnValue setNonlinearFeedback (const DMatrix &C, const Expression &feedb)
 
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)=0
 
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)=0
 
virtual returnValue updateImplicitSystem (ExportStatementBlock *block, const ExportIndex &index1, const ExportIndex &index2, const ExportIndex &tmp_index)
 
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

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)
 
virtual ExportVariable getAuxVariable () const =0
 
uint getIntegrationInterval (double time)
 

Protected Attributes

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 Runge-Kutta integrator for fast model predictive control.

The class RungeKuttaExport allows to export a tailored Runge-Kutta integrator for fast model predictive control.

Author
Rien Quirynen

Definition at line 54 of file rk_export.hpp.

Constructor & Destructor Documentation

BEGIN_NAMESPACE_ACADO RungeKuttaExport::RungeKuttaExport ( 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 rk_export.cpp.

RungeKuttaExport::RungeKuttaExport ( const RungeKuttaExport arg)

Copy constructor (deep copy).

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

Definition at line 52 of file rk_export.cpp.

RungeKuttaExport::~RungeKuttaExport ( )
virtual

Destructor.

Definition at line 59 of file rk_export.cpp.

Member Function Documentation

BooleanType RungeKuttaExport::checkSymmetry ( const DVector _cc)

This routine checks the symmetry of the cc vector from the Butcher Tableau.

Definition at line 93 of file rk_export.cpp.

returnValue RungeKuttaExport::copy ( const RungeKuttaExport arg)
protectedvirtual

Copies all class members from given object.

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

\return SUCCESSFUL_RETURN

Definition at line 122 of file rk_export.cpp.

virtual returnValue RungeKuttaExport::getCode ( ExportStatementBlock code)
pure 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

Implements IntegratorExport.

Implemented in ImplicitRungeKuttaExport, ExplicitRungeKuttaExport, AdjointLiftedIRKExport, FeedbackLiftedIRKExport, ForwardBackwardLiftedIRKExport, ForwardLiftedIRKExport, SymmetricLiftedIRKExport, SymmetricIRKExport, ForwardIRKExport, LiftedERKExport, ThreeSweepsERKExport, and AdjointERKExport.

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

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

@param[in] declarations             List of declarations.

\return SUCCESSFUL_RETURN

Implements IntegratorExport.

Implemented in ImplicitRungeKuttaExport, ExplicitRungeKuttaExport, AdjointLiftedIRKExport, FeedbackLiftedIRKExport, ForwardBackwardLiftedIRKExport, ForwardLiftedIRKExport, SymmetricLiftedIRKExport, SymmetricIRKExport, LiftedERKExport, ThreeSweepsERKExport, AdjointERKExport, and ForwardIRKExport.

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

Implements IntegratorExport.

Implemented in ImplicitRungeKuttaExport, ExplicitRungeKuttaExport, AdjointLiftedIRKExport, FeedbackLiftedIRKExport, ForwardBackwardLiftedIRKExport, ForwardLiftedIRKExport, SymmetricLiftedIRKExport, SymmetricIRKExport, and ForwardIRKExport.

uint RungeKuttaExport::getNumStages ( )

This routine returns the number of stages of the Runge-Kutta integrator that will be exported.

Definition at line 106 of file rk_export.cpp.

returnValue RungeKuttaExport::initializeButcherTableau ( const DMatrix _AA,
const DVector _bb,
const DVector _cc 
)

This routine initializes the matrices AA, bb and cc which form the Butcher Tableau.

Definition at line 78 of file rk_export.cpp.

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

Assignment operator (deep copy).

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

Definition at line 65 of file rk_export.cpp.

virtual returnValue RungeKuttaExport::setDifferentialEquation ( const Expression rhs)
pure virtual

Assigns Differential Equation to be used by the integrator.

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

\return SUCCESSFUL_RETURN

Implements IntegratorExport.

Implemented in ImplicitRungeKuttaExport, AdjointLiftedIRKExport, ForwardBackwardLiftedIRKExport, ForwardLiftedIRKExport, SymmetricLiftedIRKExport, SymmetricIRKExport, ExplicitRungeKuttaExport, LiftedERKExport, ThreeSweepsERKExport, AdjointERKExport, and ForwardOverBackwardERKExport.

returnValue RungeKuttaExport::setNARXmodel ( const uint  delay,
const DMatrix parms 
)
virtual

Sets a polynomial NARX model to be used by the integrator.

@param[in] delay            The delay for the states in the NARX model.
@param[in] parms            The parameters defining the polynomial NARX model.

\return SUCCESSFUL_RETURN

Implements IntegratorExport.

Definition at line 112 of file rk_export.cpp.

virtual returnValue RungeKuttaExport::setup ( )
pure virtual
virtual returnValue RungeKuttaExport::setupOutput ( const std::vector< Grid outputGrids_,
const std::vector< Expression rhs 
)
pure virtual

Sets up the output with the grids for the different output functions.

Parameters
outputGrids_The vector containing a grid for each output function.
rhsThe expressions corresponding the output functions.

Returns
SUCCESSFUL_RETURN

Implements IntegratorExport.

Implemented in ExplicitRungeKuttaExport, and ImplicitRungeKuttaExport.

Member Data Documentation

DMatrix RungeKuttaExport::AA
protected

This matrix defines the Runge-Kutta method to be exported.

Definition at line 191 of file rk_export.hpp.

DVector RungeKuttaExport::bb
protected

Definition at line 192 of file rk_export.hpp.

DVector RungeKuttaExport::cc
protected

These vectors define the Runge-Kutta method to be exported.

Definition at line 192 of file rk_export.hpp.

BooleanType RungeKuttaExport::is_symmetric
protected

Boolean defining whether a certain RK method is symmetric or not, which is important for backward sensitivity propagation.

Definition at line 194 of file rk_export.hpp.

uint RungeKuttaExport::numStages
protected

This is the number of stages for the Runge-Kutta method.

Definition at line 196 of file rk_export.hpp.

ExportVariable RungeKuttaExport::rk_kkk
protected

Variable containing intermediate results of the RK integrator.

Definition at line 189 of file rk_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:26