Public Member Functions

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

#include <dirk_export.hpp>

Inheritance diagram for DiagonallyImplicitRKExport:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 DiagonallyImplicitRKExport (UserInteraction *_userInteraction=0, const std::string &_commonHeaderName="")
 DiagonallyImplicitRKExport (const DiagonallyImplicitRKExport &arg)
virtual returnValue evaluateMatrix (ExportStatementBlock *block, const ExportIndex &index1, const ExportIndex &index2, const ExportIndex &tmp_index, const ExportVariable &Ah, const ExportVariable &C, bool evaluateB, bool DERIVATIVES)
virtual returnValue evaluateRhsImplicitSystem (ExportStatementBlock *block, const ExportIndex &stage)
virtual returnValue evaluateStatesImplicitSystem (ExportStatementBlock *block, const ExportVariable &Ah, const ExportVariable &C, const ExportIndex &stage, const ExportIndex &i, const ExportIndex &j)
virtual DMatrix formMatrix (const DMatrix &mass, const DMatrix &jacobian)
DiagonallyImplicitRKExportoperator= (const DiagonallyImplicitRKExport &arg)
virtual returnValue prepareInputSystem (ExportStatementBlock &code)
virtual returnValue prepareOutputSystem (ExportStatementBlock &code)
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)
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 setup ()
virtual returnValue solveImplicitSystem (ExportStatementBlock *block, const ExportIndex &index1, const ExportIndex &index2, const ExportIndex &index3, const ExportIndex &tmp_index, const ExportVariable &Ah, const ExportVariable &C, const ExportVariable &det, bool DERIVATIVES=false)
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)
virtual ~DiagonallyImplicitRKExport ()

Detailed Description

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

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

Author:
Rien Quirynen

Definition at line 54 of file dirk_export.hpp.


Constructor & Destructor Documentation

BEGIN_NAMESPACE_ACADO DiagonallyImplicitRKExport::DiagonallyImplicitRKExport ( UserInteraction _userInteraction = 0,
const std::string &  _commonHeaderName = "" 
)

Default constructor.

Parameters:
[in]_userInteractionPointer to corresponding user interface.
[in]_commonHeaderNameName of common header file to be included.

Definition at line 48 of file dirk_export.cpp.

Copy constructor (deep copy).

Parameters:
[in]argRight-hand side object.

Definition at line 55 of file dirk_export.cpp.

Destructor.

Definition at line 61 of file dirk_export.cpp.


Member Function Documentation

returnValue DiagonallyImplicitRKExport::evaluateMatrix ( ExportStatementBlock block,
const ExportIndex index1,
const ExportIndex index2,
const ExportIndex tmp_index,
const ExportVariable Ah,
const ExportVariable C,
bool  evaluateB,
bool  DERIVATIVES 
) [virtual]

Exports the evaluation of the matrix of the linear system.

Parameters:
[in]blockThe block to which the code will be exported.
[in]index1The loop index of the outer loop.
[in]index2The loop index of the inner loop.
[in]tmp_indexA temporary index to be used.
[in]AhThe matrix A of the IRK method, multiplied by the step size h.
[in]evaluateBTrue if the right-hand side of the linear system should also be evaluated, false otherwise.
Returns:
SUCCESSFUL_RETURN

Reimplemented from ImplicitRungeKuttaExport.

Definition at line 319 of file dirk_export.cpp.

Exports the evaluation of the right-hand side of the linear system at a specific stage.

Parameters:
[in]blockThe block to which the code will be exported.
[in]indexThe loop index, defining the stage.
Returns:
SUCCESSFUL_RETURN

Reimplemented from ImplicitRungeKuttaExport.

Definition at line 375 of file dirk_export.cpp.

returnValue DiagonallyImplicitRKExport::evaluateStatesImplicitSystem ( ExportStatementBlock block,
const ExportVariable Ah,
const ExportVariable C,
const ExportIndex stage,
const ExportIndex i,
const ExportIndex j 
) [virtual]

Exports the evaluation of the states at a specific stage.

Parameters:
[in]blockThe block to which the code will be exported.
[in]AhThe matrix A of the IRK method, multiplied by the step size h.
[in]indexThe loop index, defining the stage.
Returns:
SUCCESSFUL_RETURN

Reimplemented from ImplicitRungeKuttaExport.

Definition at line 350 of file dirk_export.cpp.

DMatrix DiagonallyImplicitRKExport::formMatrix ( const DMatrix mass,
const DMatrix jacobian 
) [virtual]

Forms a constant linear system matrix for the collocation equations, given a constant jacobian and mass matrix.

Parameters:
[in]jacobiangiven constant Jacobian matrix
[in]massgiven constant mass matrix
Returns:
SUCCESSFUL_RETURN

Reimplemented from ImplicitRungeKuttaExport.

Definition at line 163 of file dirk_export.cpp.

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

Assignment operator (deep copy).

Parameters:
[in]argRight-hand side object.

Definition at line 71 of file dirk_export.cpp.

Precompute as much as possible for the linear input system and export the resulting definitions.

Parameters:
[in]codeThe block to which the code will be exported.
Returns:
SUCCESSFUL_RETURN

Reimplemented from ForwardIRKExport.

Definition at line 107 of file dirk_export.cpp.

Precompute as much as possible for the linear output system and export the resulting definitions.

Parameters:
[in]codeThe block to which the code will be exported.
Returns:
SUCCESSFUL_RETURN

Reimplemented from ForwardIRKExport.

Definition at line 533 of file dirk_export.cpp.

returnValue DiagonallyImplicitRKExport::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 
) [virtual]

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

Parameters:
[in]blockThe block to which the code will be exported.
[in]AhThe variable containing the internal coefficients of the RK method, multiplied with the step size.
[in]BhThe variable containing the weights of the RK method, multiplied with the step size.
[in]detThe variable that holds the determinant of the matrix in the linear system.
[in]STATESTrue if the sensitivities with respect to a state are needed, false otherwise.
[in]numberThis number defines the stage of the state with respect to which the sensitivities are computed.
Returns:
SUCCESSFUL_RETURN

Reimplemented from ForwardIRKExport.

Definition at line 236 of file dirk_export.cpp.

returnValue DiagonallyImplicitRKExport::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]

Exports the code needed to compute the sensitivities of the states, defined by the linear output system.

Parameters:
[in]blockThe block to which the code will be exported.
[in]AhThe variable containing the internal coefficients of the RK method, multiplied with the step size.
[in]BhThe variable containing the weights of the RK method, multiplied with the step size.
[in]STATESTrue if the sensitivities with respect to a state are needed, false otherwise.
[in]numberThis number defines the stage of the state with respect to which the sensitivities are computed.
Returns:
SUCCESSFUL_RETURN

Reimplemented from ForwardIRKExport.

Definition at line 421 of file dirk_export.cpp.

Initializes export of a tailored integrator.

Returns:
SUCCESSFUL_RETURN

Reimplemented from ForwardIRKExport.

Definition at line 572 of file dirk_export.cpp.

returnValue DiagonallyImplicitRKExport::solveImplicitSystem ( ExportStatementBlock block,
const ExportIndex index1,
const ExportIndex index2,
const ExportIndex index3,
const ExportIndex tmp_index,
const ExportVariable Ah,
const ExportVariable C,
const ExportVariable det,
bool  DERIVATIVES = false 
) [virtual]

Exports the code needed to solve the system of collocation equations for the nonlinear, fully implicit system.

Parameters:
[in]blockThe block to which the code will be exported.
[in]AhThe variable containing the internal coefficients of the RK method, multiplied with the step size.
[in]detThe variable that holds the determinant of the matrix in the linear system.
Returns:
SUCCESSFUL_RETURN

Reimplemented from ImplicitRungeKuttaExport.

Definition at line 190 of file dirk_export.cpp.

returnValue DiagonallyImplicitRKExport::solveInputSystem ( ExportStatementBlock block,
const ExportIndex index1,
const ExportIndex index2,
const ExportIndex index3,
const ExportIndex tmp_index,
const ExportVariable Ah 
) [virtual]

Exports the code needed to solve the system of collocation equations for the linear input system.

Parameters:
[in]blockThe block to which the code will be exported.
[in]A1A constant matrix defining the equations of the linear input system.
[in]B1A constant matrix defining the equations of the linear input system.
[in]AhThe variable containing the internal coefficients of the RK method, multiplied with the step size.
Returns:
SUCCESSFUL_RETURN

Reimplemented from ImplicitRungeKuttaExport.

Definition at line 81 of file dirk_export.cpp.

returnValue DiagonallyImplicitRKExport::solveOutputSystem ( ExportStatementBlock block,
const ExportIndex index1,
const ExportIndex index2,
const ExportIndex index3,
const ExportIndex tmp_index,
const ExportVariable Ah,
bool  DERIVATIVES = false 
) [virtual]

Exports the code needed to solve the system of collocation equations for the linear output system.

Parameters:
[in]blockThe block to which the code will be exported.
[in]AhThe variable containing the internal coefficients of the RK method, multiplied with the step size.
[in]A3A constant matrix defining the equations of the linear output system.
Returns:
SUCCESSFUL_RETURN

Reimplemented from ImplicitRungeKuttaExport.

Definition at line 394 of file dirk_export.cpp.


The documentation for this class was generated from the following files:


acado
Author(s): Milan Vukov, Rien Quirynen
autogenerated on Thu Aug 27 2015 12:01:38