Provides matrix-valued optimization variables. More...
#include <matrix_variable.hpp>
Public Member Functions | |
MatrixVariable | getCols (uint startIdx, uint endIdx) const |
DMatrix | getMatrix () const |
MatrixVariable | getRows (uint startIdx, uint endIdx) const |
returnValue | init (uint _nRows, uint _nCols, VariableType _type=VT_UNKNOWN, const char **const _names=0, const char **const _units=0, DVector _scaling=emptyVector, DVector _lb=emptyVector, DVector _ub=emptyVector, BooleanType _autoInit=defaultAutoInit) |
MatrixVariable () | |
MatrixVariable (uint _nRows, uint _nCols, VariableType _type=VT_UNKNOWN, const char **const _names=0, const char **const _units=0, DVector _scaling=emptyVector, DVector _lb=emptyVector, DVector _ub=emptyVector, BooleanType _autoInit=defaultAutoInit) | |
MatrixVariable (const MatrixVariable &rhs) | |
MatrixVariable (const DMatrix &_matrix, VariableType _type=VT_UNKNOWN) | |
MatrixVariable & | operator= (const MatrixVariable &rhs) |
MatrixVariable & | operator= (const DMatrix &rhs) |
~MatrixVariable () | |
Public Member Functions inherited from GenericMatrix< double > | |
GenericMatrix | absolute () const |
GenericMatrix & | appendCols (const GenericMatrix &_arg) |
GenericMatrix & | appendRows (const GenericMatrix &_arg) |
GenericMatrix (const Eigen::MatrixBase< OtherDerived > &other) | |
GenericMatrix (const Eigen::ReturnByValue< OtherDerived > &other) | |
GenericMatrix (const Eigen::EigenBase< OtherDerived > &other) | |
GenericMatrix< double > | getAbsolute () const |
GenericVector< double > | getCol (unsigned _idx) const |
GenericMatrix | getCols (unsigned _start, unsigned _end) const |
double | getConditionNumber () const |
GenericVector< double > | getDiag () const |
unsigned | getDim () const |
double | getMax () const |
double | getMean () const |
double | getMin () const |
double | getNorm () const |
unsigned | getNumCols () const |
unsigned | getNumRows () const |
GenericVector< double > | getRow (unsigned _idx) const |
GenericMatrix | getRows (unsigned _start, unsigned _end) const |
double | getTrace () const |
void | init (unsigned _nRows=0, unsigned _nCols=0) |
bool | isEmpty () const |
bool | isPositiveDefinite () const |
bool | isPositiveSemiDefinite () const |
bool | isSquare () const |
bool | isSymmetric () const |
GenericMatrix & | makeVector () |
GenericMatrix | negative () const |
bool | operator!= (const GenericMatrix &arg) const |
bool | operator== (const GenericMatrix &arg) const |
GenericMatrix | positive () const |
virtual returnValue | print (std::ostream &_stream=std::cout, const std::string &_name=DEFAULT_LABEL, const std::string &_startString=DEFAULT_START_STRING, const std::string &_endString=DEFAULT_END_STRING, uint _width=DEFAULT_WIDTH, uint _precision=DEFAULT_PRECISION, const std::string &_colSeparator=DEFAULT_COL_SEPARATOR, const std::string &_rowSeparator=DEFAULT_ROW_SEPARATOR) const |
virtual returnValue | print (std::ostream &stream, const std::string &name, PrintScheme printScheme) const |
virtual returnValue | print (const std::string &_filename, const std::string &_name=DEFAULT_LABEL, const std::string &_startString=DEFAULT_START_STRING, const std::string &_endString=DEFAULT_END_STRING, uint _width=DEFAULT_WIDTH, uint _precision=DEFAULT_PRECISION, const std::string &_colSeparator=DEFAULT_COL_SEPARATOR, const std::string &_rowSeparator=DEFAULT_ROW_SEPARATOR) const |
virtual returnValue | print (const std::string &_filename, const std::string &_name, PrintScheme _printScheme) const |
virtual returnValue | read (std::istream &_stream) |
virtual returnValue | read (const std::string &_filename) |
void | setAll (const double &_value) |
GenericMatrix & | setCol (unsigned _idx, const GenericVector< double > &_arg) |
GenericMatrix & | setRow (unsigned _idx, const GenericVector< double > &_values) |
GenericVector< double > | sumCol () const |
GenericVector< double > | sumRow () const |
returnValue | symmetrize () |
virtual | ~GenericMatrix () |
GenericMatrix () | |
GenericMatrix (const double &_value) | |
GenericMatrix (unsigned _nRows, unsigned _nCols) | |
GenericMatrix (unsigned _nRows, unsigned _nCols, const double *const _values) | |
GenericMatrix (unsigned _nRows, unsigned _nCols, std::vector< double > &_values) | |
GenericMatrix (unsigned _nRows, unsigned _nCols, std::vector< std::vector< double > > &_values) | |
Public Member Functions inherited from Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor|Eigen::AutoAlign > | |
Index | innerStride () const |
EIGEN_STRONG_INLINE | Matrix () |
Default constructor. More... | |
Matrix (internal::constructor_without_unaligned_array_assert) | |
EIGEN_STRONG_INLINE | Matrix (Index dim) |
Constructs a vector or row-vector with given dimension. . More... | |
EIGEN_STRONG_INLINE | Matrix (const T0 &x, const T1 &y) |
EIGEN_STRONG_INLINE | Matrix (const Scalar &x, const Scalar &y, const Scalar &z) |
Constructs an initialized 3D vector with given coefficients. More... | |
EIGEN_STRONG_INLINE | Matrix (const Scalar &x, const Scalar &y, const Scalar &z, const Scalar &w) |
Constructs an initialized 4D vector with given coefficients. More... | |
Matrix (const Scalar *data) | |
EIGEN_STRONG_INLINE | Matrix (const MatrixBase< OtherDerived > &other) |
Constructor copying the value of the expression other. More... | |
EIGEN_STRONG_INLINE | Matrix (const Matrix &other) |
Copy constructor. More... | |
EIGEN_STRONG_INLINE | Matrix (const ReturnByValue< OtherDerived > &other) |
Copy constructor with in-place evaluation. More... | |
EIGEN_STRONG_INLINE | Matrix (const EigenBase< OtherDerived > &other) |
Copy constructor for generic expressions. More... | |
Matrix (const RotationBase< OtherDerived, ColsAtCompileTime > &r) | |
Constructs a Dim x Dim rotation matrix from the rotation r. More... | |
EIGEN_STRONG_INLINE Matrix & | operator= (const Matrix &other) |
Assigns matrices to each other. More... | |
EIGEN_STRONG_INLINE Matrix & | operator= (const MatrixBase< OtherDerived > &other) |
EIGEN_STRONG_INLINE Matrix & | operator= (const EigenBase< OtherDerived > &other) |
Copies the generic expression other into *this. More... | |
EIGEN_STRONG_INLINE Matrix & | operator= (const ReturnByValue< OtherDerived > &func) |
Matrix & | operator= (const RotationBase< OtherDerived, ColsAtCompileTime > &r) |
Index | outerStride () const |
void | swap (MatrixBase< OtherDerived > const &other) |
Public Member Functions inherited from Eigen::PlainObjectBase< Derived > | |
Base & | base () |
const Base & | base () const |
EIGEN_STRONG_INLINE const Scalar & | coeff (Index rowId, Index colId) const |
EIGEN_STRONG_INLINE const Scalar & | coeff (Index index) const |
EIGEN_STRONG_INLINE Scalar & | coeffRef (Index rowId, Index colId) |
EIGEN_STRONG_INLINE Scalar & | coeffRef (Index index) |
EIGEN_STRONG_INLINE const Scalar & | coeffRef (Index rowId, Index colId) const |
EIGEN_STRONG_INLINE const Scalar & | coeffRef (Index index) const |
EIGEN_STRONG_INLINE Index | cols () const |
EIGEN_STRONG_INLINE void | conservativeResize (Index nbRows, Index nbCols) |
EIGEN_STRONG_INLINE void | conservativeResize (Index nbRows, NoChange_t) |
EIGEN_STRONG_INLINE void | conservativeResize (NoChange_t, Index nbCols) |
EIGEN_STRONG_INLINE void | conservativeResize (Index size) |
template<typename OtherDerived > | |
EIGEN_STRONG_INLINE void | conservativeResizeLike (const DenseBase< OtherDerived > &other) |
EIGEN_STRONG_INLINE const Scalar * | data () const |
EIGEN_STRONG_INLINE Scalar * | data () |
template<typename OtherDerived > | |
EIGEN_STRONG_INLINE Derived & | lazyAssign (const DenseBase< OtherDerived > &other) |
EIGEN_STRONG_INLINE Derived & | operator= (const PlainObjectBase &other) |
template<typename OtherDerived > | |
EIGEN_STRONG_INLINE Derived & | operator= (const ReturnByValue< OtherDerived > &func) |
template<typename OtherDerived > | |
EIGEN_STRONG_INLINE Derived & | operator= (const EigenBase< OtherDerived > &other) |
template<int LoadMode> | |
EIGEN_STRONG_INLINE PacketScalar | packet (Index rowId, Index colId) const |
template<int LoadMode> | |
EIGEN_STRONG_INLINE PacketScalar | packet (Index index) const |
EIGEN_STRONG_INLINE | PlainObjectBase () |
PlainObjectBase (internal::constructor_without_unaligned_array_assert) | |
EIGEN_STRONG_INLINE | PlainObjectBase (Index a_size, Index nbRows, Index nbCols) |
template<typename OtherDerived > | |
EIGEN_STRONG_INLINE | PlainObjectBase (const EigenBase< OtherDerived > &other) |
EIGEN_STRONG_INLINE void | resize (Index nbRows, Index nbCols) |
void | resize (Index size) |
void | resize (NoChange_t, Index nbCols) |
void | resize (Index nbRows, NoChange_t) |
template<typename OtherDerived > | |
EIGEN_STRONG_INLINE void | resizeLike (const EigenBase< OtherDerived > &_other) |
EIGEN_STRONG_INLINE Index | rows () const |
Derived & | setConstant (Index size, const Scalar &value) |
Derived & | setConstant (Index rows, Index cols, const Scalar &value) |
Derived & | setOnes (Index size) |
Derived & | setOnes (Index rows, Index cols) |
Derived & | setRandom (Index size) |
Derived & | setRandom (Index rows, Index cols) |
Derived & | setZero (Index size) |
Derived & | setZero (Index rows, Index cols) |
template<int StoreMode> | |
EIGEN_STRONG_INLINE void | writePacket (Index rowId, Index colId, const PacketScalar &val) |
template<int StoreMode> | |
EIGEN_STRONG_INLINE void | writePacket (Index index, const PacketScalar &val) |
Public Member Functions inherited from VariableSettings | |
returnValue | appendSettings (const VariableSettings &rhs) |
returnValue | appendSettings (uint _dim, const char **const _names, const char **const _units, const DVector &_scaling=emptyConstVector, const DVector &_lb=emptyConstVector, const DVector &_ub=emptyConstVector) |
BooleanType | getAutoInit () const |
double | getLowerBound (uint idx) const |
DVector | getLowerBounds () const |
returnValue | getName (uint idx, char *_name) const |
DVector | getScaling () const |
double | getScaling (uint idx) const |
VariableType | getType () const |
returnValue | getUnit (uint idx, char *_unit) const |
double | getUpperBound (uint idx) const |
DVector | getUpperBounds () const |
BooleanType | hasLowerBounds () const |
BooleanType | hasNames () const |
BooleanType | hasScaling () const |
BooleanType | hasUnits () const |
BooleanType | hasUpperBounds () const |
returnValue | init () |
returnValue | init (uint _dim, VariableType _type, const char **const _names, const char **const _units, const DVector &_scaling=emptyConstVector, const DVector &_lb=emptyConstVector, const DVector &_ub=emptyConstVector, BooleanType _autoInit=defaultAutoInit) |
VariableSettings & | operator= (const VariableSettings &rhs) |
returnValue | setAutoInit (BooleanType _autoInit) |
returnValue | setLowerBound (uint idx, double _lb) |
returnValue | setLowerBounds (const DVector &_lb) |
returnValue | setName (uint idx, const char *const _name) |
returnValue | setScaling (const DVector &_scaling) |
returnValue | setScaling (uint idx, double _scaling) |
returnValue | setType (VariableType _type) |
returnValue | setUnit (uint idx, const char *const _unit) |
returnValue | setUpperBound (uint idx, double _ub) |
returnValue | setUpperBounds (const DVector &_ub) |
VariableSettings () | |
VariableSettings (uint _dim, VariableType _type=VT_UNKNOWN, const char **const _names=0, const char **const _units=0, const DVector &_scaling=emptyConstVector, const DVector &_lb=emptyConstVector, const DVector &_ub=emptyConstVector, BooleanType _autoInit=defaultAutoInit) | |
VariableSettings (const VariableSettings &rhs) | |
~VariableSettings () | |
Additional Inherited Members | |
Public Types inherited from GenericMatrix< double > | |
typedef Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor|Eigen::AutoAlign > | Base |
Public Types inherited from Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor|Eigen::AutoAlign > | |
enum | |
typedef PlainObjectBase< Matrix > | Base |
Base class typedef. More... | |
typedef Base::PlainObject | PlainObject |
Public Types inherited from Eigen::PlainObjectBase< Derived > | |
enum | { Options = internal::traits<Derived>::Options } |
enum | { NeedsToAlign = SizeAtCompileTime != Dynamic && (internal::traits<Derived>::Flags & AlignedBit) != 0 } |
typedef Eigen::Map< Derived, Aligned > | AlignedMapType |
typedef internal::dense_xpr_base< Derived >::type | Base |
typedef const Eigen::Map< const Derived, Aligned > | ConstAlignedMapType |
typedef const Eigen::Map< const Derived, Unaligned > | ConstMapType |
typedef Derived | DenseType |
typedef internal::traits< Derived >::Index | Index |
typedef Eigen::Map< Derived, Unaligned > | MapType |
typedef internal::packet_traits< Scalar >::type | PacketScalar |
typedef NumTraits< Scalar >::Real | RealScalar |
typedef internal::traits< Derived >::Scalar | Scalar |
typedef internal::traits< Derived >::StorageKind | StorageKind |
Static Public Member Functions inherited from Eigen::PlainObjectBase< Derived > | |
static EIGEN_STRONG_INLINE void | _check_template_params () |
static ConstMapType | Map (const Scalar *data) |
static MapType | Map (Scalar *data) |
static ConstMapType | Map (const Scalar *data, Index size) |
static MapType | Map (Scalar *data, Index size) |
static ConstMapType | Map (const Scalar *data, Index rows, Index cols) |
static MapType | Map (Scalar *data, Index rows, Index cols) |
static ConstAlignedMapType | MapAligned (const Scalar *data) |
static AlignedMapType | MapAligned (Scalar *data) |
static ConstAlignedMapType | MapAligned (const Scalar *data, Index size) |
static AlignedMapType | MapAligned (Scalar *data, Index size) |
static ConstAlignedMapType | MapAligned (const Scalar *data, Index rows, Index cols) |
static AlignedMapType | MapAligned (Scalar *data, Index rows, Index cols) |
template<int Outer, int Inner> | |
static StridedConstMapType< Stride< Outer, Inner > >::type | Map (const Scalar *data, const Stride< Outer, Inner > &stride) |
template<int Outer, int Inner> | |
static StridedMapType< Stride< Outer, Inner > >::type | Map (Scalar *data, const Stride< Outer, Inner > &stride) |
template<int Outer, int Inner> | |
static StridedConstMapType< Stride< Outer, Inner > >::type | Map (const Scalar *data, Index size, const Stride< Outer, Inner > &stride) |
template<int Outer, int Inner> | |
static StridedMapType< Stride< Outer, Inner > >::type | Map (Scalar *data, Index size, const Stride< Outer, Inner > &stride) |
template<int Outer, int Inner> | |
static StridedConstMapType< Stride< Outer, Inner > >::type | Map (const Scalar *data, Index rows, Index cols, const Stride< Outer, Inner > &stride) |
template<int Outer, int Inner> | |
static StridedMapType< Stride< Outer, Inner > >::type | Map (Scalar *data, Index rows, Index cols, const Stride< Outer, Inner > &stride) |
template<int Outer, int Inner> | |
static StridedConstAlignedMapType< Stride< Outer, Inner > >::type | MapAligned (const Scalar *data, const Stride< Outer, Inner > &stride) |
template<int Outer, int Inner> | |
static StridedAlignedMapType< Stride< Outer, Inner > >::type | MapAligned (Scalar *data, const Stride< Outer, Inner > &stride) |
template<int Outer, int Inner> | |
static StridedConstAlignedMapType< Stride< Outer, Inner > >::type | MapAligned (const Scalar *data, Index size, const Stride< Outer, Inner > &stride) |
template<int Outer, int Inner> | |
static StridedAlignedMapType< Stride< Outer, Inner > >::type | MapAligned (Scalar *data, Index size, const Stride< Outer, Inner > &stride) |
template<int Outer, int Inner> | |
static StridedConstAlignedMapType< Stride< Outer, Inner > >::type | MapAligned (const Scalar *data, Index rows, Index cols, const Stride< Outer, Inner > &stride) |
template<int Outer, int Inner> | |
static StridedAlignedMapType< Stride< Outer, Inner > >::type | MapAligned (Scalar *data, Index rows, Index cols, const Stride< Outer, Inner > &stride) |
Protected Member Functions inherited from Eigen::PlainObjectBase< Derived > | |
template<typename T0 , typename T1 > | |
EIGEN_STRONG_INLINE void | _init2 (Index nbRows, Index nbCols, typename internal::enable_if< Base::SizeAtCompileTime!=2, T0 >::type *=0) |
template<typename T0 , typename T1 > | |
EIGEN_STRONG_INLINE void | _init2 (const Scalar &val0, const Scalar &val1, typename internal::enable_if< Base::SizeAtCompileTime==2, T0 >::type *=0) |
template<typename OtherDerived > | |
EIGEN_STRONG_INLINE void | _resize_to_match (const EigenBase< OtherDerived > &other) |
template<typename OtherDerived > | |
EIGEN_STRONG_INLINE Derived & | _set (const DenseBase< OtherDerived > &other) |
Copies the value of the expression other into *this with automatic resizing. More... | |
template<typename OtherDerived > | |
EIGEN_STRONG_INLINE Derived & | _set_noalias (const DenseBase< OtherDerived > &other) |
template<typename OtherDerived > | |
EIGEN_STRONG_INLINE void | _set_selector (const OtherDerived &other, const internal::true_type &) |
template<typename OtherDerived > | |
EIGEN_STRONG_INLINE void | _set_selector (const OtherDerived &other, const internal::false_type &) |
template<typename OtherDerived > | |
void | _swap (DenseBase< OtherDerived > const &other) |
Protected Member Functions inherited from VariableSettings | |
returnValue | clear () |
Protected Attributes inherited from Eigen::PlainObjectBase< Derived > | |
DenseStorage< Scalar, Base::MaxSizeAtCompileTime, Base::RowsAtCompileTime, Base::ColsAtCompileTime, Options > | m_storage |
Protected Attributes inherited from VariableSettings | |
BooleanType | autoInit |
uint | dim |
DVector | lb |
char ** | names |
DVector | scaling |
VariableType | type |
DVector | ub |
char ** | units |
Provides matrix-valued optimization variables.
The class MatrixVariable provides matrix-valued optimization variables by enhancing the DMatrix class with variable-specific settings.
Definition at line 55 of file matrix_variable.hpp.
BEGIN_NAMESPACE_ACADO MatrixVariable::MatrixVariable | ( | ) |
Default constructor.
Definition at line 46 of file matrix_variable.cpp.
MatrixVariable::MatrixVariable | ( | uint | _nRows, |
uint | _nCols, | ||
VariableType | _type = VT_UNKNOWN , |
||
const char **const | _names = 0 , |
||
const char **const | _units = 0 , |
||
DVector | _scaling = emptyVector , |
||
DVector | _lb = emptyVector , |
||
DVector | _ub = emptyVector , |
||
BooleanType | _autoInit = defaultAutoInit |
||
) |
Constructor which takes dimensions of the matrix as well as all variable settings.
[in] | _nRows | Number of rows of each matrix. |
[in] | _nCols | Number of columns of each matrix. |
[in] | _type | Type of the variable. |
[in] | _names | Array containing name labels for each component of the variable. |
[in] | _units | Array containing unit labels for each component of the variable. |
[in] | _scaling | Scaling for each component of the variable. |
[in] | _lb | Lower bounds for each component of the variable. |
[in] | _ub | Upper bounds for each component of the variable. |
[in] | _autoInit | Flag indicating whether variable is to be automatically initialized. |
Definition at line 51 of file matrix_variable.cpp.
MatrixVariable::MatrixVariable | ( | const MatrixVariable & | rhs | ) |
Copy constructor (deep copy).
@param[in] rhs Right-hand side object.
Definition at line 65 of file matrix_variable.cpp.
MatrixVariable::MatrixVariable | ( | const DMatrix & | _matrix, |
VariableType | _type = VT_UNKNOWN |
||
) |
Copy constructor converting a matrix to a MatrixVariable (of given type).
@param[in] _matrix DMatrix to be converted. @param[in] _type Type of the variable.
Definition at line 70 of file matrix_variable.cpp.
MatrixVariable::~MatrixVariable | ( | ) |
Destructor.
Definition at line 77 of file matrix_variable.cpp.
MatrixVariable MatrixVariable::getCols | ( | uint | startIdx, |
uint | endIdx | ||
) | const |
Returns a MatrixVariable containing only the columns between given indices while keeping all rows.
[in] | startIdx | Index of first column to be included. |
[in] | endIdx | Index of last column to be included. |
Definition at line 148 of file matrix_variable.cpp.
|
inline |
Returns matrix containing the numerical values of the MatrixVariable.
\return DMatrix containing the numerical values
MatrixVariable MatrixVariable::getRows | ( | uint | startIdx, |
uint | endIdx | ||
) | const |
Returns a MatrixVariable containing only the rows between given indices while keeping all columns.
[in] | startIdx | Index of first row to be included. |
[in] | endIdx | Index of last row to be included. |
Definition at line 128 of file matrix_variable.cpp.
returnValue MatrixVariable::init | ( | uint | _nRows, |
uint | _nCols, | ||
VariableType | _type = VT_UNKNOWN , |
||
const char **const | _names = 0 , |
||
const char **const | _units = 0 , |
||
DVector | _scaling = emptyVector , |
||
DVector | _lb = emptyVector , |
||
DVector | _ub = emptyVector , |
||
BooleanType | _autoInit = defaultAutoInit |
||
) |
Initializes object with given dimensions of the matrix and given variable settings.
[in] | _nRows | Number of rows of each matrix. |
[in] | _nCols | Number of columns of each matrix. |
[in] | _type | Type of the variable. |
[in] | _names | Array containing name labels for each component of the variable. |
[in] | _units | Array containing unit labels for each component of the variable. |
[in] | _scaling | Scaling for each component of the variable. |
[in] | _lb | Lower bounds for each component of the variable. |
[in] | _ub | Upper bounds for each component of the variable. |
[in] | _autoInit | Flag indicating whether variable is to be automatically initialized. |
Definition at line 107 of file matrix_variable.cpp.
MatrixVariable & MatrixVariable::operator= | ( | const MatrixVariable & | rhs | ) |
Assignment operator (deep copy).
@param[in] rhs Right-hand side object.
Definition at line 82 of file matrix_variable.cpp.
MatrixVariable & MatrixVariable::operator= | ( | const DMatrix & | rhs | ) |
Assignment operator converting a matrix to a MatrixVariable.
@param[in] rhs Right-hand side object.
Definition at line 94 of file matrix_variable.cpp.