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

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

#include <variables_grid.hpp>

Inheritance diagram for VariablesGrid:
Inheritance graph
[legend]

Public Member Functions

returnValue addVector (const DVector &newVector, double newTime=-INFTY)
 
returnValue appendTimes (const VariablesGrid &arg, MergeMethod _mergeMethod=MM_DUPLICATE)
 
returnValue appendTimes (const DMatrix &arg, MergeMethod _mergeMethod=MM_DUPLICATE)
 
returnValue appendValues (const VariablesGrid &arg)
 
DVector getFirstVector () const
 
returnValue getIntegral (InterpolationMode mode, DVector &value) const
 
DVector getLastVector () const
 
returnValue getSum (DVector &sum) const
 
VariablesGrid getTimeSubGrid (uint startIdx, uint endIdx) const
 
VariablesGrid getTimeSubGrid (double startTime, double endTime) const
 
VariablesGrid getValuesSubGrid (uint startIdx, uint endIdx) const
 
DVector getVector (uint pointIdx) const
 
returnValue init ()
 
returnValue init (uint _dim, 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 _dim, 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 _dim, 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 DVector &arg, const Grid &_grid=trivialGrid, VariableType _type=VT_UNKNOWN)
 
returnValue merge (const VariablesGrid &arg, MergeMethod _mergeMethod=MM_DUPLICATE, BooleanType keepOverlap=BT_TRUE)
 
 operator DMatrix () const
 
double & operator() (uint pointIdx, uint rowIdx)
 
double operator() (uint pointIdx, uint rowIdx) const
 
VariablesGrid operator() (const uint rowIdx) const
 
VariablesGrid operator+ (const VariablesGrid &arg) const
 
VariablesGridoperator+= (const VariablesGrid &arg)
 
VariablesGrid operator- (const VariablesGrid &arg) const
 
VariablesGridoperator-= (const VariablesGrid &arg)
 
VariablesGridoperator= (const VariablesGrid &rhs)
 
VariablesGridoperator= (const MatrixVariablesGrid &rhs)
 
VariablesGridoperator= (const DMatrix &rhs)
 
BooleanType operator== (const VariablesGrid &arg) const
 
VariablesGrid operator[] (const uint pointIdx) const
 
returnValue setAllVectors (const DVector &_values)
 
returnValue setVector (uint pointIdx, const DVector &_values)
 
VariablesGridshiftBackwards (DVector lastValue=emptyVector)
 
VariablesGridshiftTimes (double timeShift)
 
 VariablesGrid ()
 
 VariablesGrid (uint _dim, 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)
 
 VariablesGrid (uint _dim, 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)
 
 VariablesGrid (uint _dim, 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)
 
 VariablesGrid (const DVector &arg, const Grid &_grid=trivialGrid, VariableType _type=VT_UNKNOWN)
 
 VariablesGrid (const DMatrix &arg, VariableType _type=VT_UNKNOWN)
 
 VariablesGrid (const VariablesGrid &rhs)
 
 VariablesGrid (const MatrixVariablesGrid &rhs)
 
 ~VariablesGrid ()
 
- Public Member Functions inherited from MatrixVariablesGrid
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 initializeFromBounds ()
 
- Protected Member Functions inherited from MatrixVariablesGrid
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)
 

Friends

class OptimizationAlgorithm
 
class OptimizationAlgorithmBase
 
class RealTimeAlgorithm
 

Additional Inherited Members

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

Detailed Description

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

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

The class specalizes the MatrixVariablesGrid class to vectors represented internally as matrices with exactly one column.

Author
Hans Joachim Ferreau, Boris Houska

Definition at line 56 of file variables_grid.hpp.

Constructor & Destructor Documentation

BEGIN_NAMESPACE_ACADO VariablesGrid::VariablesGrid ( )

Default constructor.

Definition at line 46 of file variables_grid.cpp.

VariablesGrid::VariablesGrid ( uint  _dim,
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 dimension of each vector-valued MatrixVariable as well as the grid on which they are defined. Further information can optionally be specified.

Parameters
[in]_dimDimension of each vector.
[in]_gridGrid on which the vector-valued MatrixVariable(s) are defined.
[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.

Definition at line 51 of file variables_grid.cpp.

VariablesGrid::VariablesGrid ( uint  _dim,
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 dimension of each vector-valued MatrixVariable as well as the number of grid points on which they are defined. Further information can optionally be specified.

Parameters
[in]_dimDimension of each vector.
[in]_nPointsNumber of grid points on which the vector-valued MatrixVariable(s) are defined.
[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.

Definition at line 65 of file variables_grid.cpp.

VariablesGrid::VariablesGrid ( uint  _dim,
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 vector-valued 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]_dimDimension of each vector.
[in]_firstTimeTime of first grid point.
[in]_lastTimeTime of last grid point.
[in]_nPointsNumber of grid points on which the vector-valued MatrixVariable(s) are defined.
[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.

Definition at line 79 of file variables_grid.cpp.

VariablesGrid::VariablesGrid ( const DVector arg,
const Grid _grid = trivialGrid,
VariableType  _type = VT_UNKNOWN 
)

Constructor that creates a VariablesGrid on a given grid with given type. At each grid point, the vector-valued MatrixVariable is constructed from the vector passed.

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

Definition at line 95 of file variables_grid.cpp.

VariablesGrid::VariablesGrid ( const DMatrix arg,
VariableType  _type = VT_UNKNOWN 
)

Constructor which reads data from a matrix. 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 vector-valued 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]fileFile to be read.
Note
The file is closed at the end of routine.

Definition at line 103 of file variables_grid.cpp.

VariablesGrid::VariablesGrid ( const VariablesGrid rhs)

Copy constructor (deep copy).

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

Definition at line 119 of file variables_grid.cpp.

VariablesGrid::VariablesGrid ( const MatrixVariablesGrid rhs)

Copy constructor (deep copy).

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

Definition at line 125 of file variables_grid.cpp.

VariablesGrid::~VariablesGrid ( )

Destructor.

Definition at line 133 of file variables_grid.cpp.

Member Function Documentation

returnValue VariablesGrid::addVector ( const DVector newVector,
double  newTime = -INFTY 
)

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

@param[in] newVector        DVector 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 271 of file variables_grid.cpp.

returnValue VariablesGrid::appendTimes ( const VariablesGrid 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 362 of file variables_grid.cpp.

returnValue VariablesGrid::appendTimes ( const DMatrix 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 matrix form.
[in]_mergeMethodMerge method, see documentation of MergeMethod for details.
Returns
SUCCESSFUL_RETURN,
RET_INVALID_ARGUMENTS

Definition at line 412 of file variables_grid.cpp.

returnValue VariablesGrid::appendValues ( const VariablesGrid 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 421 of file variables_grid.cpp.

DVector VariablesGrid::getFirstVector ( ) const

Returns vector at first grid point.

Returns
DVector at first grid point

Definition at line 316 of file variables_grid.cpp.

returnValue VariablesGrid::getIntegral ( InterpolationMode  mode,
DVector value 
) const

Returns a component-wise approximation of the integral over all vectors at all grid points.

@param[in]  mode    Specifies how the vector-values are interpolated for approximating the integral, see documentation of InterpolationMode for details.
@param[out] value   Component-wise approximation of the integral over all vectors at all grid points.
Returns
SUCCESSFUL_RETURN

Definition at line 625 of file variables_grid.cpp.

DVector VariablesGrid::getLastVector ( ) const

Returns vector at first grid point.

Returns
DVector at first grid point

Definition at line 325 of file variables_grid.cpp.

returnValue VariablesGrid::getSum ( DVector sum) const

Returns the component-wise sum over all vectors at all grid points.

@param[out] sum             Component-wise sum over all vectors at all grid points.
Returns
SUCCESSFUL_RETURN

Definition at line 613 of file variables_grid.cpp.

VariablesGrid VariablesGrid::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 542 of file variables_grid.cpp.

VariablesGrid VariablesGrid::getTimeSubGrid ( double  startTime,
double  endTime 
) const

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

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

Definition at line 561 of file variables_grid.cpp.

VariablesGrid VariablesGrid::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 vectors at all grid points have same number of components (or at least more than 'endIdx').
Returns
Sub grid of values

Definition at line 593 of file variables_grid.cpp.

DVector VariablesGrid::getVector ( uint  pointIdx) const

Returns vector at grid point with given index.

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

Definition at line 306 of file variables_grid.cpp.

returnValue VariablesGrid::init ( )

Initializes an empty VariablesGrid.

\return SUCCESSFUL_RETURN

Definition at line 208 of file variables_grid.cpp.

returnValue VariablesGrid::init ( uint  _dim,
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 VariablesGrid on a given grid with given dimension of each vector-valued MatrixVariable. Further information can optionally be specified.

Parameters
[in]_dimDimension of each vector.
[in]_gridGrid on which the vector-valued MatrixVariable(s) are defined.
[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 214 of file variables_grid.cpp.

returnValue VariablesGrid::init ( uint  _dim,
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 VariablesGrid taking the dimension of each vector-valued MatrixVariable as well as the number of grid points on which they are defined. Further information can optionally be specified.

Parameters
[in]_dimDimension of each vector.
[in]_nPointsNumber of grid points on which the vector-valued MatrixVariable(s) are defined.
[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 229 of file variables_grid.cpp.

returnValue VariablesGrid::init ( uint  _dim,
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 dimension of each vector-valued 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]_dimDimension of each vector.
[in]_firstTimeTime of first grid point.
[in]_lastTimeTime of last grid point.
[in]_nPointsNumber of grid points on which the vector-valued MatrixVariable(s) are defined.
[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 244 of file variables_grid.cpp.

returnValue VariablesGrid::init ( const DVector arg,
const Grid _grid = trivialGrid,
VariableType  _type = VT_UNKNOWN 
)

Initializes the VariablesGrid on a given grid with given type. At each grid point, the vector-valued MatrixVariable is constructed from the matrix passed.

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

Definition at line 261 of file variables_grid.cpp.

returnValue VariablesGrid::initializeFromBounds ( )
protected

Initializes the grid vector by taking average between upper and lower bound. If one of these bounds is infinity it is initialized with the bound. If both bounds are infinity it is initialized with 0. This routine is only for internal use by the OptimizationAlgorithm, that is a friend of this class.

Returns
SUCCESSFUL_RETURN

Definition at line 666 of file variables_grid.cpp.

returnValue VariablesGrid::merge ( const VariablesGrid 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 446 of file variables_grid.cpp.

VariablesGrid::operator DMatrix ( ) const

Definition at line 703 of file variables_grid.cpp.

double& VariablesGrid::operator() ( uint  pointIdx,
uint  rowIdx 
)
inline

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.
Returns
Value of component 'rowIdx' at grid point 'pointIdx'
double VariablesGrid::operator() ( uint  pointIdx,
uint  rowIdx 
) const
inline

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.
Returns
Value of component 'rowIdx' at grid point 'pointIdx'
VariablesGrid VariablesGrid::operator() ( const uint  rowIdx) const

Returns a VariablesGrid consisting only of the given row.

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

Definition at line 169 of file variables_grid.cpp.

VariablesGrid VariablesGrid::operator+ ( const VariablesGrid arg) const
inline

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

@param[in] arg              Second summand.
Returns
Temporary object containing sum of VariablesGrids.
VariablesGrid& VariablesGrid::operator+= ( const VariablesGrid arg)
inline

Adds (element-wise) a VariablesGrid to object.

@param[in] arg              Second summand.
Returns
Reference to object after addition
VariablesGrid VariablesGrid::operator- ( const VariablesGrid arg) const
inline

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

@param[in] arg              Subtrahend.
Returns
Temporary object containing the difference of the VariablesGrids
VariablesGrid& VariablesGrid::operator-= ( const VariablesGrid arg)
inline

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

@param[in] arg              Subtrahend.
Returns
Reference to object after subtraction
VariablesGrid & VariablesGrid::operator= ( const VariablesGrid rhs)

Assignment operator (deep copy).

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

Definition at line 138 of file variables_grid.cpp.

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

Assignment operator (deep copy).

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

Definition at line 149 of file variables_grid.cpp.

VariablesGrid & VariablesGrid::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 vector-valued 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 162 of file variables_grid.cpp.

BooleanType VariablesGrid::operator== ( const VariablesGrid arg) const
inline

Tests for equality,

@param[in] rhs      Object of comparison.
Returns
BT_TRUE iff both objects are equal,
BT_FALSE otherwise
VariablesGrid VariablesGrid::operator[] ( const uint  pointIdx) const

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

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

Definition at line 191 of file variables_grid.cpp.

returnValue VariablesGrid::setAllVectors ( const DVector _values)

Assigns new vector to all grid points.

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

Definition at line 296 of file variables_grid.cpp.

returnValue VariablesGrid::setVector ( uint  pointIdx,
const DVector _values 
)

Assigns new vector to grid point with given index.

@param[in] pointIdx         Index of grid point.
@param[in] _value           New vector.
Returns
SUCCESSFUL_RETURN,
RET_INDEX_OUT_OF_BOUNDS,
RET_VECTOR_DIMENSION_MISMATCH
Parameters
pointIdxIndex of the grid point.
_valuesNew values of the sub-vector.

Definition at line 279 of file variables_grid.cpp.

VariablesGrid & VariablesGrid::shiftBackwards ( DVector  lastValue = emptyVector)

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 343 of file variables_grid.cpp.

VariablesGrid & VariablesGrid::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 335 of file variables_grid.cpp.

Friends And Related Function Documentation

friend class OptimizationAlgorithm
friend

Definition at line 59 of file variables_grid.hpp.

friend class OptimizationAlgorithmBase
friend

Definition at line 58 of file variables_grid.hpp.

friend class RealTimeAlgorithm
friend

Definition at line 60 of file 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:27