Public Member Functions | Protected Attributes

Data class for defining models and everything that is related, to be passed to the integrator. More...

#include <model_data.hpp>

List of all members.

Public Member Functions

uint addOutput (const OutputFcn &outputEquation_, const Grid &measurements)
uint addOutput (const std::string &output, const std::string &diffs_output, const uint dim, const Grid &measurements)
uint addOutput (const std::string &output, const std::string &diffs_output, const uint dim, const Grid &measurements, const std::string &colInd, const std::string &rowPtr)
returnValue clearIntegrationGrid ()
BooleanType exportRhs () const
uint getDimOutput (uint index) const
DVector getDimOutputs () const
returnValue getDimOutputs (std::vector< uint > &dims) const
const std::string getFileNameModel () const
returnValue getIntegrationGrid (Grid &integrationGrid_) const
returnValue getLinearInput (DMatrix &M1_, DMatrix &A1_, DMatrix &B1_) const
returnValue getLinearOutput (DMatrix &M3_, DMatrix &A3_, OutputFcn &rhs_) const
returnValue getLinearOutput (DMatrix &M3_, DMatrix &A3_) const
returnValue getModel (DifferentialEquation &_f) const
uint getN () const
const std::string getNameDiffsOutput () const
returnValue getNameDiffsOutputs (std::vector< std::string > &names) const
const std::string getNameDiffsRhs () const
const std::string getNameOutput () const
returnValue getNameOutputs (std::vector< std::string > &names) const
const std::string getNameRhs () const
returnValue getNARXmodel (uint &_delay, DMatrix &_parms) const
uint getNDX () const
uint getNDX3 () const
uint getNOD () const
uint getNP () const
uint getNU () const
DVector getNumMeas () const
uint getNumOutputs () const
returnValue getNumSteps (DVector &_numSteps) const
uint getNX () const
uint getNX1 () const
uint getNX2 () const
uint getNX3 () const
uint getNXA () const
uint getNXA3 () const
std::vector< DMatrixgetOutputDependencies () const
returnValue getOutputExpressions (std::vector< Expression > &outputExpressions_) const
returnValue getOutputGrids (std::vector< Grid > &outputGrids_) const
BooleanType hasCompressedStorage () const
BooleanType hasDifferentialEquation () const
BooleanType hasEquidistantControlGrid () const
BooleanType hasOutputFunctions () const
BooleanType hasOutputs () const
 ModelData ()
BooleanType modelDimensionsSet () const
returnValue setDimensions (uint _NX1, uint _NX2, uint _NX3, uint _NDX, uint _NDX3, uint _NXA, uint _NXA3, uint _NU, uint _NOD, uint _NP)
returnValue setIntegrationGrid (const Grid &_ocpGrid, const uint _numSteps)
returnValue setLinearInput (const DMatrix &M1_, const DMatrix &A1_, const DMatrix &B1_)
returnValue setLinearOutput (const DMatrix &M3_, const DMatrix &A3_, const OutputFcn &rhs_)
returnValue setLinearOutput (const DMatrix &M3_, const DMatrix &A3_, const std::string &_rhs3, const std::string &_diffs3)
returnValue setModel (const DifferentialEquation &_f)
returnValue setModel (const std::string &fileName, const std::string &_rhs_ODE, const std::string &_diffs_rhs_ODE)
returnValue setN (const uint N_)
returnValue setNARXmodel (const uint _delay, const DMatrix &_parms)
returnValue setNumSteps (const DVector &_numSteps)

Protected Attributes

DMatrix A1
DMatrix A3
DMatrix B1
std::vector< DVectorcolInd_outputs
uint delay
DifferentialEquation differentialEquation
std::string diffs3_name
std::string diffs_name
std::vector< std::string > diffs_outputNames
std::vector< uintdim_outputs
BooleanType export_rhs
std::string externModel
Grid integrationGrid
DMatrix M1
DMatrix M3
BooleanType model_dimensions_set
uint N
uint NDX
uint NDX3
uint NOD
uint NP
uint NU
std::vector< uintnum_meas
DVector numSteps
uint NX1
uint NX2
uint NX3
uint NXA
uint NXA3
std::vector< ExpressionoutputExpressions
std::vector< GridoutputGrids
std::vector< std::string > outputNames
DMatrix parms
OutputFcn rhs3
std::string rhs3_name
std::string rhs_name
std::vector< DVectorrowPtr_outputs

Detailed Description

Data class for defining models and everything that is related, to be passed to the integrator.

TODO: Rien

Author:
Rien Quirynen

Definition at line 52 of file model_data.hpp.


Constructor & Destructor Documentation

Default constructor.

Definition at line 44 of file model_data.cpp.


Member Function Documentation

uint ModelData::addOutput ( const OutputFcn outputEquation_,
const Grid measurements 
)

Adds an output function.

Parameters:
outputEquation_an output function to be added
measurementsThe measurement grid per interval
Returns:
SUCCESSFUL_RETURN

Definition at line 80 of file model_data.cpp.

uint ModelData::addOutput ( const std::string &  output,
const std::string &  diffs_output,
const uint  dim,
const Grid measurements 
)

Adds an output function.

Parameters:
outputThe output function to be added.
diffs_outputThe derivatives of the output function to be added.
dimThe dimension of the output function.
measurementsThe measurement grid per interval
Returns:
SUCCESSFUL_RETURN

Definition at line 106 of file model_data.cpp.

uint ModelData::addOutput ( const std::string &  output,
const std::string &  diffs_output,
const uint  dim,
const Grid measurements,
const std::string &  colInd,
const std::string &  rowPtr 
)

Adds an output function.

Parameters:
outputThe output function to be added.
diffs_outputThe derivatives of the output function to be added.
dimThe dimension of the output function.
measurementsThe measurement grid per interval
colIndDVector stores the column indices of the elements for Compressed Row Storage (CRS).
rowPtrDVector stores the locations that start a row for Compressed Row Storage (CRS).
Returns:
SUCCESSFUL_RETURN

Definition at line 126 of file model_data.cpp.

Clears any previously set integration grid.

Returns:
SUCCESSFUL_RETURN

Definition at line 411 of file model_data.cpp.

Definition at line 445 of file model_data.cpp.

uint ModelData::getDimOutput ( uint  index) const

Returns the dimension of a specific output function.

Parameters:
indexThe index of the output function.
Returns:
The dimension of a specific output function.

Returns the dimensions of the different output functions.

Returns:
dimensions of the different output functions.

Definition at line 550 of file model_data.cpp.

returnValue ModelData::getDimOutputs ( std::vector< uint > &  dims) const

Returns the dimensions of the different output functions.

Returns:
dimensions of the different output functions.

Definition at line 566 of file model_data.cpp.

const std::string ModelData::getFileNameModel ( ) const

Definition at line 583 of file model_data.cpp.

returnValue ModelData::getIntegrationGrid ( Grid integrationGrid_) const

Returns the grid to be used by the integrator.

Returns:
The grid to be used by the integrator.

Definition at line 369 of file model_data.cpp.

returnValue ModelData::getLinearInput ( DMatrix M1_,
DMatrix A1_,
DMatrix B1_ 
) const
Parameters:
[in].
Returns:
SUCCESSFUL_RETURN

Definition at line 219 of file model_data.cpp.

returnValue ModelData::getLinearOutput ( DMatrix M3_,
DMatrix A3_,
OutputFcn rhs_ 
) const
Parameters:
[in].
Returns:
SUCCESSFUL_RETURN

Definition at line 228 of file model_data.cpp.

returnValue ModelData::getLinearOutput ( DMatrix M3_,
DMatrix A3_ 
) const
Parameters:
[in].
Returns:
SUCCESSFUL_RETURN

Definition at line 237 of file model_data.cpp.

Returns the differential equations in the model.

Returns:
SUCCESSFUL_RETURN

Definition at line 203 of file model_data.cpp.

uint ModelData::getN ( ) const

Returns number of shooting intervals.

Returns:
Number of shooting intervals

Definition at line 537 of file model_data.cpp.

const std::string ModelData::getNameDiffsOutput ( ) const

Definition at line 603 of file model_data.cpp.

returnValue ModelData::getNameDiffsOutputs ( std::vector< std::string > &  names) const

Definition at line 614 of file model_data.cpp.

const std::string ModelData::getNameDiffsRhs ( ) const

Definition at line 593 of file model_data.cpp.

const std::string ModelData::getNameOutput ( ) const

Definition at line 598 of file model_data.cpp.

returnValue ModelData::getNameOutputs ( std::vector< std::string > &  names) const

Definition at line 608 of file model_data.cpp.

const std::string ModelData::getNameRhs ( ) const

Definition at line 588 of file model_data.cpp.

returnValue ModelData::getNARXmodel ( uint _delay,
DMatrix _parms 
) const

Returns the polynomial NARX model.

Returns:
SUCCESSFUL_RETURN

Definition at line 210 of file model_data.cpp.

Returns number of differential state derivatives.

Returns:
Number of differential state derivatives

Definition at line 487 of file model_data.cpp.

Definition at line 496 of file model_data.cpp.

Returns number of parameters.

Returns:
Number of parameters

Definition at line 531 of file model_data.cpp.

Returns number of parameters.

Returns:
Number of parameters

Definition at line 526 of file model_data.cpp.

Returns number of control inputs.

Returns:
Number of control inputs

Definition at line 520 of file model_data.cpp.

Returns the number of measurements for the different output functions.

Returns:
number of measurements for the different output functions.

Definition at line 573 of file model_data.cpp.

Returns the number of different output functions.

Returns:
the number of different output functions.

Definition at line 560 of file model_data.cpp.

returnValue ModelData::getNumSteps ( DVector _numSteps) const

Returns the number of integration steps along the horizon.

Returns:
SUCCESSFUL_RETURN

Definition at line 152 of file model_data.cpp.

Returns number of differential states.

Returns:
Number of differential states

Definition at line 458 of file model_data.cpp.

Definition at line 469 of file model_data.cpp.

Definition at line 475 of file model_data.cpp.

Definition at line 481 of file model_data.cpp.

Returns number of algebraic states.

Returns:
Number of algebraic states

Definition at line 505 of file model_data.cpp.

Definition at line 511 of file model_data.cpp.

std::vector< DMatrix > ModelData::getOutputDependencies ( ) const

Returns the dependency matrix for each output function, which is defined externally.

Returns:
The dependency matrix for each output function, defined externally.

Definition at line 173 of file model_data.cpp.

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

Returns the output functions.

Returns:
SUCCESSFUL_RETURN

Definition at line 166 of file model_data.cpp.

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

Returns the output grids.

Returns:
SUCCESSFUL_RETURN

Definition at line 196 of file model_data.cpp.

Definition at line 451 of file model_data.cpp.

Definition at line 432 of file model_data.cpp.

Definition at line 419 of file model_data.cpp.

Definition at line 425 of file model_data.cpp.

Returns true if there are extra outputs, specified for the integrator.

Returns:
True if there are extra outputs, specified for the integrator.

Definition at line 145 of file model_data.cpp.

Definition at line 439 of file model_data.cpp.

returnValue ModelData::setDimensions ( uint  _NX1,
uint  _NX2,
uint  _NX3,
uint  _NDX,
uint  _NDX3,
uint  _NXA,
uint  _NXA3,
uint  _NU,
uint  _NOD,
uint  _NP 
)

Assigns the model dimensions to be used by the integrator.

Parameters:
[in]_NX1Number of differential states in linear input subsystem.
[in]_NX2Number of differential states in nonlinear subsystem.
[in]_NX3Number of differential states in linear output subsystem.
[in]_NDXNumber of differential states derivatives.
[in]_NDX3Number of differential states derivatives in the linear output subsystem.
[in]_NXANumber of algebraic states.
[in]_NXA3Number of algebraic states in the linear output subsystem.
[in]_NUNumber of control inputs
[in]_NODNumber of "online data" values
[in]_NPNumber of parameters
Returns:
SUCCESSFUL_RETURN

Definition at line 63 of file model_data.cpp.

returnValue ModelData::setIntegrationGrid ( const Grid _ocpGrid,
const uint  _numSteps 
)

Sets integration grid.

Parameters:
[in]_ocpGridEvaluation grid for optimal control.
[in]numStepsThe number of integration steps along the horizon.
Returns:
SUCCESSFUL_RETURN

Definition at line 376 of file model_data.cpp.

returnValue ModelData::setLinearInput ( const DMatrix M1_,
const DMatrix A1_,
const DMatrix B1_ 
)
Parameters:
[in].
Returns:
SUCCESSFUL_RETURN

Definition at line 301 of file model_data.cpp.

returnValue ModelData::setLinearOutput ( const DMatrix M3_,
const DMatrix A3_,
const OutputFcn rhs_ 
)
Parameters:
[in].
Returns:
SUCCESSFUL_RETURN

Definition at line 314 of file model_data.cpp.

returnValue ModelData::setLinearOutput ( const DMatrix M3_,
const DMatrix A3_,
const std::string &  _rhs3,
const std::string &  _diffs3 
)
Parameters:
[in].
Returns:
SUCCESSFUL_RETURN

Definition at line 332 of file model_data.cpp.

Assigns Differential Equation to be used by the integrator.

Parameters:
[in]fDifferential equation.
Returns:
SUCCESSFUL_RETURN

Definition at line 245 of file model_data.cpp.

returnValue ModelData::setModel ( const std::string &  fileName,
const std::string &  _rhs_ODE,
const std::string &  _diffs_rhs_ODE 
)

Assigns the model to be used by the integrator.

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

Definition at line 350 of file model_data.cpp.

Sets the number of shooting intervals.

Parameters:
[in]N_The number of shooting intervals.
Returns:
SUCCESSFUL_RETURN

Definition at line 543 of file model_data.cpp.

returnValue ModelData::setNARXmodel ( const uint  _delay,
const DMatrix _parms 
)

Assigns 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

Definition at line 272 of file model_data.cpp.

returnValue ModelData::setNumSteps ( const DVector _numSteps)

Sets the number of integration steps along the horizon.

Returns:
SUCCESSFUL_RETURN

Definition at line 159 of file model_data.cpp.


Member Data Documentation

DMatrix ModelData::A1 [protected]

Definition at line 454 of file model_data.hpp.

DMatrix ModelData::A3 [protected]

Definition at line 458 of file model_data.hpp.

DMatrix ModelData::B1 [protected]

Definition at line 455 of file model_data.hpp.

std::vector<DVector> ModelData::colInd_outputs [protected]

A separate DVector of column indices for each output if in CRS format.

Definition at line 445 of file model_data.hpp.

uint ModelData::delay [protected]

Definition at line 462 of file model_data.hpp.

The differential equations in the model.

Definition at line 434 of file model_data.hpp.

std::string ModelData::diffs3_name [protected]

The name of the function evaluating the derivatives for the linear output system, if provided.

Definition at line 433 of file model_data.hpp.

std::string ModelData::diffs_name [protected]

The name of the function evaluating the derivatives of the ODE right-hand side, if provided.

Definition at line 431 of file model_data.hpp.

std::vector<std::string> ModelData::diffs_outputNames [protected]

A separate function name for evaluating the derivatives of each output.

Definition at line 444 of file model_data.hpp.

std::vector<uint> ModelData::dim_outputs [protected]

Dimensions of the different output functions.

Definition at line 441 of file model_data.hpp.

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

Definition at line 427 of file model_data.hpp.

std::string ModelData::externModel [protected]

The name of the file containing the needed functions, if provided.

Definition at line 429 of file model_data.hpp.

Integration grid.

Definition at line 436 of file model_data.hpp.

DMatrix ModelData::M1 [protected]

Definition at line 453 of file model_data.hpp.

DMatrix ModelData::M3 [protected]

Definition at line 457 of file model_data.hpp.

True if the model dimensions have been set.

Definition at line 428 of file model_data.hpp.

uint ModelData::N [protected]

Number of shooting intervals.

Definition at line 425 of file model_data.hpp.

uint ModelData::NDX [protected]

Number of differential states derivatives.

Definition at line 418 of file model_data.hpp.

uint ModelData::NDX3 [protected]

Number of differential states derivatives in output system.

Definition at line 419 of file model_data.hpp.

uint ModelData::NOD [protected]

Number of online data values.

Definition at line 424 of file model_data.hpp.

uint ModelData::NP [protected]

Number of parameters.

Definition at line 423 of file model_data.hpp.

uint ModelData::NU [protected]

Number of control inputs.

Definition at line 422 of file model_data.hpp.

std::vector<uint> ModelData::num_meas [protected]

Number of measurements for the different output functions.

Definition at line 442 of file model_data.hpp.

The number of integration steps per shooting interval.

Definition at line 437 of file model_data.hpp.

uint ModelData::NX1 [protected]

Number of differential states (defined by input system).

Definition at line 415 of file model_data.hpp.

uint ModelData::NX2 [protected]

Number of differential states (defined by implicit system).

Definition at line 416 of file model_data.hpp.

uint ModelData::NX3 [protected]

Number of differential states (defined by output system).

Definition at line 417 of file model_data.hpp.

uint ModelData::NXA [protected]

Number of algebraic states.

Definition at line 420 of file model_data.hpp.

uint ModelData::NXA3 [protected]

Number of algebraic states in output system.

Definition at line 421 of file model_data.hpp.

std::vector<Expression> ModelData::outputExpressions [protected]

A vector with the output functions.

Definition at line 439 of file model_data.hpp.

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

A separate grid for each output function.

Definition at line 440 of file model_data.hpp.

std::vector<std::string> ModelData::outputNames [protected]

A separate function name for each output.

Definition at line 443 of file model_data.hpp.

Definition at line 463 of file model_data.hpp.

Definition at line 459 of file model_data.hpp.

std::string ModelData::rhs3_name [protected]

The name of the nonlinear function in the linear output system, if provided.

Definition at line 432 of file model_data.hpp.

std::string ModelData::rhs_name [protected]

The name of the function evaluating the ODE right-hand side, if provided.

Definition at line 430 of file model_data.hpp.

std::vector<DVector> ModelData::rowPtr_outputs [protected]

A separate DVector of row pointers for each output if in CRS format.

Definition at line 446 of file model_data.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