Allows to export a tailored integrator for fast model predictive control. More...
#include <integrator_export.hpp>
Public Member Functions | |
virtual bool | equidistantControlGrid () const |
virtual returnValue | getCode (ExportStatementBlock &code)=0 |
virtual returnValue | getDataDeclarations (ExportStatementBlock &declarations, ExportStruct dataStruct=ACADO_ANY) const =0 |
uint | getDimOUTPUT (uint index) const |
virtual returnValue | getFunctionDeclarations (ExportStatementBlock &declarations) const =0 |
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 | setDifferentialEquation (const Expression &rhs)=0 |
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 | setNARXmodel (const uint delay, const DMatrix &parms)=0 |
virtual returnValue | setNonlinearFeedback (const DMatrix &C, const Expression &feedb) |
virtual returnValue | setup ()=0 |
virtual returnValue | setupOutput (const std::vector< Grid > outputGrids_, const std::vector< Expression > rhs)=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)=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 |
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 () |
Protected Member Functions | |
virtual returnValue | clear () |
virtual returnValue | copy (const IntegratorExport &arg) |
DMatrix | expandOutputMatrix (const DMatrix &A3) |
virtual ExportVariable | getAuxVariable () const =0 |
uint | getIntegrationInterval (double time) |
Allows to export a tailored integrator for fast model predictive control.
The class IntegratorExport allows to export a tailored integrator for fast model predictive control.
Definition at line 57 of file integrator_export.hpp.
BEGIN_NAMESPACE_ACADO IntegratorExport::IntegratorExport | ( | 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 integrator_export.cpp.
IntegratorExport::IntegratorExport | ( | const IntegratorExport & | arg | ) |
Copy constructor (deep copy).
@param[in] arg Right-hand side object.
Definition at line 66 of file integrator_export.cpp.
|
virtual |
Destructor.
Definition at line 83 of file integrator_export.cpp.
|
protectedvirtual |
Frees internal dynamic memory to yield an empty function.
\return SUCCESSFUL_RETURN
Definition at line 656 of file integrator_export.cpp.
|
protectedvirtual |
Copies all class members from given object.
@param[in] arg Right-hand side object. \return SUCCESSFUL_RETURN
Definition at line 641 of file integrator_export.cpp.
|
virtual |
Returns whether the grid is equidistant.
Definition at line 699 of file integrator_export.cpp.
@param[in] A3 . \return SUCCESSFUL_RETURN
Definition at line 628 of file integrator_export.cpp.
|
protectedpure virtual |
Returns the largest global export variable.
\return SUCCESSFUL_RETURN
Implemented in ImplicitRungeKuttaExport, ForwardLiftedIRKExport, ForwardIRKExport, SymmetricIRKExport, ExplicitRungeKuttaExport, ForwardBackwardLiftedIRKExport, DiscreteTimeExport, FeedbackLiftedIRKExport, AdjointLiftedIRKExport, SymmetricLiftedIRKExport, ThreeSweepsERKExport, and LiftedERKExport.
|
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 ExportAlgorithm.
Implemented in ImplicitRungeKuttaExport, DiscreteTimeExport, ExplicitRungeKuttaExport, RungeKuttaExport, AdjointLiftedIRKExport, FeedbackLiftedIRKExport, ForwardBackwardLiftedIRKExport, ForwardLiftedIRKExport, SymmetricLiftedIRKExport, SymmetricIRKExport, ForwardIRKExport, LiftedERKExport, ThreeSweepsERKExport, and AdjointERKExport.
|
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 ExportAlgorithm.
Implemented in ImplicitRungeKuttaExport, DiscreteTimeExport, ExplicitRungeKuttaExport, RungeKuttaExport, NARXExport, AdjointLiftedIRKExport, FeedbackLiftedIRKExport, ForwardBackwardLiftedIRKExport, ForwardLiftedIRKExport, SymmetricLiftedIRKExport, SymmetricIRKExport, LiftedERKExport, ThreeSweepsERKExport, AdjointERKExport, and ForwardIRKExport.
Definition at line 729 of file integrator_export.cpp.
|
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 ExportAlgorithm.
Implemented in ImplicitRungeKuttaExport, DiscreteTimeExport, ExplicitRungeKuttaExport, RungeKuttaExport, AdjointLiftedIRKExport, FeedbackLiftedIRKExport, ForwardBackwardLiftedIRKExport, ForwardLiftedIRKExport, SymmetricLiftedIRKExport, SymmetricIRKExport, and ForwardIRKExport.
|
virtual |
Returns the grid of the integrator.
Definition at line 672 of file integrator_export.cpp.
|
protected |
Get the index of the integration interval, corresponding a certain time.
[in] | time | The time. |
Definition at line 662 of file integrator_export.cpp.
const std::string IntegratorExport::getNameDiffsOUTPUT | ( | uint | index | ) | const |
Definition at line 743 of file integrator_export.cpp.
const std::string IntegratorExport::getNameDiffsRHS | ( | ) | const |
Definition at line 739 of file integrator_export.cpp.
|
virtual |
Definition at line 708 of file integrator_export.cpp.
const std::string IntegratorExport::getNameOUTPUT | ( | uint | index | ) | const |
Definition at line 725 of file integrator_export.cpp.
const std::string IntegratorExport::getNameOutputDiffs | ( | ) | const |
Definition at line 721 of file integrator_export.cpp.
const std::string IntegratorExport::getNameOutputRHS | ( | ) | const |
Definition at line 717 of file integrator_export.cpp.
const std::string IntegratorExport::getNameRHS | ( | ) | const |
Definition at line 704 of file integrator_export.cpp.
|
virtual |
Returns the number of integration steps along the prediction horizon.
Definition at line 679 of file integrator_export.cpp.
|
virtual |
Returns the output expressions.
Definition at line 686 of file integrator_export.cpp.
|
virtual |
Returns the output grids.
Definition at line 693 of file integrator_export.cpp.
IntegratorExport & IntegratorExport::operator= | ( | const IntegratorExport & | arg | ) |
Assignment operator (deep copy).
@param[in] arg Right-hand side object.
Definition at line 89 of file integrator_export.cpp.
|
virtual |
Exports the code needed to propagate 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 in SymmetricIRKExport, and NARXExport.
Definition at line 495 of file integrator_export.cpp.
|
virtual |
Exports the code needed to propagate the sensitivities of the states, defined by the linear input system.
@param[in] block The block to which the code will be exported. \return SUCCESSFUL_RETURN
Reimplemented in NARXExport.
Definition at line 429 of file integrator_export.cpp.
|
virtual |
Exports the code needed to propagate the sensitivities of the states, defined by the linear output system.
@param[in] block The block to which the code will be exported. \return SUCCESSFUL_RETURN
Reimplemented in NARXExport.
Definition at line 564 of file integrator_export.cpp.
|
pure virtual |
Assigns Differential Equation to be used by the integrator.
@param[in] rhs Right-hand side expression. \return SUCCESSFUL_RETURN
Implemented in ImplicitRungeKuttaExport, RungeKuttaExport, DiscreteTimeExport, AdjointLiftedIRKExport, ForwardBackwardLiftedIRKExport, ForwardLiftedIRKExport, SymmetricLiftedIRKExport, SymmetricIRKExport, ExplicitRungeKuttaExport, NARXExport, LiftedERKExport, ThreeSweepsERKExport, AdjointERKExport, and ForwardOverBackwardERKExport.
|
virtual |
Sets integration grid (this grid is expected to be non equidistant, otherwise use the other setGrid function).
@param[in] _grid integration grid \return SUCCESSFUL_RETURN
Definition at line 101 of file integrator_export.cpp.
|
virtual |
@param[in] . \return SUCCESSFUL_RETURN
Reimplemented in ExplicitRungeKuttaExport.
Definition at line 109 of file integrator_export.cpp.
|
virtual |
@param[in] . \return SUCCESSFUL_RETURN
Reimplemented in NARXExport, and ExplicitRungeKuttaExport.
Definition at line 176 of file integrator_export.cpp.
|
virtual |
@param[in] . \return SUCCESSFUL_RETURN
Reimplemented in NARXExport, and ExplicitRungeKuttaExport.
Definition at line 266 of file integrator_export.cpp.
|
virtual |
Assigns the model to be used by the integrator.
@param[in] _name_ODE Name of the function, evaluating the ODE right-hand side. @param[in] _name_diffs_ODE Name of the function, evaluating the derivatives of the ODE right-hand side. \return SUCCESSFUL_RETURN
Reimplemented in ImplicitRungeKuttaExport, and NARXExport.
Definition at line 141 of file integrator_export.cpp.
|
virtual |
Passes all the necessary model data to the integrator.
@param[in] data The model data. \return SUCCESSFUL_RETURN
Definition at line 302 of file integrator_export.cpp.
|
pure 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
Implemented in NARXExport, RungeKuttaExport, and DiscreteTimeExport.
|
virtual |
@param[in] . \return SUCCESSFUL_RETURN
Reimplemented in FeedbackLiftedIRKExport.
Definition at line 255 of file integrator_export.cpp.
|
pure virtual |
Initializes export of a tailored integrator.
\return SUCCESSFUL_RETURN
Reimplemented from ExportAlgorithm.
Implemented in DiagonallyImplicitRKExport, LiftedERKExport, ThreeSweepsERKExport, AdjointERKExport, ForwardOverBackwardERKExport, ImplicitRungeKuttaExport, ForwardIRKExport, DiscreteTimeExport, AdjointLiftedIRKExport, FeedbackLiftedIRKExport, ForwardBackwardLiftedIRKExport, ForwardLiftedIRKExport, SymmetricLiftedIRKExport, SymmetricIRKExport, RungeKuttaExport, ExplicitRungeKuttaExport, and NARXExport.
|
pure 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. |
Implemented in RungeKuttaExport, ExplicitRungeKuttaExport, ImplicitRungeKuttaExport, and DiscreteTimeExport.
|
pure 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. |
Implemented in ExplicitRungeKuttaExport, ImplicitRungeKuttaExport, and DiscreteTimeExport.
|
pure 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. |
Implemented in ExplicitRungeKuttaExport, ImplicitRungeKuttaExport, and DiscreteTimeExport.
|
virtual |
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 in ForwardLiftedIRKExport, SymmetricIRKExport, ForwardBackwardLiftedIRKExport, AdjointLiftedIRKExport, SymmetricLiftedIRKExport, and NARXExport.
Definition at line 457 of file integrator_export.cpp.
|
virtual |
Exports the code needed to update the sensitivities of the states, defined by the linear input system.
@param[in] block The block to which the code will be exported. \return SUCCESSFUL_RETURN
Reimplemented in NARXExport.
Definition at line 407 of file integrator_export.cpp.
|
virtual |
Exports the code needed to update the sensitivities of the states, defined by the linear output system.
@param[in] block The block to which the code will be exported. \return SUCCESSFUL_RETURN
Reimplemented in NARXExport.
Definition at line 542 of file integrator_export.cpp.
|
protected |
Definition at line 443 of file integrator_export.hpp.
|
protected |
Definition at line 444 of file integrator_export.hpp.
|
protected |
Definition at line 443 of file integrator_export.hpp.
|
protected |
True if the CRS format is used for the jacobian of output functions.
Definition at line 447 of file integrator_export.hpp.
|
protected |
Module to export the evaluation of the derivatives of the output functions.
Definition at line 492 of file integrator_export.hpp.
|
protected |
Module to export the evaluation of the derivatives of the ordinary differential equations.
Definition at line 458 of file integrator_export.hpp.
|
protected |
Definition at line 463 of file integrator_export.hpp.
|
protected |
This is the total number of sensitivities needed.
Definition at line 438 of file integrator_export.hpp.
|
protected |
The differential state derivatives in the model.
Definition at line 483 of file integrator_export.hpp.
|
protected |
Variable containing the error code, returned by the integrator.
Definition at line 465 of file integrator_export.hpp.
|
protected |
True if the right-hand side and their derivatives should be exported too.
Definition at line 446 of file integrator_export.hpp.
|
protected |
Function that evaluates the full right-hand side.
Definition at line 452 of file integrator_export.hpp.
|
protected |
Evaluation grid along the prediction horizon.
Definition at line 449 of file integrator_export.hpp.
|
protected |
This is the dimension of the input to the integrator.
Definition at line 439 of file integrator_export.hpp.
|
protected |
Function that integrates the exported ODE.
Definition at line 456 of file integrator_export.hpp.
|
protected |
Definition at line 460 of file integrator_export.hpp.
|
protected |
Definition at line 443 of file integrator_export.hpp.
|
protected |
Definition at line 444 of file integrator_export.hpp.
|
protected |
Definition at line 435 of file integrator_export.hpp.
|
protected |
A separate dimension for each output.
Definition at line 494 of file integrator_export.hpp.
|
protected |
The number of integration steps per shooting interval.
Definition at line 450 of file integrator_export.hpp.
|
protected |
Definition at line 432 of file integrator_export.hpp.
|
protected |
Definition at line 433 of file integrator_export.hpp.
|
protected |
Definition at line 434 of file integrator_export.hpp.
|
protected |
Definition at line 436 of file integrator_export.hpp.
|
protected |
The "online" data values in the model.
Definition at line 486 of file integrator_export.hpp.
|
protected |
A separate dependency matrix for each output.
Definition at line 490 of file integrator_export.hpp.
|
protected |
A separate expression for each output.
Definition at line 489 of file integrator_export.hpp.
|
protected |
A separate grid for each output.
Definition at line 488 of file integrator_export.hpp.
|
protected |
Module to export output functions.
Definition at line 491 of file integrator_export.hpp.
|
protected |
Variable containing the number of the current integration step.
Definition at line 466 of file integrator_export.hpp.
|
protected |
Module to export ODE.
Definition at line 457 of file integrator_export.hpp.
|
protected |
Definition at line 462 of file integrator_export.hpp.
|
protected |
Definition at line 453 of file integrator_export.hpp.
|
protected |
Definition at line 454 of file integrator_export.hpp.
|
protected |
Definition at line 473 of file integrator_export.hpp.
|
protected |
Variable containing the derivatives wrt the previous values.
Definition at line 476 of file integrator_export.hpp.
|
protected |
Definition at line 479 of file integrator_export.hpp.
|
protected |
Definition at line 472 of file integrator_export.hpp.
|
protected |
Variable containing the sensitivities from the previous integration step.
Definition at line 475 of file integrator_export.hpp.
|
protected |
Definition at line 480 of file integrator_export.hpp.
|
protected |
Variable containing intermediate results of evaluations of the derivatives of the differential equations (ordinary and algebraic).
Definition at line 477 of file integrator_export.hpp.
|
protected |
Variable containing the inputs or the results of the integrator.
Definition at line 470 of file integrator_export.hpp.
|
protected |
Variable containing the number of the current shooting interval.
Definition at line 467 of file integrator_export.hpp.
|
protected |
Variable containing the integration time.
Definition at line 468 of file integrator_export.hpp.
|
protected |
Variable containing the current integrator state.
Definition at line 469 of file integrator_export.hpp.
|
protected |
Definition at line 441 of file integrator_export.hpp.
|
protected |
The control inputs in the model.
Definition at line 485 of file integrator_export.hpp.
|
protected |
The differential states in the model.
Definition at line 482 of file integrator_export.hpp.
|
protected |
The algebraic states in the model.
Definition at line 484 of file integrator_export.hpp.