Allows to export a tailored implicit Runge-Kutta integrator for fast model predictive control. More...
#include <irk_export.hpp>
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.
Definition at line 55 of file irk_export.hpp.
BEGIN_NAMESPACE_ACADO ImplicitRungeKuttaExport::ImplicitRungeKuttaExport | ( | UserInteraction * | _userInteraction = 0 , |
const std::string & | _commonHeaderName = "" |
||
) |
Default constructor.
[in] | _userInteraction | Pointer to corresponding user interface. |
[in] | _commonHeaderName | Name of common header file to be included. |
Definition at line 44 of file irk_export.cpp.
Copy constructor (deep copy).
[in] | arg | Right-hand side object. |
Definition at line 67 of file irk_export.cpp.
ImplicitRungeKuttaExport::~ImplicitRungeKuttaExport | ( | ) | [virtual] |
Destructor.
Definition at line 91 of file irk_export.cpp.
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.
[in] | cVec | The vector with all the elements of the vector cc from the Butcher table, of which combinations are computed in a recursive way. |
[in] | index | An index of the vector cVec which denotes the relevant part for this invocation. |
[in] | numEls | The number of elements in the combination. |
Definition at line 900 of file irk_export.cpp.
returnValue ImplicitRungeKuttaExport::copy | ( | const ImplicitRungeKuttaExport & | arg | ) | [protected, virtual] |
Copies all class members from given object.
[in] | arg | Right-hand side object. |
Definition at line 1413 of file irk_export.cpp.
DVector ImplicitRungeKuttaExport::divideMeasurements | ( | uint | index | ) | [protected] |
Divide the total number of measurements over the different integration steps.
[in] | index | The index of the continuous output for which the division of measurements is returned. |
Definition at line 1041 of file irk_export.cpp.
DVector ImplicitRungeKuttaExport::evaluateDerivedPolynomial | ( | double | time | ) | [protected] |
Returns the coefficients of the derived polynomial, representing the derivative of the continuous output with respect to time.
[in] | time | The point in the interval (0,1] for which the coefficients are returned. |
Definition at line 1002 of file irk_export.cpp.
returnValue ImplicitRungeKuttaExport::evaluateDerivedPolynomial | ( | ExportStatementBlock & | block, |
const ExportVariable & | variable, | ||
const ExportVariable & | grid | ||
) | [protected] |
Exports the evaluation of the coefficients of the derived polynomial, representing the derivative of the continuous output with respect to time.
[in] | block | The block to which the code will be exported. |
[in] | variable | The variable containing the coefficients of the polynomial. |
[in] | grid | The variable containing the grid point for the specific output. |
Definition at line 1021 of file irk_export.cpp.
DMatrix ImplicitRungeKuttaExport::evaluateDerivedPolynomial | ( | uint | index | ) | [protected] |
Returns the coefficients of the derived polynomial for the complete grid of the output, corresponding a certain index.
[in] | index | The index of the continuous output for which the coefficients are returned. |
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.
[in] | block | The block to which the code will be exported. |
[in] | index1 | The loop index of the outer loop. |
[in] | index2 | The loop index of the inner loop. |
[in] | tmp_index | A temporary index to be used. |
[in] | Ah | The matrix A of the IRK method, multiplied by the step size h. |
[in] | evaluateB | True if the right-hand side of the linear system should also be evaluated, false otherwise. |
Reimplemented in DiagonallyImplicitRKExport.
Definition at line 724 of file irk_export.cpp.
DVector ImplicitRungeKuttaExport::evaluatePolynomial | ( | double | time | ) | [protected] |
Returns the coefficients of the polynomial, representing the continuous output of the integrator.
[in] | time | The point in the interval (0,1] for which the coefficients are returned. |
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.
[in] | block | The block to which the code will be exported. |
[in] | variable | The variable containing the coefficients of the polynomial. |
[in] | grid | The variable containing the grid point for the specific output. |
[in] | h | The integration step size. |
Definition at line 958 of file irk_export.cpp.
DMatrix ImplicitRungeKuttaExport::evaluatePolynomial | ( | uint | index | ) | [protected] |
Returns the coefficients of the polynomial for the complete grid of the output, corresponding a certain index.
[in] | index | The index of the continuous output for which the coefficients are returned. |
Definition at line 922 of file irk_export.cpp.
returnValue ImplicitRungeKuttaExport::evaluateRhsImplicitSystem | ( | ExportStatementBlock * | block, |
const ExportIndex & | stage | ||
) | [protected, virtual] |
Exports the evaluation of the right-hand side of the linear system at a specific stage.
[in] | block | The block to which the code will be exported. |
[in] | index | The loop index, defining the stage. |
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.
[in] | block | The block to which the code will be exported. |
[in] | Ah | The matrix A of the IRK method, multiplied by the step size h. |
[in] | index | The loop index, defining the stage. |
Reimplemented in DiagonallyImplicitRKExport.
Definition at line 657 of file irk_export.cpp.
returnValue ImplicitRungeKuttaExport::evaluateStatesOutputSystem | ( | ExportStatementBlock * | block, |
const ExportVariable & | Ah, | ||
const ExportIndex & | stage | ||
) | [protected] |
Exports the evaluation of the states at a specific stage.
[in] | block | The block to which the code will be exported. |
[in] | Ah | The matrix A of the IRK method, multiplied by the step size h. |
[in] | index | The loop index, defining the stage. |
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.
[in] | jacobian | given constant Jacobian matrix |
[in] | mass | given constant mass matrix |
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.
[in] | block | The block to which the code will be exported. |
[in] | tmp_meas | The number of measurements in the current integration step (in case of an online grid). |
[in] | rk_tPrev | The time point, defining the beginning of the current integration step (in case of an online grid). |
[in] | time_tmp | A variable used for time transformations (in case of an online grid). |
Definition at line 768 of file irk_export.cpp.
ExportVariable ImplicitRungeKuttaExport::getAuxVariable | ( | ) | const [protected, virtual] |
Returns the largest global export variable.
Implements IntegratorExport.
Reimplemented in ForwardIRKExport.
Definition at line 171 of file irk_export.cpp.
returnValue ImplicitRungeKuttaExport::getCode | ( | ExportStatementBlock & | code | ) | [virtual] |
Exports source code of the auto-generated integrator into the given directory.
[in] | code | Code block containing the auto-generated integrator. |
Implements RungeKuttaExport.
Reimplemented in ForwardIRKExport.
Definition at line 256 of file irk_export.cpp.
returnValue ImplicitRungeKuttaExport::getCRSIndex | ( | uint | output, |
ExportIndex | row, | ||
ExportIndex | col | ||
) | [protected] |
Returns the index corresponding Compressed Row Storage (CRS) for the dependency matrix of a specific output function.
[in] | output | The number of the output function. |
[in] | row | The number of the row, corresponding the element of interest. |
[in] | col | The number of the column, corresponding the element of interest. |
Reimplemented in ForwardIRKExport.
returnValue ImplicitRungeKuttaExport::getDataDeclarations | ( | ExportStatementBlock & | declarations, |
ExportStruct | dataStruct = ACADO_ANY |
||
) | const [virtual] |
Adds all data declarations of the auto-generated integrator to given list of declarations.
[in] | declarations | List of declarations. |
Implements RungeKuttaExport.
Reimplemented in ForwardIRKExport.
Definition at line 200 of file irk_export.cpp.
returnValue ImplicitRungeKuttaExport::getFunctionDeclarations | ( | ExportStatementBlock & | declarations | ) | const [virtual] |
Adds all function (forward) declarations of the auto-generated integrator to given list of declarations.
[in] | declarations | List of declarations. |
Implements RungeKuttaExport.
Reimplemented in ForwardIRKExport.
Definition at line 244 of file irk_export.cpp.
uint ImplicitRungeKuttaExport::getNumIts | ( | ) | const [protected] |
Returns the performed number of Newton iterations.
Definition at line 1473 of file irk_export.cpp.
uint ImplicitRungeKuttaExport::getNumItsInit | ( | ) | const [protected] |
Returns the performed number of Newton iterations for the initialization of the first step.
Definition at line 1479 of file irk_export.cpp.
returnValue ImplicitRungeKuttaExport::initializeCoefficients | ( | ) | [protected] |
Initializes the matrix coeffs, containing coefficients of polynomials that are used to evaluate the continuous output (see evaluatePolynomial).
Definition at line 860 of file irk_export.cpp.
returnValue ImplicitRungeKuttaExport::initializeDDMatrix | ( | ) | [protected] |
Initializes the matrix DD, which is used to extrapolate the variables of the IRK method to the next step.
Definition at line 841 of file irk_export.cpp.
ImplicitRungeKuttaExport & ImplicitRungeKuttaExport::operator= | ( | const ImplicitRungeKuttaExport & | arg | ) |
Assignment operator (deep copy).
[in] | arg | Right-hand side object. |
Definition at line 101 of file irk_export.cpp.
returnValue ImplicitRungeKuttaExport::prepareInputSystem | ( | ExportStatementBlock & | code | ) | [protected, virtual] |
Precompute as much as possible for the linear input system and export the resulting definitions.
[in] | code | The block to which the code will be exported. |
Reimplemented in ForwardIRKExport, and DiagonallyImplicitRKExport.
Definition at line 501 of file irk_export.cpp.
returnValue ImplicitRungeKuttaExport::prepareOutputEvaluation | ( | ExportStatementBlock & | code | ) | [protected] |
Prepares the structures to evaluate the continuous output and exports the resulting definitions.
[in] | code | The block to which the code will be exported. |
Definition at line 1376 of file irk_export.cpp.
returnValue ImplicitRungeKuttaExport::prepareOutputSystem | ( | ExportStatementBlock & | code | ) | [protected, virtual] |
Precompute as much as possible for the linear output system and export the resulting definitions.
[in] | code | The block to which the code will be exported. |
Reimplemented in DiagonallyImplicitRKExport, and ForwardIRKExport.
Definition at line 515 of file irk_export.cpp.
returnValue ImplicitRungeKuttaExport::setDifferentialEquation | ( | const Expression & | rhs | ) | [virtual] |
Assigns Differential Equation to be used by the integrator.
[in] | rhs | Right-hand side expression. |
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.
[in] | _rhs | Name of the function, evaluating the right-hand side. |
[in] | _diffs_rhs | Name of the function, evaluating the derivatives of the right-hand side. |
Reimplemented from IntegratorExport.
Definition at line 159 of file irk_export.cpp.
returnValue ImplicitRungeKuttaExport::setup | ( | ) | [virtual] |
Initializes export of a tailored integrator.
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.
outputGrids_ | The vector containing a grid for each output function. |
rhs | The expressions corresponding the output functions. |
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.
outputGrids_ | The vector containing a grid for each output function. |
_outputNames | The names of the output functions. |
_diffs_outputNames | The names of the functions, evaluating the derivatives of the outputs. |
_dims_output | The dimensions of the output functions. |
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.
outputGrids_ | The vector containing a grid for each output function. |
_outputNames | The names of the output functions. |
_diffs_outputNames | The names of the functions, evaluating the derivatives of the outputs. |
_dims_output | The dimensions of the output functions. |
_outputDependencies | A separate dependency matrix for each output. |
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.
[in] | block | The block to which the code will be exported. |
[in] | Ah | The variable containing the internal coefficients of the RK method, multiplied with the step size. |
[in] | det | The variable that holds the determinant of the matrix in the linear system. |
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.
[in] | block | The block to which the code will be exported. |
[in] | A1 | A constant matrix defining the equations of the linear input system. |
[in] | B1 | A constant matrix defining the equations of the linear input system. |
[in] | Ah | The variable containing the internal coefficients of the RK method, multiplied with the step size. |
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.
[in] | block | The block to which the code will be exported. |
[in] | Ah | The variable containing the internal coefficients of the RK method, multiplied with the step size. |
[in] | A3 | A constant matrix defining the equations of the linear output system. |
Reimplemented in DiagonallyImplicitRKExport.
Definition at line 633 of file irk_export.cpp.
DMatrix ImplicitRungeKuttaExport::coeffs [protected] |
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.
bool ImplicitRungeKuttaExport::CONTINUOUS_OUTPUT [protected] |
This boolean is true when continuous output needs to be provided.
Definition at line 514 of file irk_export.hpp.
DMatrix ImplicitRungeKuttaExport::DD [protected] |
This matrix is used for the initialization of the variables for the next integration step.
Definition at line 526 of file irk_export.hpp.
ExportVariable ImplicitRungeKuttaExport::debug_mat [protected] |
Definition at line 566 of file irk_export.hpp.
std::vector<ExportVariable> ImplicitRungeKuttaExport::gridVariables [protected] |
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.
uint ImplicitRungeKuttaExport::NDX2 [protected] |
Definition at line 519 of file irk_export.hpp.
DVector ImplicitRungeKuttaExport::numDX_output [protected] |
Definition at line 529 of file irk_export.hpp.
uint ImplicitRungeKuttaExport::numIts [protected] |
This is the performed number of Newton iterations.
Definition at line 516 of file irk_export.hpp.
uint ImplicitRungeKuttaExport::numItsInit [protected] |
This is the performed number of Newton iterations for the initialization of the first step.
Definition at line 517 of file irk_export.hpp.
std::vector<ExportIndex> ImplicitRungeKuttaExport::numMeas [protected] |
Indices containing the number of measurements that are already computed.
Definition at line 550 of file irk_export.hpp.
std::vector<ExportVariable> ImplicitRungeKuttaExport::numMeasVariables [protected] |
Variables containing the number of measurements per integration interval.
Definition at line 549 of file irk_export.hpp.
DVector ImplicitRungeKuttaExport::numVARS_output [protected] |
Definition at line 531 of file irk_export.hpp.
DVector ImplicitRungeKuttaExport::numXA_output [protected] |
Definition at line 530 of file irk_export.hpp.
uint ImplicitRungeKuttaExport::NVARS2 [protected] |
Definition at line 520 of file irk_export.hpp.
uint ImplicitRungeKuttaExport::NVARS3 [protected] |
Definition at line 522 of file irk_export.hpp.
std::vector<ExportVariable> ImplicitRungeKuttaExport::polynDerVariables [protected] |
Variables containing the coefficients for the derived polynomial.
Definition at line 548 of file irk_export.hpp.
ExportVariable ImplicitRungeKuttaExport::polynEvalVar [protected] |
Local variable that is used for the evaluations of the continuous output.
Definition at line 539 of file irk_export.hpp.
std::vector<ExportVariable> ImplicitRungeKuttaExport::polynVariables [protected] |
Variables containing the coefficients for the polynomial.
Definition at line 547 of file irk_export.hpp.
bool ImplicitRungeKuttaExport::REUSE [protected] |
This boolean is true when the IFTR method is used instead of the IFT method.
Definition at line 513 of file irk_export.hpp.
ExportVariable ImplicitRungeKuttaExport::rk_A [protected] |
Variable containing the matrix of the linear system.
Definition at line 555 of file irk_export.hpp.
ExportVariable ImplicitRungeKuttaExport::rk_auxSolver [protected] |
Variable containing auxiliary values for the exported linear solver.
Definition at line 557 of file irk_export.hpp.
ExportVariable ImplicitRungeKuttaExport::rk_b [protected] |
Variable containing the right-hand side of the linear system.
Definition at line 556 of file irk_export.hpp.
ExportVariable ImplicitRungeKuttaExport::rk_diffK [protected] |
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.
ExportVariable ImplicitRungeKuttaExport::rk_dk1 [protected] |
Definition at line 553 of file irk_export.hpp.
ExportVariable ImplicitRungeKuttaExport::rk_dk3 [protected] |
Definition at line 562 of file irk_export.hpp.
ExportVariable ImplicitRungeKuttaExport::rk_mat1 [protected] |
Definition at line 552 of file irk_export.hpp.
ExportVariable ImplicitRungeKuttaExport::rk_mat3 [protected] |
Definition at line 561 of file irk_export.hpp.
ExportVariable ImplicitRungeKuttaExport::rk_out [protected] |
Variable that is used for the evaluations of the continuous output.
Definition at line 538 of file irk_export.hpp.
ExportVariable ImplicitRungeKuttaExport::rk_outH [protected] |
Variable that is used for the evaluations of the continuous output.
Definition at line 537 of file irk_export.hpp.
std::vector<ExportVariable> ImplicitRungeKuttaExport::rk_outputs [protected] |
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.
ExportVariable ImplicitRungeKuttaExport::rk_rhsTemp [protected] |
Variable containing intermediate results of evaluations of the right-hand side expression.
Definition at line 558 of file irk_export.hpp.
ExportLinearSolver* ImplicitRungeKuttaExport::solver [protected] |
This is the exported linear solver that is used by the implicit Runge-Kutta method.
Definition at line 524 of file irk_export.hpp.
ExportVariable ImplicitRungeKuttaExport::stepsH [protected] |
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.