Public Member Functions | Protected Member Functions | Protected Attributes

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

#include <integrator_export.hpp>

Inheritance diagram for IntegratorExport:
Inheritance graph
[legend]

List of all members.

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)
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 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 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 ()

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)

Protected Attributes

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

Detailed Description

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.

Author:
Hans Joachim Ferreau, Boris Houska, Rien Quirynen

Definition at line 57 of file integrator_export.hpp.


Constructor & Destructor Documentation

BEGIN_NAMESPACE_ACADO IntegratorExport::IntegratorExport ( 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 45 of file integrator_export.cpp.

Copy constructor (deep copy).

Parameters:
[in]argRight-hand side object.

Definition at line 66 of file integrator_export.cpp.

Destructor.

Definition at line 83 of file integrator_export.cpp.


Member Function Documentation

returnValue IntegratorExport::clear ( ) [protected, virtual]

Frees internal dynamic memory to yield an empty function.

Returns:
SUCCESSFUL_RETURN

Definition at line 618 of file integrator_export.cpp.

returnValue IntegratorExport::copy ( const IntegratorExport arg) [protected, virtual]

Copies all class members from given object.

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

Definition at line 603 of file integrator_export.cpp.

bool IntegratorExport::equidistantControlGrid ( ) const [virtual]

Returns whether the grid is equidistant.

Returns:
true iff the grid is equidistant, false otherwise.

Definition at line 661 of file integrator_export.cpp.

Parameters:
[in]A3.
Returns:
SUCCESSFUL_RETURN

Definition at line 590 of file integrator_export.cpp.

virtual ExportVariable IntegratorExport::getAuxVariable ( ) const [protected, pure virtual]

Returns the largest global export variable.

Returns:
SUCCESSFUL_RETURN

Implemented in ImplicitRungeKuttaExport, ForwardIRKExport, ExplicitRungeKuttaExport, DiscreteTimeExport, and ThreeSweepsERKExport.

virtual returnValue IntegratorExport::getCode ( ExportStatementBlock code) [pure virtual]

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 ExportAlgorithm.

Implemented in ImplicitRungeKuttaExport, DiscreteTimeExport, ExplicitRungeKuttaExport, RungeKuttaExport, ForwardIRKExport, ThreeSweepsERKExport, and AdjointERKExport.

virtual returnValue IntegratorExport::getDataDeclarations ( ExportStatementBlock declarations,
ExportStruct  dataStruct = ACADO_ANY 
) const [pure virtual]

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

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

Implements ExportAlgorithm.

Implemented in ImplicitRungeKuttaExport, DiscreteTimeExport, ExplicitRungeKuttaExport, RungeKuttaExport, NARXExport, ThreeSweepsERKExport, AdjointERKExport, and ForwardIRKExport.

Definition at line 691 of file integrator_export.cpp.

virtual returnValue IntegratorExport::getFunctionDeclarations ( ExportStatementBlock declarations) const [pure virtual]

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

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

Implements ExportAlgorithm.

Implemented in ImplicitRungeKuttaExport, DiscreteTimeExport, ExplicitRungeKuttaExport, RungeKuttaExport, and ForwardIRKExport.

returnValue IntegratorExport::getGrid ( Grid grid_) const [virtual]

Returns the grid of the integrator.

Returns:
SUCCESSFUL_RETURN

Definition at line 634 of file integrator_export.cpp.

uint IntegratorExport::getIntegrationInterval ( double  time) [protected]

Get the index of the integration interval, corresponding a certain time.

Parameters:
[in]timeThe time.
Returns:
The index of the integration interval.

Definition at line 624 of file integrator_export.cpp.

const std::string IntegratorExport::getNameDiffsOUTPUT ( uint  index) const

Definition at line 705 of file integrator_export.cpp.

const std::string IntegratorExport::getNameDiffsRHS ( ) const

Definition at line 701 of file integrator_export.cpp.

const std::string IntegratorExport::getNameFullRHS ( ) const [virtual]

Definition at line 670 of file integrator_export.cpp.

const std::string IntegratorExport::getNameOUTPUT ( uint  index) const

Definition at line 687 of file integrator_export.cpp.

const std::string IntegratorExport::getNameOutputDiffs ( ) const

Definition at line 683 of file integrator_export.cpp.

const std::string IntegratorExport::getNameOutputRHS ( ) const

Definition at line 679 of file integrator_export.cpp.

const std::string IntegratorExport::getNameRHS ( ) const

Definition at line 666 of file integrator_export.cpp.

returnValue IntegratorExport::getNumSteps ( DVector _numSteps) const [virtual]

Returns the number of integration steps along the prediction horizon.

Returns:
SUCCESSFUL_RETURN

Definition at line 641 of file integrator_export.cpp.

returnValue IntegratorExport::getOutputExpressions ( std::vector< Expression > &  outputExpressions_) const [virtual]

Returns the output expressions.

Returns:
SUCCESSFUL_RETURN

Definition at line 648 of file integrator_export.cpp.

returnValue IntegratorExport::getOutputGrids ( std::vector< Grid > &  outputGrids_) const [virtual]

Returns the output grids.

Returns:
SUCCESSFUL_RETURN

Definition at line 655 of file integrator_export.cpp.

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

Assignment operator (deep copy).

Parameters:
[in]argRight-hand side object.

Definition at line 89 of file integrator_export.cpp.

returnValue IntegratorExport::propagateImplicitSystem ( ExportStatementBlock block,
const ExportIndex index1,
const ExportIndex index2,
const ExportIndex index3,
const ExportIndex tmp_index 
) [virtual]

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

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

Reimplemented in NARXExport.

Definition at line 460 of file integrator_export.cpp.

returnValue IntegratorExport::propagateInputSystem ( ExportStatementBlock block,
const ExportIndex index1,
const ExportIndex index2,
const ExportIndex index3,
const ExportIndex tmp_index 
) [virtual]

Exports the code needed to propagate the sensitivities of the states, defined by the linear input system.

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

Reimplemented in NARXExport.

Definition at line 394 of file integrator_export.cpp.

returnValue IntegratorExport::propagateOutputSystem ( ExportStatementBlock block,
const ExportIndex index1,
const ExportIndex index2,
const ExportIndex index3,
const ExportIndex tmp_index 
) [virtual]

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

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

Reimplemented in NARXExport.

Definition at line 526 of file integrator_export.cpp.

virtual returnValue IntegratorExport::setDifferentialEquation ( const Expression rhs) [pure virtual]

Assigns Differential Equation to be used by the integrator.

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

Implemented in RungeKuttaExport, DiscreteTimeExport, ImplicitRungeKuttaExport, ExplicitRungeKuttaExport, NARXExport, ThreeSweepsERKExport, AdjointERKExport, and ForwardOverBackwardERKExport.

returnValue IntegratorExport::setGrid ( const Grid _grid) [virtual]

Sets integration grid (this grid is expected to be non equidistant, otherwise use the other setGrid function).

Parameters:
[in]_gridintegration grid
Returns:
SUCCESSFUL_RETURN

Definition at line 101 of file integrator_export.cpp.

returnValue IntegratorExport::setLinearInput ( const DMatrix M1,
const DMatrix A1,
const DMatrix B1 
) [virtual]
Parameters:
[in].
Returns:
SUCCESSFUL_RETURN

Reimplemented in ExplicitRungeKuttaExport.

Definition at line 109 of file integrator_export.cpp.

returnValue IntegratorExport::setLinearOutput ( const DMatrix M3,
const DMatrix A3,
const Expression rhs 
) [virtual]
Parameters:
[in].
Returns:
SUCCESSFUL_RETURN

Reimplemented in NARXExport, and ExplicitRungeKuttaExport.

Definition at line 174 of file integrator_export.cpp.

returnValue IntegratorExport::setLinearOutput ( const DMatrix M3,
const DMatrix A3,
const std::string &  _rhs3,
const std::string &  _diffs_rhs3 
) [virtual]
Parameters:
[in].
Returns:
SUCCESSFUL_RETURN

Reimplemented in NARXExport, and ExplicitRungeKuttaExport.

Definition at line 253 of file integrator_export.cpp.

returnValue IntegratorExport::setModel ( const std::string &  _name_ODE,
const std::string &  _name_diffs_ODE 
) [virtual]

Assigns the model to be used by the integrator.

Parameters:
[in]_name_ODEName of the function, evaluating the ODE right-hand side.
[in]_name_diffs_ODEName of the function, evaluating the derivatives of the ODE right-hand side.
Returns:
SUCCESSFUL_RETURN

Reimplemented in ImplicitRungeKuttaExport, and NARXExport.

Definition at line 139 of file integrator_export.cpp.

Passes all the necessary model data to the integrator.

Parameters:
[in]dataThe model data.
Returns:
SUCCESSFUL_RETURN

Definition at line 289 of file integrator_export.cpp.

virtual returnValue IntegratorExport::setNARXmodel ( const uint  delay,
const DMatrix parms 
) [pure virtual]

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

Parameters:
[in]delayThe delay for the states in the NARX model.
[in]parmsThe parameters defining the polynomial NARX model.
Returns:
SUCCESSFUL_RETURN

Implemented in NARXExport, RungeKuttaExport, and DiscreteTimeExport.

virtual returnValue IntegratorExport::setup ( ) [pure virtual]
virtual returnValue IntegratorExport::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

Implemented in RungeKuttaExport, ExplicitRungeKuttaExport, ImplicitRungeKuttaExport, and DiscreteTimeExport.

virtual returnValue IntegratorExport::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 
) [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.
_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

Implemented in ExplicitRungeKuttaExport, ImplicitRungeKuttaExport, and DiscreteTimeExport.

virtual returnValue IntegratorExport::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 
) [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.
_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

Implemented in ExplicitRungeKuttaExport, ImplicitRungeKuttaExport, and DiscreteTimeExport.

returnValue IntegratorExport::updateImplicitSystem ( ExportStatementBlock block,
const ExportIndex index1,
const ExportIndex index2,
const ExportIndex tmp_index 
) [virtual]

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

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

Reimplemented in NARXExport.

Definition at line 422 of file integrator_export.cpp.

returnValue IntegratorExport::updateInputSystem ( ExportStatementBlock block,
const ExportIndex index1,
const ExportIndex index2,
const ExportIndex tmp_index 
) [virtual]

Exports the code needed to update the sensitivities of the states, defined by the linear input system.

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

Reimplemented in NARXExport.

Definition at line 372 of file integrator_export.cpp.

returnValue IntegratorExport::updateOutputSystem ( ExportStatementBlock block,
const ExportIndex index1,
const ExportIndex index2,
const ExportIndex tmp_index 
) [virtual]

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

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

Reimplemented in NARXExport.

Definition at line 504 of file integrator_export.cpp.


Member Data Documentation

Definition at line 434 of file integrator_export.hpp.

Definition at line 435 of file integrator_export.hpp.

Definition at line 434 of file integrator_export.hpp.

bool IntegratorExport::crsFormat [protected]

True if the CRS format is used for the jacobian of output functions.

Definition at line 438 of file integrator_export.hpp.

Module to export the evaluation of the derivatives of the output functions.

Definition at line 483 of file integrator_export.hpp.

Module to export the evaluation of the derivatives of the ordinary differential equations.

Definition at line 449 of file integrator_export.hpp.

Definition at line 454 of file integrator_export.hpp.

This is the total number of sensitivities needed.

Definition at line 429 of file integrator_export.hpp.

The differential state derivatives in the model.

Definition at line 474 of file integrator_export.hpp.

Variable containing the error code, returned by the integrator.

Definition at line 456 of file integrator_export.hpp.

bool IntegratorExport::exportRhs [protected]

True if the right-hand side and their derivatives should be exported too.

Definition at line 437 of file integrator_export.hpp.

Function that evaluates the full right-hand side.

Definition at line 443 of file integrator_export.hpp.

Evaluation grid along the prediction horizon.

Definition at line 440 of file integrator_export.hpp.

This is the dimension of the input to the integrator.

Definition at line 430 of file integrator_export.hpp.

Function that integrates the exported ODE.

Definition at line 447 of file integrator_export.hpp.

Definition at line 451 of file integrator_export.hpp.

Definition at line 434 of file integrator_export.hpp.

Definition at line 435 of file integrator_export.hpp.

Definition at line 426 of file integrator_export.hpp.

std::vector<uint> IntegratorExport::num_outputs [protected]

A separate dimension for each output.

Definition at line 485 of file integrator_export.hpp.

The number of integration steps per shooting interval.

Definition at line 441 of file integrator_export.hpp.

Definition at line 423 of file integrator_export.hpp.

Definition at line 424 of file integrator_export.hpp.

Definition at line 425 of file integrator_export.hpp.

Definition at line 427 of file integrator_export.hpp.

The "online" data values in the model.

Definition at line 477 of file integrator_export.hpp.

A separate dependency matrix for each output.

Definition at line 481 of file integrator_export.hpp.

A separate expression for each output.

Definition at line 480 of file integrator_export.hpp.

std::vector<Grid> IntegratorExport::outputGrids [protected]

A separate grid for each output.

Definition at line 479 of file integrator_export.hpp.

Module to export output functions.

Definition at line 482 of file integrator_export.hpp.

Variable containing the number of the current integration step.

Definition at line 457 of file integrator_export.hpp.

Module to export ODE.

Definition at line 448 of file integrator_export.hpp.

Definition at line 453 of file integrator_export.hpp.

Definition at line 444 of file integrator_export.hpp.

Definition at line 445 of file integrator_export.hpp.

Definition at line 464 of file integrator_export.hpp.

Variable containing the derivatives wrt the previous values.

Definition at line 467 of file integrator_export.hpp.

Definition at line 470 of file integrator_export.hpp.

Definition at line 463 of file integrator_export.hpp.

Variable containing the sensitivities from the previous integration step.

Definition at line 466 of file integrator_export.hpp.

Definition at line 471 of file integrator_export.hpp.

Variable containing intermediate results of evaluations of the derivatives of the differential equations (ordinary and algebraic).

Definition at line 468 of file integrator_export.hpp.

Variable containing the inputs or the results of the integrator.

Definition at line 461 of file integrator_export.hpp.

Variable containing the number of the current shooting interval.

Definition at line 458 of file integrator_export.hpp.

Variable containing the integration time.

Definition at line 459 of file integrator_export.hpp.

Variable containing the current integrator state.

Definition at line 460 of file integrator_export.hpp.

Definition at line 432 of file integrator_export.hpp.

The control inputs in the model.

Definition at line 476 of file integrator_export.hpp.

The differential states in the model.

Definition at line 473 of file integrator_export.hpp.

The algebraic states in the model.

Definition at line 475 of file integrator_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