Provides a time grid consisting of vector-valued optimization variables at each grid point. More...
#include <variables_grid.hpp>
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 |
VariablesGrid & | operator+= (const VariablesGrid &arg) |
VariablesGrid | operator- (const VariablesGrid &arg) const |
VariablesGrid & | operator-= (const VariablesGrid &arg) |
VariablesGrid & | operator= (const VariablesGrid &rhs) |
VariablesGrid & | operator= (const MatrixVariablesGrid &rhs) |
VariablesGrid & | operator= (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) |
VariablesGrid & | shiftBackwards (DVector lastValue=emptyVector) |
VariablesGrid & | shiftTimes (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 () | |
Protected Member Functions | |
returnValue | initializeFromBounds () |
Friends | |
class | OptimizationAlgorithm |
class | OptimizationAlgorithmBase |
class | RealTimeAlgorithm |
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.
Definition at line 56 of file variables_grid.hpp.
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.
[in] | _dim | Dimension of each vector. |
[in] | _grid | Grid on which the vector-valued MatrixVariable(s) are defined. |
[in] | _type | Type of the variable(s). |
[in] | _names | Array containing names (labels) for each component of the variable(s). |
[in] | _units | Array containing units for each component of the variable(s). |
[in] | _scaling | Array containing the scaling for each component of the variable(s). |
[in] | _lb | Array containing lower bounds for each component of the variable(s). |
[in] | _ub | Array containing upper bounds for each component of the variable(s). |
[in] | _autoInit | Array 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.
[in] | _dim | Dimension of each vector. |
[in] | _nPoints | Number of grid points on which the vector-valued MatrixVariable(s) are defined. |
[in] | _type | Type of the variable(s). |
[in] | _names | Array containing names (labels) for each component of the variable(s). |
[in] | _units | Array containing units for each component of the variable(s). |
[in] | _scaling | Array containing the scaling for each component of the variable(s). |
[in] | _lb | Array containing lower bounds for each component of the variable(s). |
[in] | _ub | Array containing upper bounds for each component of the variable(s). |
[in] | _autoInit | Array 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.
[in] | _dim | Dimension of each vector. |
[in] | _firstTime | Time of first grid point. |
[in] | _lastTime | Time of last grid point. |
[in] | _nPoints | Number of grid points on which the vector-valued MatrixVariable(s) are defined. |
[in] | _type | Type of the variable(s). |
[in] | _names | Array containing names (labels) for each component of the variable(s). |
[in] | _units | Array containing units for each component of the variable(s). |
[in] | _scaling | Array containing the scaling for each component of the variable(s). |
[in] | _lb | Array containing lower bounds for each component of the variable(s). |
[in] | _ub | Array containing upper bounds for each component of the variable(s). |
[in] | _autoInit | Array 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.
[in] | arg | DVector to be assign at each point of the grid. |
[in] | _grid | Grid on which the vector-valued MatrixVariable(s) are defined. |
[in] | _type | Type 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.
[in] | file | File to be read. |
Definition at line 103 of file variables_grid.cpp.
VariablesGrid::VariablesGrid | ( | const VariablesGrid & | rhs | ) |
Copy constructor (deep copy).
[in] | rhs | Right-hand side object. |
Definition at line 119 of file variables_grid.cpp.
VariablesGrid::VariablesGrid | ( | const MatrixVariablesGrid & | rhs | ) |
Copy constructor (deep copy).
[in] | rhs | Right-hand side object. |
Definition at line 125 of file variables_grid.cpp.
Destructor.
Definition at line 133 of file variables_grid.cpp.
returnValue VariablesGrid::addVector | ( | const DVector & | newVector, |
double | newTime = -INFTY |
||
) |
Adds a new grid point with given vector and time to grid.
[in] | newVector | DVector of grid point to be added. |
[in] | newTime | Time of grid point to be added. |
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.
[in] | arg | Grid to append. |
[in] | _mergeMethod | Merge method, see documentation of MergeMethod for details. |
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.
[in] | arg | Grid to append in matrix form. |
[in] | _mergeMethod | Merge method, see documentation of MergeMethod for details. |
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.
[in] | arg | Grid whose values are to appended. |
Definition at line 421 of file variables_grid.cpp.
DVector VariablesGrid::getFirstVector | ( | ) | const |
Returns vector 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.
[in] | mode | Specifies how the vector-values are interpolated for approximating the integral, see documentation of InterpolationMode for details. |
[out] | value | Component-wise approximation of the integral over all vectors at all grid points. |
Definition at line 625 of file variables_grid.cpp.
DVector VariablesGrid::getLastVector | ( | ) | const |
Returns vector 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.
[out] | sum | Component-wise sum over all vectors at all grid points. |
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.
[in] | startIdx | Index of first grid point to be included in sub grid. |
[in] | endIdx | Index of last grid point to be included in sub grid. |
Reimplemented from MatrixVariablesGrid.
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.
[in] | startTime | Time of first grid point to be included in sub grid. |
[in] | endTime | Time of last grid point to be included in sub grid. |
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.
[in] | startIdx | Index of first compenent to be included in sub grid. |
[in] | endIdx | Index of last compenent to be included in sub grid. |
Reimplemented from MatrixVariablesGrid.
Definition at line 593 of file variables_grid.cpp.
DVector VariablesGrid::getVector | ( | uint | pointIdx | ) | const |
Returns vector at grid point with given index.
[in] | pointIdx | Index of grid point. |
Definition at line 306 of file variables_grid.cpp.
Initializes an empty VariablesGrid.
Reimplemented from MatrixVariablesGrid.
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.
[in] | _dim | Dimension of each vector. |
[in] | _grid | Grid on which the vector-valued MatrixVariable(s) are defined. |
[in] | _type | Type of the variable(s). |
[in] | _names | Array containing names (labels) for each component of the variable(s). |
[in] | _units | Array containing units for each component of the variable(s). |
[in] | _scaling | Array containing the scaling for each component of the variable(s). |
[in] | _lb | Array containing lower bounds for each component of the variable(s). |
[in] | _ub | Array containing upper bounds for each component of the variable(s). |
[in] | _autoInit | Array defining if each component of the variable(s) is to be automatically initialized. |
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.
[in] | _dim | Dimension of each vector. |
[in] | _nPoints | Number of grid points on which the vector-valued MatrixVariable(s) are defined. |
[in] | _type | Type of the variable(s). |
[in] | _names | Array containing names (labels) for each component of the variable(s). |
[in] | _units | Array containing units for each component of the variable(s). |
[in] | _scaling | Array containing the scaling for each component of the variable(s). |
[in] | _lb | Array containing lower bounds for each component of the variable(s). |
[in] | _ub | Array containing upper bounds for each component of the variable(s). |
[in] | _autoInit | Array defining if each component of the variable(s) is to be automatically initialized. |
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.
[in] | _dim | Dimension of each vector. |
[in] | _firstTime | Time of first grid point. |
[in] | _lastTime | Time of last grid point. |
[in] | _nPoints | Number of grid points on which the vector-valued MatrixVariable(s) are defined. |
[in] | _type | Type of the variable(s). |
[in] | _names | Array containing names (labels) for each component of the variable(s). |
[in] | _units | Array containing units for each component of the variable(s). |
[in] | _scaling | Array containing the scaling for each component of the variable(s). |
[in] | _lb | Array containing lower bounds for each component of the variable(s). |
[in] | _ub | Array containing upper bounds for each component of the variable(s). |
[in] | _autoInit | Array defining if each component of the variable(s) is to be automatically initialized. |
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.
[in] | arg | DVector to be assign at each point of the grid. |
[in] | _grid | Grid on which the vector-valued MatrixVariable(s) are defined. |
[in] | _type | Type of the variable(s). |
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.
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.
[in] | arg | Grid to append. |
[in] | _mergeMethod | Merge method, see documentation of MergeMethod for details. |
[in] | keepOverlap | Flag indicating whether overlap shall be kept. |
Definition at line 446 of file variables_grid.cpp.
VariablesGrid::operator DMatrix | ( | ) | const |
Definition at line 703 of file variables_grid.cpp.
Returns the value of a certain component at a certain grid point.
[in] | pointIdx | Index of grid point. |
[in] | rowIdx | Row index of the component to be returned. |
Returns the value of a certain component at a certain grid point.
[in] | pointIdx | Index of grid point. |
[in] | rowIdx | Row index of the component to be returned. |
VariablesGrid VariablesGrid::operator() | ( | const uint | rowIdx | ) | const |
Returns a VariablesGrid consisting only of the given row.
[in] | rowIdx | Row index of the component to be returned. |
Reimplemented from MatrixVariablesGrid.
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.
[in] | arg | Second summand. |
VariablesGrid& VariablesGrid::operator+= | ( | const VariablesGrid & | arg | ) | [inline] |
Adds (element-wise) a VariablesGrid to object.
[in] | arg | Second summand. |
VariablesGrid VariablesGrid::operator- | ( | const VariablesGrid & | arg | ) | const [inline] |
Subtracts (element-wise) a VariablesGrid from the object and stores result into a temporary object.
[in] | arg | Subtrahend. |
VariablesGrid& VariablesGrid::operator-= | ( | const VariablesGrid & | arg | ) | [inline] |
Subtracts (element-wise) a VariablesGrid from the object.
[in] | arg | Subtrahend. |
VariablesGrid & VariablesGrid::operator= | ( | const VariablesGrid & | rhs | ) |
Assignment operator (deep copy).
[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).
[in] | rhs | Right-hand side object. |
Reimplemented from MatrixVariablesGrid.
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.
[in] | rhs | DMatrix to be read. |
Reimplemented from MatrixVariablesGrid.
Definition at line 162 of file variables_grid.cpp.
BooleanType VariablesGrid::operator== | ( | const VariablesGrid & | arg | ) | const [inline] |
Tests for equality,
[in] | rhs | Object of comparison. |
VariablesGrid VariablesGrid::operator[] | ( | const uint | pointIdx | ) | const |
Returns a VariablesGrid consisting only of the values at given grid point.
[in] | pointIdx | Index of grid point. |
Reimplemented from MatrixVariablesGrid.
Definition at line 191 of file variables_grid.cpp.
returnValue VariablesGrid::setAllVectors | ( | const DVector & | _values | ) |
Assigns new vector to all grid points.
[in] | _value | New vector. |
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.
[in] | pointIdx | Index of grid point. |
[in] | _value | New vector. |
pointIdx | Index of the grid point. |
_values | New 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.
Definition at line 343 of file variables_grid.cpp.
VariablesGrid & VariablesGrid::shiftTimes | ( | double | timeShift | ) |
Shifts times at all grid points by a given offset.
[in] | timeShift | Time offset for shifting. |
Reimplemented from MatrixVariablesGrid.
Definition at line 335 of file variables_grid.cpp.
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.