Public Member Functions | Protected Member Functions | Protected Attributes | List of all members

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

#include <integrator_export.hpp>

Inheritance diagram for IntegratorExport:
Inheritance graph
[legend]

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

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
 
- Protected Attributes inherited from ExportAlgorithm
std::string commonHeaderName
 
uint N
 
uint NDX
 
uint NOD
 
uint NP
 
uint NU
 
uint NX
 
uint NXA
 
uint NY
 
uint NYN
 
- Protected Attributes inherited from AlgorithmicBase
int outputLoggingIdx
 
BooleanType useModuleStandalone
 
UserInteractionuserInteraction
 

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.

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

IntegratorExport::~IntegratorExport ( )
virtual

Destructor.

Definition at line 83 of file integrator_export.cpp.

Member Function Documentation

returnValue IntegratorExport::clear ( )
protectedvirtual

Frees internal dynamic memory to yield an empty function.

\return SUCCESSFUL_RETURN

Definition at line 656 of file integrator_export.cpp.

returnValue IntegratorExport::copy ( const IntegratorExport arg)
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.

bool IntegratorExport::equidistantControlGrid ( ) const
virtual

Returns whether the grid is equidistant.

Returns
true iff the grid is equidistant, false otherwise.

Definition at line 699 of file integrator_export.cpp.

DMatrix IntegratorExport::expandOutputMatrix ( const DMatrix A3)
protected
@param[in] A3                       .

\return SUCCESSFUL_RETURN

Definition at line 628 of file integrator_export.cpp.

virtual ExportVariable IntegratorExport::getAuxVariable ( ) const
protectedpure virtual
virtual returnValue IntegratorExport::getCode ( ExportStatementBlock code)
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.

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.

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

uint IntegratorExport::getDimOUTPUT ( uint  index) const

Definition at line 729 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.

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

returnValue IntegratorExport::getGrid ( Grid grid_) const
virtual

Returns the grid of the integrator.

Returns
SUCCESSFUL_RETURN

Definition at line 672 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 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.

const std::string IntegratorExport::getNameFullRHS ( ) const
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.

returnValue IntegratorExport::getNumSteps ( DVector _numSteps) const
virtual

Returns the number of integration steps along the prediction horizon.

Returns
SUCCESSFUL_RETURN

Definition at line 679 of file integrator_export.cpp.

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

Returns the output expressions.

Returns
SUCCESSFUL_RETURN

Definition at line 686 of file integrator_export.cpp.

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

Returns the output grids.

Returns
SUCCESSFUL_RETURN

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.

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.

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

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.

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

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.

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

virtual returnValue IntegratorExport::setDifferentialEquation ( const Expression rhs)
pure virtual
returnValue IntegratorExport::setGrid ( const Grid _grid)
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.

returnValue IntegratorExport::setLinearInput ( const DMatrix M1,
const DMatrix A1,
const DMatrix B1 
)
virtual
@param[in]          .

\return 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
@param[in]          .

\return SUCCESSFUL_RETURN

Reimplemented in NARXExport, and ExplicitRungeKuttaExport.

Definition at line 176 of file integrator_export.cpp.

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

\return SUCCESSFUL_RETURN

Reimplemented in NARXExport, and ExplicitRungeKuttaExport.

Definition at line 266 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.

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

returnValue IntegratorExport::setModelData ( const ModelData data)
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.

virtual returnValue IntegratorExport::setNARXmodel ( const uint  delay,
const DMatrix parms 
)
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.

returnValue IntegratorExport::setNonlinearFeedback ( const DMatrix C,
const Expression feedb 
)
virtual
@param[in]          .

\return SUCCESSFUL_RETURN

Reimplemented in FeedbackLiftedIRKExport.

Definition at line 255 of file integrator_export.cpp.

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.

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

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.

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

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.

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

Member Data Documentation

DMatrix IntegratorExport::A11
protected

Definition at line 443 of file integrator_export.hpp.

DMatrix IntegratorExport::A33
protected

Definition at line 444 of file integrator_export.hpp.

DMatrix IntegratorExport::B11
protected

Definition at line 443 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 447 of file integrator_export.hpp.

std::vector<ExportAcadoFunction> IntegratorExport::diffs_outputs
protected

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

Definition at line 492 of file integrator_export.hpp.

ExportAcadoFunction IntegratorExport::diffs_rhs
protected

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

Definition at line 458 of file integrator_export.hpp.

ExportAcadoFunction IntegratorExport::diffs_rhs3
protected

Definition at line 463 of file integrator_export.hpp.

uint IntegratorExport::diffsDim
protected

This is the total number of sensitivities needed.

Definition at line 438 of file integrator_export.hpp.

DifferentialStateDerivative IntegratorExport::dx
protected

The differential state derivatives in the model.

Definition at line 483 of file integrator_export.hpp.

ExportVariable IntegratorExport::error_code
protected

Variable containing the error code, returned by the integrator.

Definition at line 465 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 446 of file integrator_export.hpp.

ExportFunction IntegratorExport::fullRhs
protected

Function that evaluates the full right-hand side.

Definition at line 452 of file integrator_export.hpp.

Grid IntegratorExport::grid
protected

Evaluation grid along the prediction horizon.

Definition at line 449 of file integrator_export.hpp.

uint IntegratorExport::inputDim
protected

This is the dimension of the input to the integrator.

Definition at line 439 of file integrator_export.hpp.

ExportFunction IntegratorExport::integrate
protected

Function that integrates the exported ODE.

Definition at line 456 of file integrator_export.hpp.

ExportAcadoFunction IntegratorExport::lin_input
protected

Definition at line 460 of file integrator_export.hpp.

DMatrix IntegratorExport::M11
protected

Definition at line 443 of file integrator_export.hpp.

DMatrix IntegratorExport::M33
protected

Definition at line 444 of file integrator_export.hpp.

uint IntegratorExport::NDX3
protected

Definition at line 435 of file integrator_export.hpp.

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

A separate dimension for each output.

Definition at line 494 of file integrator_export.hpp.

DVector IntegratorExport::numSteps
protected

The number of integration steps per shooting interval.

Definition at line 450 of file integrator_export.hpp.

uint IntegratorExport::NX1
protected

Definition at line 432 of file integrator_export.hpp.

uint IntegratorExport::NX2
protected

Definition at line 433 of file integrator_export.hpp.

uint IntegratorExport::NX3
protected

Definition at line 434 of file integrator_export.hpp.

uint IntegratorExport::NXA3
protected

Definition at line 436 of file integrator_export.hpp.

OnlineData IntegratorExport::od
protected

The "online" data values in the model.

Definition at line 486 of file integrator_export.hpp.

std::vector<DMatrix> IntegratorExport::outputDependencies
protected

A separate dependency matrix for each output.

Definition at line 490 of file integrator_export.hpp.

std::vector<Expression> IntegratorExport::outputExpressions
protected

A separate expression for each output.

Definition at line 489 of file integrator_export.hpp.

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

A separate grid for each output.

Definition at line 488 of file integrator_export.hpp.

std::vector<ExportAcadoFunction> IntegratorExport::outputs
protected

Module to export output functions.

Definition at line 491 of file integrator_export.hpp.

ExportVariable IntegratorExport::reset_int
protected

Variable containing the number of the current integration step.

Definition at line 466 of file integrator_export.hpp.

ExportAcadoFunction IntegratorExport::rhs
protected

Module to export ODE.

Definition at line 457 of file integrator_export.hpp.

ExportAcadoFunction IntegratorExport::rhs3
protected

Definition at line 462 of file integrator_export.hpp.

ExportVariable IntegratorExport::rhs_in
protected

Definition at line 453 of file integrator_export.hpp.

ExportVariable IntegratorExport::rhs_out
protected

Definition at line 454 of file integrator_export.hpp.

ExportVariable IntegratorExport::rk_diffsNew1
protected

Definition at line 473 of file integrator_export.hpp.

ExportVariable IntegratorExport::rk_diffsNew2
protected

Variable containing the derivatives wrt the previous values.

Definition at line 476 of file integrator_export.hpp.

ExportVariable IntegratorExport::rk_diffsNew3
protected

Definition at line 479 of file integrator_export.hpp.

ExportVariable IntegratorExport::rk_diffsPrev1
protected

Definition at line 472 of file integrator_export.hpp.

ExportVariable IntegratorExport::rk_diffsPrev2
protected

Variable containing the sensitivities from the previous integration step.

Definition at line 475 of file integrator_export.hpp.

ExportVariable IntegratorExport::rk_diffsPrev3
protected

Definition at line 480 of file integrator_export.hpp.

ExportVariable IntegratorExport::rk_diffsTemp2
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.

ExportVariable IntegratorExport::rk_eta
protected

Variable containing the inputs or the results of the integrator.

Definition at line 470 of file integrator_export.hpp.

ExportVariable IntegratorExport::rk_index
protected

Variable containing the number of the current shooting interval.

Definition at line 467 of file integrator_export.hpp.

ExportVariable IntegratorExport::rk_ttt
protected

Variable containing the integration time.

Definition at line 468 of file integrator_export.hpp.

ExportVariable IntegratorExport::rk_xxx
protected

Variable containing the current integrator state.

Definition at line 469 of file integrator_export.hpp.

bool IntegratorExport::timeDependant
protected

Definition at line 441 of file integrator_export.hpp.

Control IntegratorExport::u
protected

The control inputs in the model.

Definition at line 485 of file integrator_export.hpp.

DifferentialState IntegratorExport::x
protected

The differential states in the model.

Definition at line 482 of file integrator_export.hpp.

AlgebraicState IntegratorExport::z
protected

The algebraic states in the model.

Definition at line 484 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 Mon Jun 10 2019 12:35:25