Public Member Functions | Protected Member Functions | Protected Attributes

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

#include <irk_export.hpp>

Inheritance diagram for ImplicitRungeKuttaExport:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual returnValue getCode (ExportStatementBlock &code)
virtual returnValue getDataDeclarations (ExportStatementBlock &declarations, ExportStruct dataStruct=ACADO_ANY) const
virtual returnValue getFunctionDeclarations (ExportStatementBlock &declarations) const
 ImplicitRungeKuttaExport (UserInteraction *_userInteraction=0, const std::string &_commonHeaderName="")
 ImplicitRungeKuttaExport (const ImplicitRungeKuttaExport &arg)
ImplicitRungeKuttaExportoperator= (const ImplicitRungeKuttaExport &arg)
virtual returnValue setDifferentialEquation (const Expression &rhs)
returnValue setModel (const std::string &_rhs, const std::string &_diffs_rhs)
virtual returnValue setup ()
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 ()

Protected Member Functions

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 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)
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)
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)
ExportVariable getAuxVariable () const
returnValue getCRSIndex (uint output, ExportIndex row, ExportIndex col)
uint getNumIts () const
uint getNumItsInit () const
returnValue initializeCoefficients ()
returnValue initializeDDMatrix ()
virtual returnValue prepareInputSystem (ExportStatementBlock &code)
returnValue prepareOutputEvaluation (ExportStatementBlock &code)
virtual returnValue prepareOutputSystem (ExportStatementBlock &code)
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)

Protected Attributes

DMatrix coeffs
bool CONTINUOUS_OUTPUT
DMatrix DD
ExportVariable debug_mat
std::vector< ExportVariablegridVariables
ExportAcadoFunction lin_output
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
ExportLinearSolversolver
ExportVariable stepsH
std::vector< uinttotalMeas

Detailed Description

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

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

Author:
Rien Quirynen

Definition at line 55 of file irk_export.hpp.


Constructor & Destructor Documentation

BEGIN_NAMESPACE_ACADO ImplicitRungeKuttaExport::ImplicitRungeKuttaExport ( 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 44 of file irk_export.cpp.

Copy constructor (deep copy).

Parameters:
[in]argRight-hand side object.

Definition at line 67 of file irk_export.cpp.

Destructor.

Definition at line 91 of file irk_export.cpp.


Member Function Documentation

DVector ImplicitRungeKuttaExport::computeCombinations ( const DVector cVec,
uint  index,
uint  numEls 
) [protected]

Recursive function that helps with the computation of the coefficients of polynomials that are used to evaluate the continuous output (see initializeCoefficients), by computing the correct combinations of elements of the vector cc from the Butcher table.

Parameters:
[in]cVecThe vector with all the elements of the vector cc from the Butcher table, of which combinations are computed in a recursive way.
[in]indexAn index of the vector cVec which denotes the relevant part for this invocation.
[in]numElsThe number of elements in the combination.
Returns:
SUCCESSFUL_RETURN

Definition at line 900 of file irk_export.cpp.

Copies all class members from given object.

Parameters:
[in]argRight-hand side object.
Returns:
SUCCESSFUL_RETURN

Definition at line 1413 of file irk_export.cpp.

Divide the total number of measurements over the different integration steps.

Parameters:
[in]indexThe index of the continuous output for which the division of measurements is returned.
Returns:
The division of measurements over the integration steps, corresponding the given continuous output.

Definition at line 1041 of file irk_export.cpp.

Returns the coefficients of the derived polynomial, representing the derivative of the continuous output with respect to time.

Parameters:
[in]timeThe point in the interval (0,1] for which the coefficients are returned.
Returns:
Coefficients of the polynomial, corresponding the given grid point

Definition at line 1002 of file irk_export.cpp.

Exports the evaluation of the coefficients of the derived polynomial, representing the derivative of the continuous output with respect to time.

Parameters:
[in]blockThe block to which the code will be exported.
[in]variableThe variable containing the coefficients of the polynomial.
[in]gridThe variable containing the grid point for the specific output.
Returns:
SUCCESSFUL_RETURN

Definition at line 1021 of file irk_export.cpp.

Returns the coefficients of the derived polynomial for the complete grid of the output, corresponding a certain index.

Parameters:
[in]indexThe index of the continuous output for which the coefficients are returned.
Returns:
Coefficients of the derived polynomial, corresponding the given continuous output

Definition at line 982 of file irk_export.cpp.

returnValue ImplicitRungeKuttaExport::evaluateMatrix ( ExportStatementBlock block,
const ExportIndex index1,
const ExportIndex index2,
const ExportIndex tmp_index,
const ExportVariable Ah,
const ExportVariable C,
bool  evaluateB,
bool  DERIVATIVES 
) [protected, 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 in DiagonallyImplicitRKExport.

Definition at line 724 of file irk_export.cpp.

Returns the coefficients of the polynomial, representing the continuous output of the integrator.

Parameters:
[in]timeThe point in the interval (0,1] for which the coefficients are returned.
Returns:
Coefficients of the polynomial, corresponding the given grid point

Definition at line 942 of file irk_export.cpp.

returnValue ImplicitRungeKuttaExport::evaluatePolynomial ( ExportStatementBlock block,
const ExportVariable variable,
const ExportVariable grid,
const std::string &  h 
) [protected]

Exports the evaluation of the coefficients of the polynomial, representing the continuous output of the integrator.

Parameters:
[in]blockThe block to which the code will be exported.
[in]variableThe variable containing the coefficients of the polynomial.
[in]gridThe variable containing the grid point for the specific output.
[in]hThe integration step size.
Returns:
SUCCESSFUL_RETURN

Definition at line 958 of file irk_export.cpp.

Returns the coefficients of the polynomial for the complete grid of the output, corresponding a certain index.

Parameters:
[in]indexThe index of the continuous output for which the coefficients are returned.
Returns:
Coefficients of the polynomial, corresponding the given continuous output

Definition at line 922 of file irk_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 in DiagonallyImplicitRKExport.

Definition at line 705 of file irk_export.cpp.

returnValue ImplicitRungeKuttaExport::evaluateStatesImplicitSystem ( ExportStatementBlock block,
const ExportVariable Ah,
const ExportVariable C,
const ExportIndex stage,
const ExportIndex i,
const ExportIndex j 
) [protected, 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 in DiagonallyImplicitRKExport.

Definition at line 657 of file irk_export.cpp.

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

Definition at line 682 of file irk_export.cpp.

DMatrix ImplicitRungeKuttaExport::formMatrix ( const DMatrix mass,
const DMatrix jacobian 
) [protected, 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 in DiagonallyImplicitRKExport.

Definition at line 529 of file irk_export.cpp.

returnValue ImplicitRungeKuttaExport::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 
) [protected]

Exports the necessary code for the computation of the continuous output.

Parameters:
[in]blockThe block to which the code will be exported.
[in]tmp_measThe number of measurements in the current integration step (in case of an online grid).
[in]rk_tPrevThe time point, defining the beginning of the current integration step (in case of an online grid).
[in]time_tmpA variable used for time transformations (in case of an online grid).
Returns:
SUCCESSFUL_RETURN

Definition at line 768 of file irk_export.cpp.

Returns the largest global export variable.

Returns:
SUCCESSFUL_RETURN

Implements IntegratorExport.

Reimplemented in ForwardIRKExport.

Definition at line 171 of file irk_export.cpp.

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

Parameters:
[in]codeCode block containing the auto-generated integrator.
Returns:
SUCCESSFUL_RETURN

Implements RungeKuttaExport.

Reimplemented in ForwardIRKExport.

Definition at line 256 of file irk_export.cpp.

Returns the index corresponding Compressed Row Storage (CRS) for the dependency matrix of a specific output function.

Parameters:
[in]outputThe number of the output function.
[in]rowThe number of the row, corresponding the element of interest.
[in]colThe number of the column, corresponding the element of interest.
Returns:
The CRS index.

Reimplemented in ForwardIRKExport.

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

Parameters:
[in]declarationsList of declarations.
Returns:
SUCCESSFUL_RETURN

Implements RungeKuttaExport.

Reimplemented in ForwardIRKExport.

Definition at line 200 of file irk_export.cpp.

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

Parameters:
[in]declarationsList of declarations.
Returns:
SUCCESSFUL_RETURN

Implements RungeKuttaExport.

Reimplemented in ForwardIRKExport.

Definition at line 244 of file irk_export.cpp.

Returns the performed number of Newton iterations.

Returns:
The performed number of Newton iterations.

Definition at line 1473 of file irk_export.cpp.

Returns the performed number of Newton iterations for the initialization of the first step.

Returns:
The performed number of Newton iterations for the initialization of the first step.

Definition at line 1479 of file irk_export.cpp.

Initializes the matrix coeffs, containing coefficients of polynomials that are used to evaluate the continuous output (see evaluatePolynomial).

Returns:
SUCCESSFUL_RETURN

Definition at line 860 of file irk_export.cpp.

Initializes the matrix DD, which is used to extrapolate the variables of the IRK method to the next step.

Returns:
SUCCESSFUL_RETURN

Definition at line 841 of file irk_export.cpp.

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

Assignment operator (deep copy).

Parameters:
[in]argRight-hand side object.

Definition at line 101 of file irk_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 in ForwardIRKExport, and DiagonallyImplicitRKExport.

Definition at line 501 of file irk_export.cpp.

Prepares the structures to evaluate the continuous output and exports the resulting definitions.

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

Definition at line 1376 of file irk_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 in DiagonallyImplicitRKExport, and ForwardIRKExport.

Definition at line 515 of file irk_export.cpp.

Assigns Differential Equation to be used by the integrator.

Parameters:
[in]rhsRight-hand side expression.
Returns:
SUCCESSFUL_RETURN

Implements RungeKuttaExport.

Definition at line 112 of file irk_export.cpp.

returnValue ImplicitRungeKuttaExport::setModel ( const std::string &  _rhs,
const std::string &  _diffs_rhs 
) [virtual]

Assigns the model to be used by the integrator.

Parameters:
[in]_rhsName of the function, evaluating the right-hand side.
[in]_diffs_rhsName of the function, evaluating the derivatives of the right-hand side.
Returns:
SUCCESSFUL_RETURN

Reimplemented from IntegratorExport.

Definition at line 159 of file irk_export.cpp.

Initializes export of a tailored integrator.

Returns:
SUCCESSFUL_RETURN

Implements RungeKuttaExport.

Reimplemented in DiagonallyImplicitRKExport, and ForwardIRKExport.

Definition at line 1055 of file irk_export.cpp.

returnValue ImplicitRungeKuttaExport::setupOutput ( const std::vector< Grid outputGrids_,
const std::vector< Expression rhs 
) [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 RungeKuttaExport.

Definition at line 1185 of file irk_export.cpp.

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

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

Parameters:
outputGrids_The vector containing a grid for each output function.
_outputNamesThe names of the output functions.
_diffs_outputNamesThe names of the functions, evaluating the derivatives of the outputs.
_dims_outputThe dimensions of the output functions.

Returns:
SUCCESSFUL_RETURN

Implements IntegratorExport.

Definition at line 1279 of file irk_export.cpp.

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

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

Parameters:
outputGrids_The vector containing a grid for each output function.
_outputNamesThe names of the output functions.
_diffs_outputNamesThe names of the functions, evaluating the derivatives of the outputs.
_dims_outputThe dimensions of the output functions.
_outputDependenciesA separate dependency matrix for each output.

Returns:
SUCCESSFUL_RETURN

Implements IntegratorExport.

Definition at line 1359 of file irk_export.cpp.

returnValue ImplicitRungeKuttaExport::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 
) [protected, 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 in DiagonallyImplicitRKExport.

Definition at line 583 of file irk_export.cpp.

returnValue ImplicitRungeKuttaExport::solveInputSystem ( ExportStatementBlock block,
const ExportIndex index1,
const ExportIndex index2,
const ExportIndex index3,
const ExportIndex tmp_index,
const ExportVariable Ah 
) [protected, 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 in DiagonallyImplicitRKExport.

Definition at line 556 of file irk_export.cpp.

returnValue ImplicitRungeKuttaExport::solveOutputSystem ( ExportStatementBlock block,
const ExportIndex index1,
const ExportIndex index2,
const ExportIndex index3,
const ExportIndex tmp_index,
const ExportVariable Ah,
bool  DERIVATIVES = false 
) [protected, 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 in DiagonallyImplicitRKExport.

Definition at line 633 of file irk_export.cpp.


Member Data Documentation

This matrix contains coefficients of polynomials that are used to evaluate the continuous output (see evaluatePolynomial).

Definition at line 527 of file irk_export.hpp.

This boolean is true when continuous output needs to be provided.

Definition at line 514 of file irk_export.hpp.

This matrix is used for the initialization of the variables for the next integration step.

Definition at line 526 of file irk_export.hpp.

Definition at line 566 of file irk_export.hpp.

This vector contains an ExportVariable for the grid of each continuous output.

Definition at line 543 of file irk_export.hpp.

Definition at line 560 of file irk_export.hpp.

Definition at line 519 of file irk_export.hpp.

Definition at line 529 of file irk_export.hpp.

This is the performed number of Newton iterations.

Definition at line 516 of file irk_export.hpp.

This is the performed number of Newton iterations for the initialization of the first step.

Definition at line 517 of file irk_export.hpp.

Indices containing the number of measurements that are already computed.

Definition at line 550 of file irk_export.hpp.

Variables containing the number of measurements per integration interval.

Definition at line 549 of file irk_export.hpp.

Definition at line 531 of file irk_export.hpp.

Definition at line 530 of file irk_export.hpp.

Definition at line 520 of file irk_export.hpp.

Definition at line 522 of file irk_export.hpp.

Variables containing the coefficients for the derived polynomial.

Definition at line 548 of file irk_export.hpp.

Local variable that is used for the evaluations of the continuous output.

Definition at line 539 of file irk_export.hpp.

Variables containing the coefficients for the polynomial.

Definition at line 547 of file irk_export.hpp.

This boolean is true when the IFTR method is used instead of the IFT method.

Definition at line 513 of file irk_export.hpp.

Variable containing the matrix of the linear system.

Definition at line 555 of file irk_export.hpp.

Variable containing auxiliary values for the exported linear solver.

Definition at line 557 of file irk_export.hpp.

Variable containing the right-hand side of the linear system.

Definition at line 556 of file irk_export.hpp.

Definition at line 565 of file irk_export.hpp.

Variable containing intermediate results of evaluations of the derivatives of an output function.

Definition at line 536 of file irk_export.hpp.

Definition at line 563 of file irk_export.hpp.

Definition at line 553 of file irk_export.hpp.

Definition at line 562 of file irk_export.hpp.

Definition at line 552 of file irk_export.hpp.

Definition at line 561 of file irk_export.hpp.

Variable that is used for the evaluations of the continuous output.

Definition at line 538 of file irk_export.hpp.

Variable that is used for the evaluations of the continuous output.

Definition at line 537 of file irk_export.hpp.

Variables containing the evaluations of the continuous output from the integrator.

Definition at line 546 of file irk_export.hpp.

Variable containing intermediate results of evaluations of the right-hand side expression of an output function.

Definition at line 535 of file irk_export.hpp.

Variable containing intermediate results of evaluations of the right-hand side expression.

Definition at line 558 of file irk_export.hpp.

This is the exported linear solver that is used by the implicit Runge-Kutta method.

Definition at line 524 of file irk_export.hpp.

Variable defining the different integration step sizes in case of a non equidistant grid.

Definition at line 541 of file irk_export.hpp.

std::vector<uint> ImplicitRungeKuttaExport::totalMeas [protected]

This vector contains the total number of measurements per output (per shooting or integration interval, depending on grid type).

Definition at line 544 of file irk_export.hpp.


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:39