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

Provides a time grid consisting of matrix-valued optimization variables at each grid point. More...

#include <matrix_variables_grid.hpp>

Inheritance diagram for MatrixVariablesGrid:
Inheritance graph
[legend]

Public Member Functions

returnValue addMatrix (const DMatrix &newMatrix, double newTime=-INFTY)
 
returnValue appendTimes (const MatrixVariablesGrid &arg, MergeMethod _mergeMethod=MM_DUPLICATE)
 
returnValue appendValues (const MatrixVariablesGrid &arg)
 
returnValue coarsenGrid (const Grid &arg)
 
returnValue disableAutoInit ()
 
returnValue enableAutoInit ()
 
BooleanType getAutoInit (uint pointIdx) const
 
MatrixVariablesGrid getCoarsenedGrid (const Grid &arg) const
 
uint getDim () const
 
DMatrix getFirstMatrix () const
 
returnValue getGrid (Grid &_grid) const
 
DMatrix getLastMatrix () const
 
double getLowerBound (uint pointIdx, uint valueIdx) const
 
DVector getLowerBounds (uint pointIdx) const
 
DMatrix getMatrix (uint pointIdx) const
 
double getMax () const
 
double getMean () const
 
double getMin () const
 
returnValue getName (uint pointIdx, uint idx, char *const _name) const
 
uint getNumCols () const
 
uint getNumCols (uint pointIdx) const
 
uint getNumRows () const
 
uint getNumRows (uint pointIdx) const
 
uint getNumValues () const
 
uint getNumValues (uint pointIdx) const
 
MatrixVariablesGrid getRefinedGrid (const Grid &arg, InterpolationMode mode=IM_CONSTANT) const
 
DVector getScaling (uint pointIdx) const
 
double getScaling (uint pointIdx, uint valueIdx) const
 
Grid getTimePoints () const
 
MatrixVariablesGrid getTimeSubGrid (uint startIdx, uint endIdx) const
 
VariableType getType () const
 
VariableType getType (uint pointIdx) const
 
returnValue getUnit (uint pointIdx, uint idx, char *const _unit) const
 
double getUpperBound (uint pointIdx, uint valueIdx) const
 
DVector getUpperBounds (uint pointIdx) const
 
MatrixVariablesGrid getValuesSubGrid (uint startIdx, uint endIdx) const
 
BooleanType hasLowerBounds () const
 
BooleanType hasNames () const
 
BooleanType hasScaling () const
 
BooleanType hasUnits () const
 
BooleanType hasUpperBounds () const
 
returnValue init ()
 
returnValue init (uint _nRows, uint _nCols, const Grid &_grid, VariableType _type=VT_UNKNOWN, const char **const _names=0, const char **const _units=0, const DVector *const _scaling=0, const DVector *const _lb=0, const DVector *const _ub=0, const BooleanType *const _autoInit=0)
 
returnValue init (uint _nRows, uint _nCols, uint _nPoints, VariableType _type=VT_UNKNOWN, const char **const _names=0, const char **const _units=0, const DVector *const _scaling=0, const DVector *const _lb=0, const DVector *const _ub=0, const BooleanType *const _autoInit=0)
 
returnValue init (uint _nRows, uint _nCols, double _firstTime, double _lastTime, uint _nPoints, VariableType _type=VT_UNKNOWN, const char **const _names=0, const char **const _units=0, const DVector *const _scaling=0, const DVector *const _lb=0, const DVector *const _ub=0, const BooleanType *const _autoInit=0)
 
returnValue init (const DMatrix &arg, const Grid &_grid=trivialGrid, VariableType _type=VT_UNKNOWN)
 
DVector linearInterpolation (double time) const
 
 MatrixVariablesGrid ()
 
 MatrixVariablesGrid (uint _nRows, uint _nCols, const Grid &_grid, VariableType _type=VT_UNKNOWN, const char **const _names=0, const char **const _units=0, const DVector *const _scaling=0, const DVector *const _lb=0, const DVector *const _ub=0, const BooleanType *const _autoInit=0)
 
 MatrixVariablesGrid (uint _nRows, uint _nCols, uint _nPoints, VariableType _type=VT_UNKNOWN, const char **const _names=0, const char **const _units=0, const DVector *const _scaling=0, const DVector *const _lb=0, const DVector *const _ub=0, const BooleanType *const _autoInit=0)
 
 MatrixVariablesGrid (uint _nRows, uint _nCols, double _firstTime, double _lastTime, uint _nPoints, VariableType _type=VT_UNKNOWN, const char **const _names=0, const char **const _units=0, const DVector *const _scaling=0, const DVector *const _lb=0, const DVector *const _ub=0, const BooleanType *const _autoInit=0)
 
 MatrixVariablesGrid (const DMatrix &arg, const Grid &_grid=trivialGrid, VariableType _type=VT_UNKNOWN)
 
 MatrixVariablesGrid (const MatrixVariablesGrid &rhs)
 
returnValue merge (const MatrixVariablesGrid &arg, MergeMethod _mergeMethod=MM_DUPLICATE, BooleanType keepOverlap=BT_TRUE)
 
double & operator() (uint pointIdx, uint rowIdx, uint colIdx)
 
double operator() (uint pointIdx, uint rowIdx, uint colIdx) const
 
MatrixVariablesGrid operator() (const uint rowIdx) const
 
MatrixVariablesGrid operator+ (const MatrixVariablesGrid &arg) const
 
MatrixVariablesGridoperator+= (const MatrixVariablesGrid &arg)
 
MatrixVariablesGrid operator- (const MatrixVariablesGrid &arg) const
 
MatrixVariablesGridoperator-= (const MatrixVariablesGrid &arg)
 
MatrixVariablesGridoperator= (const MatrixVariablesGrid &rhs)
 
MatrixVariablesGridoperator= (const DMatrix &rhs)
 
MatrixVariablesGrid operator[] (const uint pointIdx) const
 
returnValue print (std::ostream &stream=std::cout, const char *const name=DEFAULT_LABEL, const char *const startString=DEFAULT_START_STRING, const char *const endString=DEFAULT_END_STRING, uint width=DEFAULT_WIDTH, uint precision=DEFAULT_PRECISION, const char *const colSeparator=DEFAULT_COL_SEPARATOR, const char *const rowSeparator=DEFAULT_ROW_SEPARATOR) const
 
returnValue print (const char *const filename, const char *const name=DEFAULT_LABEL, const char *const startString=DEFAULT_START_STRING, const char *const endString=DEFAULT_END_STRING, uint width=DEFAULT_WIDTH, uint precision=DEFAULT_PRECISION, const char *const colSeparator=DEFAULT_COL_SEPARATOR, const char *const rowSeparator=DEFAULT_ROW_SEPARATOR) const
 
returnValue print (const char *const filename, const char *const name, PrintScheme printScheme) const
 
returnValue print (std::ostream &stream, const char *const name, PrintScheme printScheme) const
 
returnValue read (std::istream &stream)
 
returnValue read (const char *const filename)
 
returnValue refineGrid (const Grid &arg, InterpolationMode mode=IM_CONSTANT)
 
returnValue setAll (double _value)
 
returnValue setAllMatrices (const DMatrix &_values)
 
returnValue setAutoInit (uint pointIdx, BooleanType _autoInit)
 
returnValue setLowerBound (uint pointIdx, uint valueIdx, double _lb)
 
returnValue setLowerBounds (uint pointIdx, const DVector &_lb)
 
returnValue setMatrix (uint pointIdx, const DMatrix &_value) const
 
returnValue setName (uint pointIdx, uint idx, const char *const _name)
 
returnValue setScaling (uint pointIdx, const DVector &_scaling)
 
returnValue setScaling (uint pointIdx, uint valueIdx, double _scaling)
 
returnValue setType (VariableType _type)
 
returnValue setType (uint pointIdx, VariableType _type)
 
returnValue setUnit (uint pointIdx, uint idx, const char *const _unit)
 
returnValue setUpperBound (uint pointIdx, uint valueIdx, double _ub)
 
returnValue setUpperBounds (uint pointIdx, const DVector &_ub)
 
returnValue setZero ()
 
MatrixVariablesGridshiftBackwards (DMatrix lastValue=emptyMatrix)
 
MatrixVariablesGridshiftTimes (double timeShift)
 
returnValue sprint (std::ostream &stream)
 
virtual ~MatrixVariablesGrid ()
 
- Public Member Functions inherited from Grid
returnValue addTime (double _time)
 
returnValue coarsenGrid (uint factor)
 
returnValue equalizeGrids (Grid &arg)
 
int findFirstTime (double _time, uint startIdx=0) const
 
int findLastTime (double _time, uint startIdx=0) const
 
int findTime (double _time, uint startIdx=0) const
 
uint getCeilIndex (double time) const
 
double getFirstTime () const
 
uint getFloorIndex (double time) const
 
double getIntervalLength () const
 
double getIntervalLength (uint pointIdx) const
 
uint getLastIndex () const
 
double getLastTime () const
 
uint getNumIntervals () const
 
uint getNumPoints () const
 
returnValue getSubGrid (double tStart, double tEnd, Grid &_subGrid) const
 
double getTime (uint pointIdx) const
 
 Grid ()
 
 Grid (uint nPoints_, double *times_=0)
 
 Grid (const DVector &times_)
 
 Grid (double _firstTime, double _lastTime, uint _nPoints=2)
 
 Grid (const Grid &rhs)
 
BooleanType hasTime (double _time) const
 
returnValue init (uint _nPoints=0, const double *const _times=0)
 
returnValue init (const DVector &times_)
 
returnValue init (double _firstTime, double _lastTime, uint _nPoints=2)
 
returnValue init (const Grid &rhs)
 
BooleanType isEmpty () const
 
BooleanType isEquidistant () const
 
BooleanType isInInterval (double _time) const
 
BooleanType isInInterval (uint pointIdx, double _time) const
 
BooleanType isInLowerHalfOpenInterval (uint pointIdx, double _time) const
 
BooleanType isInUpperHalfOpenInterval (uint pointIdx, double _time) const
 
BooleanType isLast (uint pointIdx) const
 
returnValue merge (const Grid &arg, MergeMethod _mergeMethod=MM_DUPLICATE, BooleanType keepOverlap=BT_TRUE)
 
BooleanType operator!= (const Grid &arg) const
 
Gridoperator& (const Grid &arg)
 
BooleanType operator< (const Grid &arg) const
 
BooleanType operator<= (const Grid &arg) const
 
Gridoperator= (const Grid &rhs)
 
BooleanType operator== (const Grid &arg) const
 
BooleanType operator> (const Grid &arg) const
 
BooleanType operator>= (const Grid &arg) const
 
returnValue print () const
 
returnValue refineGrid (uint factor)
 
returnValue scaleTimes (double scaling)
 
returnValue setTime (double _time)
 
returnValue setTime (uint pointIdx, double _time)
 
GridshiftTimes (double timeShift)
 
 ~Grid ()
 

Protected Member Functions

returnValue addMatrix (const MatrixVariable &newMatrix, double newTime=-INFTY)
 
returnValue clearValues ()
 
returnValue initMatrixVariables (uint _nRows, uint _nCols, VariableType _type=VT_UNKNOWN, const char **const _names=0, const char **const _units=0, const DVector *const _scaling=0, const DVector *const _lb=0, const DVector *const _ub=0, const BooleanType *const _autoInit=0)
 
- Protected Member Functions inherited from Grid
int findNextIndex () const
 
returnValue setupEquidistant (double _firstTime, double _lastTime)
 

Protected Attributes

MatrixVariable ** values
 
- Protected Attributes inherited from Grid
uint nPoints
 
double * times
 

Friends

std::ostream & operator<< (std::ostream &stream, const MatrixVariablesGrid &arg)
 
std::istream & operator>> (std::istream &stream, MatrixVariablesGrid &arg)
 

Detailed Description

Provides a time grid consisting of matrix-valued optimization variables at each grid point.

The class MatrixVariablesGrid provides a time grid consisting of matrix-valued optimization variables at each grid point, as they usually occur when discretizing optimal control problems.

The class inherits from the Grid class and stores the matrix-valued optimization variables in an re-allocatable array of MatrixVariables.

Author
Hans Joachim Ferreau, Boris Houska, Milan Vukov

Definition at line 60 of file matrix_variables_grid.hpp.

Constructor & Destructor Documentation

BEGIN_NAMESPACE_ACADO MatrixVariablesGrid::MatrixVariablesGrid ( )

Default constructor.

Definition at line 48 of file matrix_variables_grid.cpp.

MatrixVariablesGrid::MatrixVariablesGrid ( uint  _nRows,
uint  _nCols,
const Grid _grid,
VariableType  _type = VT_UNKNOWN,
const char **const  _names = 0,
const char **const  _units = 0,
const DVector *const  _scaling = 0,
const DVector *const  _lb = 0,
const DVector *const  _ub = 0,
const BooleanType *const  _autoInit = 0 
)

Constructor that takes the dimensions of each MatrixVariable as well as the grid on which they are defined. Further information can optionally be specified.

Parameters
[in]_nRowsNumber of rows of each matrix.
[in]_nColsNumber of columns of each matrix.
[in]_gridGrid on which the MatrixVariable(s) are defined.
[in]_typeType of the variable(s).
[in]_namesArray containing name labels for each component of the variable(s).
[in]_unitsArray containing unit labels for each component of the variable(s).
[in]_scalingArray containing the scaling for each component of the variable(s).
[in]_lbArray containing lower bounds for each component of the variable(s).
[in]_ubArray containing upper bounds for each component of the variable(s).
[in]_autoInitArray defining if each component of the variable(s) is to be automatically initialized.

Definition at line 54 of file matrix_variables_grid.cpp.

MatrixVariablesGrid::MatrixVariablesGrid ( uint  _nRows,
uint  _nCols,
uint  _nPoints,
VariableType  _type = VT_UNKNOWN,
const char **const  _names = 0,
const char **const  _units = 0,
const DVector *const  _scaling = 0,
const DVector *const  _lb = 0,
const DVector *const  _ub = 0,
const BooleanType *const  _autoInit = 0 
)

Constructor that takes the dimensions of each MatrixVariable as well as the number of grid points on which they are defined. Further information can optionally be specified.

Parameters
[in]_nRowsNumber of rows of each matrix.
[in]_nColsNumber of columns of each matrix.
[in]_nPointsNumber of grid points on which the MatrixVariable(s) are defined.
[in]_typeType of the variable(s).
[in]_namesArray containing name labels for each component of the variable(s).
[in]_unitsArray containing unit labels for each component of the variable(s).
[in]_scalingArray containing the scaling for each component of the variable(s).
[in]_lbArray containing lower bounds for each component of the variable(s).
[in]_ubArray containing upper bounds for each component of the variable(s).
[in]_autoInitArray defining if each component of the variable(s) is to be automatically initialized.

Definition at line 71 of file matrix_variables_grid.cpp.

MatrixVariablesGrid::MatrixVariablesGrid ( uint  _nRows,
uint  _nCols,
double  _firstTime,
double  _lastTime,
uint  _nPoints,
VariableType  _type = VT_UNKNOWN,
const char **const  _names = 0,
const char **const  _units = 0,
const DVector *const  _scaling = 0,
const DVector *const  _lb = 0,
const DVector *const  _ub = 0,
const BooleanType *const  _autoInit = 0 
)

Constructor that takes the dimensions of each MatrixVariable as well as the number of grid points on which they are defined. Moreover, it takes the time of the first and the last grid point; all intermediate grid points are setup to form a equidistant grid of time points. Further information can optionally be specified.

Parameters
[in]_nRowsNumber of rows of each matrix.
[in]_nColsNumber of columns of each matrix.
[in]_firstTimeTime of first grid point.
[in]_lastTimeTime of last grid point.
[in]_nPointsNumber of grid points on which the MatrixVariable(s) are defined.
[in]_typeType of the variable(s).
[in]_namesArray containing name labels for each component of the variable(s).
[in]_unitsArray containing unit labels for each component of the variable(s).
[in]_scalingArray containing the scaling for each component of the variable(s).
[in]_lbArray containing lower bounds for each component of the variable(s).
[in]_ubArray containing upper bounds for each component of the variable(s).
[in]_autoInitArray defining if each component of the variable(s) is to be automatically initialized.

Definition at line 88 of file matrix_variables_grid.cpp.

MatrixVariablesGrid::MatrixVariablesGrid ( const DMatrix arg,
const Grid _grid = trivialGrid,
VariableType  _type = VT_UNKNOWN 
)

Constructor that creates a variables grid on a given grid with given type. At each grid point, the MatrixVariable is constructed from the matrix passed.

Parameters
[in]argDMatrix to be assign at each point of the grid.
[in]_gridGrid on which the MatrixVariable(s) are defined.
[in]_typeType of the variable(s).

Definition at line 107 of file matrix_variables_grid.cpp.

MatrixVariablesGrid::MatrixVariablesGrid ( const MatrixVariablesGrid rhs)

Copy constructor (deep copy).

@param[in] rhs      Right-hand side object.

Definition at line 116 of file matrix_variables_grid.cpp.

MatrixVariablesGrid::~MatrixVariablesGrid ( )
virtual

Destructor.

Definition at line 129 of file matrix_variables_grid.cpp.

Member Function Documentation

returnValue MatrixVariablesGrid::addMatrix ( const DMatrix newMatrix,
double  newTime = -INFTY 
)

Adds a new grid point with given matrix and time to grid.

@param[in] newMatrix        DMatrix of grid point to be added.
@param[in] newTime          Time of grid point to be added.
Returns
SUCCESSFUL_RETURN,
RET_INVALID_ARGUMENTS

Definition at line 279 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::addMatrix ( const MatrixVariable newMatrix,
double  newTime = -INFTY 
)
protected

Adds a new grid point with given MatrixVariable and time to grid.

@param[in] newMatrix        MatrixVariable of grid point to be added.
@param[in] newTime          Time of grid point to be added.
Returns
SUCCESSFUL_RETURN,
RET_INVALID_ARGUMENTS

Definition at line 949 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::appendTimes ( const MatrixVariablesGrid arg,
MergeMethod  _mergeMethod = MM_DUPLICATE 
)

Appends grid point of given grid to object. A merge method defines the way duplicate entries are handled.

Parameters
[in]argGrid to append.
[in]_mergeMethodMerge method, see documentation of MergeMethod for details.
Returns
SUCCESSFUL_RETURN,
RET_INVALID_ARGUMENTS

Definition at line 344 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::appendValues ( const MatrixVariablesGrid arg)

Appends values at all grid points of given grid to object. Both grids need to be defined over identical grid points.

Parameters
[in]argGrid whose values are to appended.
Returns
SUCCESSFUL_RETURN,
RET_INVALID_ARGUMENTS

Definition at line 386 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::clearValues ( )
protected

Clears all MatrixVariables on the grid. Note that the grid itself is not cleared.

Returns
SUCCESSFUL_RETURN

Definition at line 894 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::coarsenGrid ( const Grid arg)

Coarsens the grid by removing all grid points of current grid that are not included in given grid. For doing so, the given grid has to be a subset of the current grid.

@param[in] arg                      Grid to be used for coarsening.

\return SUCCESSFUL_RETURN, \n
        RET_INVALID_ARGUMENTS

Definition at line 555 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::disableAutoInit ( )

Enables auto initialization at all grid points.

Returns
SUCCESSFUL_RETURN

Definition at line 1466 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::enableAutoInit ( )

Disables auto initialization at all grid points.

Returns
SUCCESSFUL_RETURN

Definition at line 1475 of file matrix_variables_grid.cpp.

BooleanType MatrixVariablesGrid::getAutoInit ( uint  pointIdx) const

Returns whether MatrixVariable at grid point with given index will be automatically initialized.

Parameters
[in]pointIdxIndex of grid point.
Returns
BT_TRUE iff MatrixVariable at given grid point will be automatically initialized,
BT_FALSE otherwise

Definition at line 1442 of file matrix_variables_grid.cpp.

MatrixVariablesGrid MatrixVariablesGrid::getCoarsenedGrid ( const Grid arg) const

Returns a coarsened grid by removing all grid points of current grid that are not included in given grid. For doing so, the given grid has to be a subset of the current grid.

@param[in] arg                      Grid to be used for coarsening.

\return Coarsened grid

Definition at line 608 of file matrix_variables_grid.cpp.

uint MatrixVariablesGrid::getDim ( ) const

Returns total dimension of MatrixVariablesGrid, i.e. the sum of dimensions of matrices at all grid point.

Returns
Total dimension of MatrixVariablesGrid

Definition at line 1128 of file matrix_variables_grid.cpp.

DMatrix MatrixVariablesGrid::getFirstMatrix ( ) const

Returns matrix at first grid point.

Returns
DMatrix at first grid point

Definition at line 325 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::getGrid ( Grid _grid) const

Returns the time grid of MatrixVariablesGrid.

@param[out] grid_           Time grid.

\return SUCCESSFUL_RETURN

Definition at line 1609 of file matrix_variables_grid.cpp.

DMatrix MatrixVariablesGrid::getLastMatrix ( ) const

Returns matrix at last grid point.

Returns
DMatrix at last grid point

Definition at line 334 of file matrix_variables_grid.cpp.

double MatrixVariablesGrid::getLowerBound ( uint  pointIdx,
uint  valueIdx 
) const

Returns lower bound of given component of MatrixVariable at grid point with given index.

Parameters
[in]pointIdxIndex of grid point.
[in]valueIdxIndex of component.
Returns
< INFTY: Lower bound of given component of MatrixVariable at given grid point,
INFTY: Index out of bounds

Definition at line 1365 of file matrix_variables_grid.cpp.

DVector MatrixVariablesGrid::getLowerBounds ( uint  pointIdx) const

Returns lower bounds of MatrixVariable at grid point with given index.

@param[in] pointIdx         Index of grid point.
Returns
Lower bounds of MatrixVariable at given grid point

Definition at line 1344 of file matrix_variables_grid.cpp.

DMatrix MatrixVariablesGrid::getMatrix ( uint  pointIdx) const

Returns matrix at grid point with given index.

@param[in] pointIdx         Index of grid point.
Returns
DMatrix at grid point with given index (empty if index is out of bounds)

Definition at line 313 of file matrix_variables_grid.cpp.

double MatrixVariablesGrid::getMax ( ) const

Returns maximum value over all matrices at all grid points.

Returns
Maximum value over all matrices at all grid points

Definition at line 1546 of file matrix_variables_grid.cpp.

double MatrixVariablesGrid::getMean ( ) const

Returns mean value over all matrices at all grid points.

Returns
Mean value over all matrices at all grid points

Definition at line 1574 of file matrix_variables_grid.cpp.

double MatrixVariablesGrid::getMin ( ) const

Returns minimum value over all matrices at all grid points.

Returns
Minimum value over all matrices at all grid points

Definition at line 1560 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::getName ( uint  pointIdx,
uint  idx,
char *const  _name 
) const

Returns name label of given component of MatrixVariable at grid point with given index.

@param[in]  pointIdx        Index of grid point.
@param[in]  idx                     Index of component.
@param[out] _name           Name label of given component at given grid point.
Returns
SUCCESSFUL_RETURN,
RET_INDEX_OUT_OF_BOUNDS,
RET_MEMBER_NOT_INITIALISED

Definition at line 1245 of file matrix_variables_grid.cpp.

uint MatrixVariablesGrid::getNumCols ( ) const

Returns number of columns of matrix at first grid point.

Returns
Number of columns of matrix at first grid point

Definition at line 1149 of file matrix_variables_grid.cpp.

uint MatrixVariablesGrid::getNumCols ( uint  pointIdx) const

Returns number of columns of matrix at grid point with given index.

@param[in] pointIdx         Index of grid point.
Returns
Number of columns of matrix at grid point with given index

Definition at line 1179 of file matrix_variables_grid.cpp.

uint MatrixVariablesGrid::getNumRows ( ) const

Returns number of rows of matrix at first grid point.

Returns
Number of rows of matrix at first grid point

Definition at line 1140 of file matrix_variables_grid.cpp.

uint MatrixVariablesGrid::getNumRows ( uint  pointIdx) const

Returns number of rows of matrix at grid point with given index.

@param[in] pointIdx         Index of grid point.
Returns
Number of rows of matrix at grid point with given index

Definition at line 1167 of file matrix_variables_grid.cpp.

uint MatrixVariablesGrid::getNumValues ( ) const

Returns number of values of matrix at first grid point.

Returns
Number of values of matrix at first grid point

Definition at line 1158 of file matrix_variables_grid.cpp.

uint MatrixVariablesGrid::getNumValues ( uint  pointIdx) const

Returns number of values of matrix at grid point with given index.

@param[in] pointIdx         Index of grid point.
Returns
Number of values of matrix at grid point with given index

Definition at line 1191 of file matrix_variables_grid.cpp.

MatrixVariablesGrid MatrixVariablesGrid::getRefinedGrid ( const Grid arg,
InterpolationMode  mode = IM_CONSTANT 
) const

Returns a refined grid by adding all grid points of given grid that are not yet included. For doing so, the given grid has to be a superset of the current grid. Values at newly added grid points are obtained by the (optionally) specified interpolation mode.

@param[in] arg                      Grid to be used for refinement.
@param[in] mode                     Interpolation mode, see documentation of InterpolationMode.

\return Refined grid

Definition at line 571 of file matrix_variables_grid.cpp.

DVector MatrixVariablesGrid::getScaling ( uint  pointIdx) const

Returns scaling of MatrixVariable at grid point with given index.

@param[in] pointIdx         Index of grid point.
Returns
Scaling of MatrixVariable at given grid point

Definition at line 1295 of file matrix_variables_grid.cpp.

double MatrixVariablesGrid::getScaling ( uint  pointIdx,
uint  valueIdx 
) const

Returns scaling of given component of MatrixVariable at grid point with given index.

Parameters
[in]pointIdxIndex of grid point.
[in]valueIdxIndex of component.
Returns
> 0.0: Scaling of given component of MatrixVariable at given grid point,
-1.0: Index out of bounds

Definition at line 1316 of file matrix_variables_grid.cpp.

Grid MatrixVariablesGrid::getTimePoints ( ) const

Returns (deep-copy of) time grid of MatrixVariablesGrid.

\note This routine is only introduced for user-convenience and
should not be used by developers aiming for maximum efficiency. 
Use routine getGrid() instead if efficiency is crucial.

\return SUCCESSFUL_RETURN

Definition at line 1616 of file matrix_variables_grid.cpp.

MatrixVariablesGrid MatrixVariablesGrid::getTimeSubGrid ( uint  startIdx,
uint  endIdx 
) const

Returns the sub grid in time starting and ending at given indices.

Parameters
[in]startIdxIndex of first grid point to be included in sub grid.
[in]endIdxIndex of last grid point to be included in sub grid.
Returns
Sub grid in time

Definition at line 499 of file matrix_variables_grid.cpp.

VariableType MatrixVariablesGrid::getType ( ) const

Returns variable type of MatrixVariable at first grid point.

Returns
Variable type of MatrixVariable at first grid point

Definition at line 1204 of file matrix_variables_grid.cpp.

VariableType MatrixVariablesGrid::getType ( uint  pointIdx) const

Returns variable type of MatrixVariable at grid point with given index.

@param[in] pointIdx         Index of grid point.
Returns
Variable type of MatrixVariable at grid point with given index

Definition at line 1223 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::getUnit ( uint  pointIdx,
uint  idx,
char *const  _unit 
) const

Returns current unit label of given component of MatrixVariable at grid point with given index.

@param[in]  pointIdx        Index of grid point.
@param[in]  idx                     Index of component.
@param[out] _unit           Unit label of given component at given grid point.
Returns
SUCCESSFUL_RETURN,
RET_INDEX_OUT_OF_BOUNDS,
RET_MEMBER_NOT_INITIALISED

Definition at line 1270 of file matrix_variables_grid.cpp.

double MatrixVariablesGrid::getUpperBound ( uint  pointIdx,
uint  valueIdx 
) const

Returns upper bound of given component of MatrixVariable at grid point with given index.

Parameters
[in]pointIdxIndex of grid point.
[in]valueIdxIndex of component.
Returns
> -INFTY: Upper bound of given component of MatrixVariable at given grid point,
-INFTY: Index out of bounds

Definition at line 1414 of file matrix_variables_grid.cpp.

DVector MatrixVariablesGrid::getUpperBounds ( uint  pointIdx) const

Returns upper bounds of MatrixVariable at grid point with given index.

@param[in] pointIdx         Index of grid point.
Returns
Upper bounds of MatrixVariable at given grid point

Definition at line 1393 of file matrix_variables_grid.cpp.

MatrixVariablesGrid MatrixVariablesGrid::getValuesSubGrid ( uint  startIdx,
uint  endIdx 
) const

Returns the sub grid of values. It comprises all grid points of the object, but comprises at each grid point only the compenents starting and ending at given indices.

Parameters
[in]startIdxIndex of first compenent to be included in sub grid.
[in]endIdxIndex of last compenent to be included in sub grid.
Note
This function implicitly assumes that matrices at all grid points have same number of components (or at least more than 'endIdx').
Returns
Sub grid of values

Definition at line 518 of file matrix_variables_grid.cpp.

BooleanType MatrixVariablesGrid::hasLowerBounds ( ) const

Returns whether MatrixVariablesGrid comprises lower bounds (at at least one of its grid points).

Returns
BT_TRUE iff MatrixVariablesGrid comprises lower bounds,
BT_FALSE otherwise

Definition at line 1521 of file matrix_variables_grid.cpp.

BooleanType MatrixVariablesGrid::hasNames ( ) const

Returns whether MatrixVariablesGrid comprises (non-empty) name labels (at at least one of its grid points).

Returns
BT_TRUE iff MatrixVariablesGrid comprises name labels,
BT_FALSE otherwise

Definition at line 1485 of file matrix_variables_grid.cpp.

BooleanType MatrixVariablesGrid::hasScaling ( ) const

Returns whether scaling is set (at at least one grid point).

Returns
BT_TRUE iff scaling is set,
BT_FALSE otherwise

Definition at line 1509 of file matrix_variables_grid.cpp.

BooleanType MatrixVariablesGrid::hasUnits ( ) const

Returns whether MatrixVariablesGrid comprises (non-empty) unit labels (at at least one of its grid points).

Returns
BT_TRUE iff MatrixVariablesGrid comprises unit labels,
BT_FALSE otherwise

Definition at line 1497 of file matrix_variables_grid.cpp.

BooleanType MatrixVariablesGrid::hasUpperBounds ( ) const

Returns whether MatrixVariablesGrid comprises upper bounds (at at least one of its grid points).

Returns
BT_TRUE iff MatrixVariablesGrid comprises upper bounds,
BT_FALSE otherwise

Definition at line 1533 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::init ( )

Initializes an empty MatrixVariablesGrid.

\return SUCCESSFUL_RETURN

Definition at line 175 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::init ( uint  _nRows,
uint  _nCols,
const Grid _grid,
VariableType  _type = VT_UNKNOWN,
const char **const  _names = 0,
const char **const  _units = 0,
const DVector *const  _scaling = 0,
const DVector *const  _lb = 0,
const DVector *const  _ub = 0,
const BooleanType *const  _autoInit = 0 
)

Initializes the MatrixVariablesGrid on a given grid with given dimensions of each MatrixVariable. Further information can optionally be specified.

Parameters
[in]_nRowsNumber of rows of each matrix.
[in]_nColsNumber of columns of each matrix.
[in]_gridGrid on which the MatrixVariable(s) are defined.
[in]_typeType of the variable(s).
[in]_namesArray containing name labels for each component of the variable(s).
[in]_unitsArray containing unit labels for each component of the variable(s).
[in]_scalingArray containing the scaling for each component of the variable(s).
[in]_lbArray containing lower bounds for each component of the variable(s).
[in]_ubArray containing upper bounds for each component of the variable(s).
[in]_autoInitArray defining if each component of the variable(s) is to be automatically initialized.
Returns
SUCCESSFUL_RETURN

Definition at line 184 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::init ( uint  _nRows,
uint  _nCols,
uint  _nPoints,
VariableType  _type = VT_UNKNOWN,
const char **const  _names = 0,
const char **const  _units = 0,
const DVector *const  _scaling = 0,
const DVector *const  _lb = 0,
const DVector *const  _ub = 0,
const BooleanType *const  _autoInit = 0 
)

Initializes the MatrixVariablesGrid taking the dimensions of each MatrixVariable as well as the number of grid points on which they are defined. Further information can optionally be specified.

Parameters
[in]_nRowsNumber of rows of each matrix.
[in]_nColsNumber of columns of each matrix.
[in]_nPointsNumber of grid points on which the MatrixVariable(s) are defined.
[in]_typeType of the variable(s).
[in]_namesArray containing name labels for each component of the variable(s).
[in]_unitsArray containing unit labels for each component of the variable(s).
[in]_scalingArray containing the scaling for each component of the variable(s).
[in]_lbArray containing lower bounds for each component of the variable(s).
[in]_ubArray containing upper bounds for each component of the variable(s).
[in]_autoInitArray defining if each component of the variable(s) is to be automatically initialized.
Returns
SUCCESSFUL_RETURN

Definition at line 208 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::init ( uint  _nRows,
uint  _nCols,
double  _firstTime,
double  _lastTime,
uint  _nPoints,
VariableType  _type = VT_UNKNOWN,
const char **const  _names = 0,
const char **const  _units = 0,
const DVector *const  _scaling = 0,
const DVector *const  _lb = 0,
const DVector *const  _ub = 0,
const BooleanType *const  _autoInit = 0 
)

Initializes the MatrixVariablesGrid taking the dimensions of each MatrixVariable as well as the number of grid points on which they are defined. Moreover, it takes the time of the first and the last grid point; all intermediate grid points are setup to form a equidistant grid of time points. Further information can optionally be specified.

Parameters
[in]_nRowsNumber of rows of each matrix.
[in]_nColsNumber of columns of each matrix.
[in]_firstTimeTime of first grid point.
[in]_lastTimeTime of last grid point.
[in]_nPointsNumber of grid points on which the MatrixVariable(s) are defined.
[in]_typeType of the variable(s).
[in]_namesArray containing name labels for each component of the variable(s).
[in]_unitsArray containing unit labels for each component of the variable(s).
[in]_scalingArray containing the scaling for each component of the variable(s).
[in]_lbArray containing lower bounds for each component of the variable(s).
[in]_ubArray containing upper bounds for each component of the variable(s).
[in]_autoInitArray defining if each component of the variable(s) is to be automatically initialized.
Returns
SUCCESSFUL_RETURN

Definition at line 232 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::init ( const DMatrix arg,
const Grid _grid = trivialGrid,
VariableType  _type = VT_UNKNOWN 
)

Initializes the MatrixVariablesGrid on a given grid with given type. At each grid point, the MatrixVariable is constructed from the matrix passed.

Parameters
[in]argDMatrix to be assign at each point of the grid.
[in]_gridGrid on which the MatrixVariable(s) are defined.
[in]_typeType of the variable(s).
Returns
SUCCESSFUL_RETURN

Definition at line 258 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::initMatrixVariables ( uint  _nRows,
uint  _nCols,
VariableType  _type = VT_UNKNOWN,
const char **const  _names = 0,
const char **const  _units = 0,
const DVector *const  _scaling = 0,
const DVector *const  _lb = 0,
const DVector *const  _ub = 0,
const BooleanType *const  _autoInit = 0 
)
protected

Initializes array of MatrixVariables with given information. Note that this function assumes that the grid has already been setup.

Parameters
[in]_nRowsNumber of rows of each matrix.
[in]_nColsNumber of columns of each matrix.
[in]_typeType of the variable(s).
[in]_namesArray containing names (labels) for each component of the variable(s).
[in]_unitsArray containing units for each component of the variable(s).
[in]_scalingArray containing the scaling for each component of the variable(s).
[in]_lbArray containing lower bounds for each component of the variable(s).
[in]_ubArray containing upper bounds for each component of the variable(s).
[in]_autoInitArray defining if each component of the variable(s) is to be automatically initialized.
Returns
SUCCESSFUL_RETURN

Definition at line 912 of file matrix_variables_grid.cpp.

DVector MatrixVariablesGrid::linearInterpolation ( double  time) const

Returns a vector with interpolated values of the MatrixVariablesGrid at given time. If given time lies in between two grid points, the value of the vector will be determined by linear interpolation between these grid points. If given time is smaller than the smallest time of the grid, the value of the first grid point will be returned. Analoguosly, if given time is larger than the largest time of the grid, the vector at the last grid point will be returned.

Parameters
[in]timeTime for evaluation.
Returns
DVector with interpolated values at given time

Definition at line 669 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::merge ( const MatrixVariablesGrid arg,
MergeMethod  _mergeMethod = MM_DUPLICATE,
BooleanType  keepOverlap = BT_TRUE 
)

Constructs the set union in time of current and given grid. A merge method defines the way duplicate entries are handled. Moreover, it can be specified whether an overlap in time of both grids shall be kept or if only the entries of one of them shall be kept according to the merge method.

Parameters
[in]argGrid to append.
[in]_mergeMethodMerge method, see documentation of MergeMethod for details.
[in]keepOverlapFlag indicating whether overlap shall be kept.
Returns
SUCCESSFUL_RETURN,
RET_INVALID_ARGUMENTS

Definition at line 404 of file matrix_variables_grid.cpp.

double & MatrixVariablesGrid::operator() ( uint  pointIdx,
uint  rowIdx,
uint  colIdx 
)

Returns the value of a certain component at a certain grid point.

    @param[in] pointIdx             Index of grid point.
    @param[in] rowIdx               Row index of the component to be returned.
    @param[in] colIdx               Column index of the component to be returned.
Returns
Value of component 'valueIdx' at grid point 'pointIdx'

Definition at line 1012 of file matrix_variables_grid.cpp.

double MatrixVariablesGrid::operator() ( uint  pointIdx,
uint  rowIdx,
uint  colIdx 
) const

Returns the value of a certain component at a certain grid point (const variant).

    @param[in] pointIdx             Index of grid point.
    @param[in] rowIdx               Row index of the component to be returned.
    @param[in] colIdx               Column index of the component to be returned.
Returns
Value of component 'valueIdx' at grid point 'pointIdx'

Definition at line 1021 of file matrix_variables_grid.cpp.

MatrixVariablesGrid MatrixVariablesGrid::operator() ( const uint  rowIdx) const

Returns a MatrixVariablesGrid consisting only of the given row.

    @param[in] rowIdx               Row index of the component to be returned.
Returns
MatrixVariablesGrid consisting only of the given row

Definition at line 1031 of file matrix_variables_grid.cpp.

MatrixVariablesGrid MatrixVariablesGrid::operator+ ( const MatrixVariablesGrid arg) const

Adds (element-wise) two MatrixVariablesGrid into a temporary object.

@param[in] arg              Second summand.
Returns
Temporary object containing sum of MatrixVariablesGrids.

Definition at line 1071 of file matrix_variables_grid.cpp.

MatrixVariablesGrid & MatrixVariablesGrid::operator+= ( const MatrixVariablesGrid arg)

Adds (element-wise) a MatrixVariablesGrid to object.

@param[in] arg              Second summand.
Returns
Reference to object after addition

Definition at line 1088 of file matrix_variables_grid.cpp.

MatrixVariablesGrid MatrixVariablesGrid::operator- ( const MatrixVariablesGrid arg) const

Subtracts (element-wise) a MatrixVariablesGrid from the object and stores result into a temporary object.

@param[in] arg              Subtrahend.
Returns
Temporary object containing the difference of the MatrixVariablesGrids

Definition at line 1101 of file matrix_variables_grid.cpp.

MatrixVariablesGrid & MatrixVariablesGrid::operator-= ( const MatrixVariablesGrid arg)

Subtracts (element-wise) a MatrixVariablesGrid from the object.

@param[in] arg              Subtrahend.
Returns
Reference to object after subtraction

Definition at line 1115 of file matrix_variables_grid.cpp.

MatrixVariablesGrid & MatrixVariablesGrid::operator= ( const MatrixVariablesGrid rhs)

Assignment operator (deep copy).

    @param[in] rhs  Right-hand side object.

Definition at line 136 of file matrix_variables_grid.cpp.

MatrixVariablesGrid & MatrixVariablesGrid::operator= ( const DMatrix rhs)

Assignment operator which reads data from a matrix. The data is interpreted as follows: the first entry of each row is taken as time of the grid point to be added, all remaining entries of each row are taken as numerical values of a MatrixVariable with exactly one column. In effect, a MatrixVariablesGrid consisting of <number of columns - 1>-by-1 MatrixVariables defined on <number of="" rows>=""> grid points is setup.

Parameters
[in]rhsDMatrix to be read.
Note
The file is closed at the end of routine.

Definition at line 158 of file matrix_variables_grid.cpp.

MatrixVariablesGrid MatrixVariablesGrid::operator[] ( const uint  pointIdx) const

Returns a MatrixVariablesGrid consisting only of the values at given grid point.

Parameters
[in]pointIdxIndex of grid point.
Returns
MatrixVariablesGrid consisting only of the values at given grid point

Definition at line 1053 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::print ( std::ostream &  stream = std::cout,
const char *const  name = DEFAULT_LABEL,
const char *const  startString = DEFAULT_START_STRING,
const char *const  endString = DEFAULT_END_STRING,
uint  width = DEFAULT_WIDTH,
uint  precision = DEFAULT_PRECISION,
const char *const  colSeparator = DEFAULT_COL_SEPARATOR,
const char *const  rowSeparator = DEFAULT_ROW_SEPARATOR 
) const

Prints object to standard ouput stream. Various settings can be specified defining its output format.

Parameters
[in]streamOutput stream for printing.
[in]nameName label to be printed before the numerical values.
[in]startStringPrefix before printing the numerical values.
[in]endStringSuffix after printing the numerical values.
[in]widthTotal number of digits per single numerical value.
[in]precisionNumber of decimals per single numerical value.
[in]colSeparatorSeparator between the columns of the numerical values.
[in]rowSeparatorSeparator between the rows of the numerical values.
Returns
SUCCESSFUL_RETURN,
RET_UNKNOWN_BUG

Definition at line 695 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::print ( const char *const  filename,
const char *const  name = DEFAULT_LABEL,
const char *const  startString = DEFAULT_START_STRING,
const char *const  endString = DEFAULT_END_STRING,
uint  width = DEFAULT_WIDTH,
uint  precision = DEFAULT_PRECISION,
const char *const  colSeparator = DEFAULT_COL_SEPARATOR,
const char *const  rowSeparator = DEFAULT_ROW_SEPARATOR 
) const

Prints object to file with given name. Various settings can be specified defining its output format.

Parameters
[in]filenameFilename for printing.
[in]nameName label to be printed before the numerical values.
[in]startStringPrefix before printing the numerical values.
[in]endStringSuffix after printing the numerical values.
[in]widthTotal number of digits per single numerical value.
[in]precisionNumber of decimals per single numerical value.
[in]colSeparatorSeparator between the columns of the numerical values.
[in]rowSeparatorSeparator between the rows of the numerical values.
Returns
SUCCESSFUL_RETURN,
RET_UNKNOWN_BUG

Definition at line 736 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::print ( const char *const  filename,
const char *const  name,
PrintScheme  printScheme 
) const

Prints object to file with given name. Various settings can be specified defining its output format.

Parameters
[in]filenameFilename for printing.
[in]nameName label to be printed before the numerical values.
[in]printSchemePrint scheme defining the output format of the information.
Returns
SUCCESSFUL_RETURN,
RET_FILE_CAN_NOT_BE_OPENED,
RET_UNKNOWN_BUG

Definition at line 760 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::print ( std::ostream &  stream,
const char *const  name,
PrintScheme  printScheme 
) const

Prints object to given file. Various settings can be specified defining its output format.

Parameters
[in]streamOutput stream for printing.
[in]nameName label to be printed before the numerical values.
[in]printSchemePrint scheme defining the output format of the information.
Returns
SUCCESSFUL_RETURN,
RET_FILE_CAN_NOT_BE_OPENED,
RET_UNKNOWN_BUG

Definition at line 778 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::read ( std::istream &  stream)

A fuction that reads data from a file. The data is expected to be in matrix format and is interpreted as follows: the first entry of each row is taken as time of the grid point to be added, all remaining entries of each row are taken as numerical values of a MatrixVariable with exactly one column. In effect, a MatrixVariablesGrid consisting of <number of columns - 1>-by-1 MatrixVariables defined on <number of="" rows>=""> grid points is setup. Note that all rows are expected to have equal number of columns.

Parameters
[in]streamAn input stream to be read.
Note
The routine is significantly different from the constructor that takes a single matrix.

Definition at line 831 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::read ( const char *const  filename)

A function that reads data from a file with given name. The data is expected to be in matrix format and is interpreted as follows: the first entry of each row is taken as time of the grid point to be added, all remaining entries of each row are taken as numerical values of a MatrixVariable with exactly one column. In effect, a MatrixVariablesGrid consisting of <number of columns - 1>-by-1 MatrixVariables defined on <number of="" rows>=""> grid points is setup. Note that all rows are expected to have equal number of columns.

Parameters
[in]filenameName of file to be read.
Note
The routine is significantly different from the constructor that takes a single matrix.

Definition at line 859 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::refineGrid ( const Grid arg,
InterpolationMode  mode = IM_CONSTANT 
)

Refines the grid by adding all grid points of given grid that are not not yet included. For doing so, the given grid has to be a superset of the current grid. Values at newly added grid points are obtained by the (optionally) specified interpolation mode.

@param[in] arg                      Grid to be used for refinement.
@param[in] mode                     Interpolation mode, see documentation of InterpolationMode.

\return SUCCESSFUL_RETURN, \n
        RET_INVALID_ARGUMENTS

Definition at line 538 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::setAll ( double  _value)

Assigns given value to all components of all matrices at all grid points.

@param[in] _value           New value.
Returns
SUCCESSFUL_RETURN

Definition at line 1598 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::setAllMatrices ( const DMatrix _values)

Assigns new matrix to all grid points.

@param[in] _value           New matrix.
Returns
SUCCESSFUL_RETURN,
RET_INDEX_OUT_OF_BOUNDS

Definition at line 303 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::setAutoInit ( uint  pointIdx,
BooleanType  _autoInit 
)

Assigns new auto initialization flag to MatrixVariable at grid point with given index.

Parameters
[in]pointIdxIndex of grid point.
[in]_autoInitNew auto initialization flag.
Returns
SUCCESSFUL_RETURN,
RET_INDEX_OUT_OF_BOUNDS

Definition at line 1455 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::setLowerBound ( uint  pointIdx,
uint  valueIdx,
double  _lb 
)

Assigns new lower bound to given component of MatrixVariable at grid point with given index.

Parameters
[in]pointIdxIndex of grid point.
[in]valueIdxIndex of component.
[in]_lbNew lower bound.
Returns
SUCCESSFUL_RETURN,
RET_INDEX_OUT_OF_BOUNDS

Definition at line 1376 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::setLowerBounds ( uint  pointIdx,
const DVector _lb 
)

Assigns new lower bounds to MatrixVariable at grid point with given index.

@param[in] pointIdx         Index of grid point.
@param[in] _lb                      New lower bounds.
Returns
SUCCESSFUL_RETURN,
RET_INDEX_OUT_OF_BOUNDS

Definition at line 1354 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::setMatrix ( uint  pointIdx,
const DMatrix _value 
) const

Assigns new matrix to grid point with given index.

@param[in] pointIdx         Index of grid point.
@param[in] _value           New matrix.
Returns
SUCCESSFUL_RETURN,
RET_INDEX_OUT_OF_BOUNDS

Definition at line 288 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::setName ( uint  pointIdx,
uint  idx,
const char *const  _name 
)

Assigns new name label to given component of MatrixVariable at grid point with given index.

@param[in]  pointIdx        Index of grid point.
@param[in]  idx                     Index of component.
@param[in]  _name           New name label of given component at given grid point.
Returns
SUCCESSFUL_RETURN,
RET_INDEX_OUT_OF_BOUNDS,
RET_MEMBER_NOT_INITIALISED

Definition at line 1257 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::setScaling ( uint  pointIdx,
const DVector _scaling 
)

Assigns new scaling to MatrixVariable at grid point with given index.

@param[in] pointIdx         Index of grid point.
@param[in] _scaling         New scaling.
Returns
SUCCESSFUL_RETURN,
RET_INDEX_OUT_OF_BOUNDS,
RET_INVALID_ARGUMENTS

Definition at line 1305 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::setScaling ( uint  pointIdx,
uint  valueIdx,
double  _scaling 
)

Assigns new scaling to given component of MatrixVariable at grid point with given index.

Parameters
[in]pointIdxIndex of grid point.
[in]valueIdxIndex of component.
[in]_scalingNew scaling.
Returns
SUCCESSFUL_RETURN,
RET_INDEX_OUT_OF_BOUNDS,
RET_INVALID_ARGUMENTS

Definition at line 1327 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::setType ( VariableType  _type)

Assigns new variable type at all grid points.

@param[in] _type            Type of the variable(s).
Returns
SUCCESSFUL_RETURN

Definition at line 1213 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::setType ( uint  pointIdx,
VariableType  _type 
)

Assigns new variable type to MatrixVariable at grid point with given index.

@param[in] pointIdx         Index of grid point.
@param[in] _type            New type of the variable(s).
Returns
SUCCESSFUL_RETURN,
RET_INDEX_OUT_OF_BOUNDS

Definition at line 1233 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::setUnit ( uint  pointIdx,
uint  idx,
const char *const  _unit 
)

Assigns new name label to given component of MatrixVariable at grid point with given index.

@param[in]  pointIdx        Index of grid point.
@param[in]  idx                     Index of component.
@param[in]  _unit           New unit label of given component at given grid point.
Returns
SUCCESSFUL_RETURN,
RET_INDEX_OUT_OF_BOUNDS,
RET_MEMBER_NOT_INITIALISED

Definition at line 1282 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::setUpperBound ( uint  pointIdx,
uint  valueIdx,
double  _ub 
)

Assigns new upper bound to given component of MatrixVariable at grid point with given index.

Parameters
[in]pointIdxIndex of grid point.
[in]valueIdxIndex of component.
[in]_ubNew upper bound.
Returns
SUCCESSFUL_RETURN,
RET_INDEX_OUT_OF_BOUNDS

Definition at line 1425 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::setUpperBounds ( uint  pointIdx,
const DVector _ub 
)

Assigns new upper bounds to MatrixVariable at grid point with given index.

@param[in] pointIdx         Index of grid point.
@param[in] _ub                      New upper bounds.
Returns
SUCCESSFUL_RETURN,
RET_INDEX_OUT_OF_BOUNDS

Definition at line 1403 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::setZero ( )

Assigns zero to all components of all matrices at all grid points.

Returns
SUCCESSFUL_RETURN

Definition at line 1589 of file matrix_variables_grid.cpp.

MatrixVariablesGrid & MatrixVariablesGrid::shiftBackwards ( DMatrix  lastValue = emptyMatrix)

Shifts all grid points backwards by one grid point, deleting the first one and doubling the value at last grid point.

Returns
Reference to object with shifted points

Definition at line 650 of file matrix_variables_grid.cpp.

MatrixVariablesGrid & MatrixVariablesGrid::shiftTimes ( double  timeShift)

Shifts times at all grid points by a given offset.

@param[in] timeShift        Time offset for shifting.
Returns
Reference to object with shifted times

Definition at line 642 of file matrix_variables_grid.cpp.

returnValue MatrixVariablesGrid::sprint ( std::ostream &  stream)

A printing function needed for plotting.

Definition at line 965 of file matrix_variables_grid.cpp.

Friends And Related Function Documentation

std::ostream& operator<< ( std::ostream &  stream,
const MatrixVariablesGrid arg 
)
friend

Output streaming operator.

Definition at line 874 of file matrix_variables_grid.cpp.

std::istream& operator>> ( std::istream &  stream,
MatrixVariablesGrid arg 
)
friend

Read a MatrixVariablesGrid from an input stream.

Definition at line 882 of file matrix_variables_grid.cpp.

Member Data Documentation

MatrixVariable** MatrixVariablesGrid::values
protected

DMatrix-valued optimization variable at all grid points.

Definition at line 1234 of file matrix_variables_grid.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