matrix.hpp
Go to the documentation of this file.
00001 /*
00002  *    This file is part of ACADO Toolkit.
00003  *
00004  *    ACADO Toolkit -- A Toolkit for Automatic Control and Dynamic Optimization.
00005  *    Copyright (C) 2008-2014 by Boris Houska, Hans Joachim Ferreau,
00006  *    Milan Vukov, Rien Quirynen, KU Leuven.
00007  *    Developed within the Optimization in Engineering Center (OPTEC)
00008  *    under supervision of Moritz Diehl. All rights reserved.
00009  *
00010  *    ACADO Toolkit is free software; you can redistribute it and/or
00011  *    modify it under the terms of the GNU Lesser General Public
00012  *    License as published by the Free Software Foundation; either
00013  *    version 3 of the License, or (at your option) any later version.
00014  *
00015  *    ACADO Toolkit is distributed in the hope that it will be useful,
00016  *    but WITHOUT ANY WARRANTY; without even the implied warranty of
00017  *    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
00018  *    Lesser General Public License for more details.
00019  *
00020  *    You should have received a copy of the GNU Lesser General Public
00021  *    License along with ACADO Toolkit; if not, write to the Free Software
00022  *    Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
00023  *
00024  */
00025 
00034 #ifndef ACADO_TOOLKIT_MATRIX_HPP
00035 #define ACADO_TOOLKIT_MATRIX_HPP
00036 
00037 #ifdef _WIN32
00038     #include <memory>
00039 #else
00040     #include <tr1/memory>
00041 #endif
00042 
00043 #include <acado/matrix_vector/vector.hpp>
00044 
00045 BEGIN_NAMESPACE_ACADO
00046 
00048 template<typename T>
00049 class GenericMatrix : public Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor | Eigen::AutoAlign>
00050 {
00051 public:
00052 
00059         typedef Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor | Eigen::AutoAlign> Base;
00060 
00061 
00063         template<typename OtherDerived>
00064         inline GenericMatrix(const Eigen::MatrixBase<OtherDerived>& other) : Base( other ) {}
00065 
00067         template<typename OtherDerived>
00068         inline GenericMatrix(const Eigen::ReturnByValue<OtherDerived>& other) : Base( other ) {}
00069 
00071         template<typename OtherDerived>
00072         inline GenericMatrix(const Eigen::EigenBase<OtherDerived>& other) : Base( other ) {}
00073 
00082         GenericMatrix() : Base() {}
00083 
00085         GenericMatrix(  const T& _value
00086                                         )
00087                 : Base(1, 1)
00088         { Base::data()[ 0 ] = _value; }
00089 
00091         GenericMatrix(  unsigned _nRows,
00092                                         unsigned _nCols
00093                                         )
00094                 : Base(_nRows, _nCols)
00095         { Base::setZero(); }
00096 
00098         GenericMatrix(  unsigned _nRows,
00099                                         unsigned _nCols,
00100                                         const T* const _values
00101                                         )
00102                 : Base(_nRows, _nCols)
00103         { std::copy(_values, _values + _nRows * _nCols, Base::data()); }
00104 
00106         GenericMatrix(  unsigned _nRows,
00107                                         unsigned _nCols,
00108                                         std::vector< T >& _values)
00109                 : Base(_nRows, _nCols)
00110         { std::copy(_values.begin(), _values.end(), Base::data()); }
00111 
00113         GenericMatrix(  unsigned _nRows,
00114                                         unsigned _nCols,
00115                                         std::vector< std::vector< T > >& _values
00116                                         );
00117 
00121         virtual ~GenericMatrix()
00122         {}
00123 
00125         bool operator==(const GenericMatrix& arg) const
00126         {
00127                 if (Base::rows() != arg.rows() || Base::cols() != arg.cols())
00128                         return false;
00129                 return Base::isApprox(arg, EQUALITY_EPS);
00130         }
00131 
00133         bool operator!=(const GenericMatrix& arg) const
00134         {
00135                 return (operator==( arg ) == false);
00136         }
00137 
00139         void init(      unsigned _nRows = 0,
00140                                 unsigned _nCols = 0
00141                                 )
00142         { Base::_set(GenericMatrix<T>(_nRows, _nCols)); }
00143 
00145         void setAll( const T& _value)
00146         { Base::setConstant( _value ); }
00147 
00149         GenericMatrix& appendRows(      const GenericMatrix& _arg
00150                                                                 );
00151 
00153         GenericMatrix& appendCols(      const GenericMatrix& _arg
00154                                                                 );
00155 
00166         GenericVector< T > sumCol() const;
00167 
00179         GenericVector< T > sumRow() const;
00180 
00182         GenericMatrix& makeVector( );
00183 
00185         unsigned getDim( ) const
00186         { return (Base::rows() * Base::cols()); }
00187 
00189         unsigned getNumRows( ) const
00190         { return Base::rows(); }
00191 
00193         unsigned getNumCols( ) const
00194         { return Base::cols(); }
00195 
00197         bool isEmpty( ) const
00198         { return Base::rows() == 0 || Base::cols() == 0; }
00199 
00201         GenericVector< T > getRow(      unsigned _idx
00202                                                                 ) const
00203         {
00204                 ASSERT( _idx < Base::rows() );
00205                 return Base::row( _idx ).transpose();
00206         }
00207 
00209         GenericVector< T > getCol(      unsigned _idx
00210                                                                 ) const
00211         {
00212                 ASSERT( _idx < Base::cols() );
00213                 return Base::col( _idx );
00214         }
00215 
00217         GenericMatrix& setRow(  unsigned _idx,
00218                                                         const GenericVector< T >& _values
00219                                                         )
00220         {
00221                 ASSERT(Base::cols() == _values.rows() && _idx < Base::rows());
00222                 Base::row( _idx ) = _values.transpose();
00223 
00224                 return *this;
00225         }
00226 
00228         GenericMatrix& setCol(  unsigned _idx,
00229                                                         const GenericVector< T >& _arg
00230                                                         )
00231         {
00232                 ASSERT(Base::rows() == _arg.rows() && _idx < Base::cols());
00233                 Base::col( _idx ) = _arg;
00234 
00235                 return *this;
00236         }
00237 
00239         GenericMatrix getRows(  unsigned _start,
00240                                                         unsigned _end
00241                                                         ) const
00242         {
00243                 if (_start >= Base::rows() || _end >= Base::rows() || _start > _end)
00244                         return GenericMatrix();
00245 
00246                 return Base::block(_start, 0, _end - _start + 1, Base::cols());
00247         }
00248 
00250         GenericMatrix getCols(  unsigned _start,
00251                                                         unsigned _end
00252                                                         ) const
00253         {
00254                 if (_start >= Base::cols() || _end >= Base::cols() || _start > _end)
00255                         return GenericMatrix();
00256 
00257                 return Base::block(0, _start, Base::rows(), _end - _start + 1);
00258         }
00259 
00261         GenericVector< T > getDiag( ) const;
00262 
00264         bool isSquare() const;
00265 
00267         bool isSymmetric( ) const;
00268 
00270         returnValue symmetrize( );
00271 
00275         bool isPositiveSemiDefinite( ) const;
00276 
00280         bool isPositiveDefinite( ) const;
00281 
00284         GenericMatrix absolute() const;
00285 
00289         GenericMatrix positive() const;
00290 
00294         GenericMatrix negative() const;
00295 
00297         T getMax( ) const
00298         { return Base::maxCoeff(); }
00299 
00301         T getMin( ) const
00302         { return Base::minCoeff(); }
00303 
00305         T getMean( ) const
00306         { return Base::mean(); }
00307 
00309         GenericMatrix< T > getAbsolute() const
00310         { return Base::cwiseAbs(); }
00311 
00313         T getNorm( ) const;
00314 
00316         T getTrace( ) const;
00317 
00321         T getConditionNumber( ) const;
00322 
00339         virtual returnValue print(      std::ostream& _stream            = std::cout,
00340                                                                 const std::string& _name         = DEFAULT_LABEL,
00341                                                                 const std::string& _startString  = DEFAULT_START_STRING,
00342                                                                 const std::string& _endString    = DEFAULT_END_STRING,
00343                                                                 uint _width                      = DEFAULT_WIDTH,
00344                                                                 uint _precision                  = DEFAULT_PRECISION,
00345                                                                 const std::string& _colSeparator = DEFAULT_COL_SEPARATOR,
00346                                                                 const std::string& _rowSeparator = DEFAULT_ROW_SEPARATOR
00347                                                                 ) const;
00348 
00360         virtual returnValue print(      std::ostream& stream,
00361                                                                 const std::string& name,
00362                                                                 PrintScheme printScheme
00363                                                                 ) const;
00364 
00381         virtual returnValue print(      const std::string& _filename,
00382                                                                 const std::string& _name         = DEFAULT_LABEL,
00383                                                                 const std::string& _startString  = DEFAULT_START_STRING,
00384                                                                 const std::string& _endString    = DEFAULT_END_STRING,
00385                                                                 uint _width                      = DEFAULT_WIDTH,
00386                                                                 uint _precision                  = DEFAULT_PRECISION,
00387                                                                 const std::string& _colSeparator = DEFAULT_COL_SEPARATOR,
00388                                                                 const std::string& _rowSeparator = DEFAULT_ROW_SEPARATOR
00389                                                                 ) const;
00390 
00402         virtual returnValue print(      const std::string& _filename,
00403                                                                 const std::string& _name,
00404                                                                 PrintScheme _printScheme
00405                                                                 ) const;
00406 
00408         virtual returnValue read(       std::istream& _stream
00409                                                                 );
00410 
00412         virtual returnValue read(       const std::string& _filename
00413                                                                 );
00414 };
00415 
00417 template<typename T>
00418 std::ostream& operator<<(       std::ostream& _stream,
00419                                                         const GenericMatrix< T >& _arg
00420                                                         )
00421 {
00422         if (_arg.print( _stream ) != SUCCESSFUL_RETURN)
00423                 ACADOERRORTEXT(RET_INVALID_ARGUMENTS, "Cannot write to output stream.");
00424 
00425         return _stream;
00426 }
00427 
00429 template<typename T>
00430 std::istream& operator>>(       std::istream& _stream,
00431                                                         GenericMatrix< T >& _arg
00432 )
00433 {
00434         if (_arg.read( _stream ) != SUCCESSFUL_RETURN )
00435                 ACADOERRORTEXT(RET_INVALID_ARGUMENTS, "Cannot read from input stream.");
00436 
00437         return _stream;
00438 }
00439 
00441 template<typename T>
00442 GenericMatrix< T > ones(        unsigned _nRows,
00443                                                         unsigned _nCols = 1
00444                                                         )
00445 { return GenericMatrix< T >(_nRows, _nCols).setOnes(); }
00446 
00448 template<typename T>
00449 GenericMatrix< T > zeros(       unsigned _nRows,
00450                                                         unsigned _nCols = 1
00451                                                         )
00452 { return GenericMatrix< T >(_nRows, _nCols).setZero(); }
00453 
00455 template<typename T>
00456 GenericMatrix< T > eye( unsigned _dim
00457                                                 )
00458 { return GenericMatrix< T >(_dim, _dim).setIdentity(); }
00459 
00461 typedef GenericMatrix< double > DMatrix;
00463 typedef GenericMatrix< int > IMatrix;
00465 typedef GenericMatrix< bool > BMatrix;
00467 typedef std::tr1::shared_ptr< GenericMatrix< double > > DMatrixPtr;
00468 
00469 static       DMatrix emptyMatrix;
00470 static const DMatrix emptyConstMatrix;
00471 
00472 CLOSE_NAMESPACE_ACADO
00473 
00475 namespace Eigen
00476 {
00477 namespace internal
00478 {
00479 template<typename T>
00480 struct traits< ACADO::GenericMatrix< T > >
00481         : traits<Matrix<T, Dynamic, Dynamic, Eigen::RowMajor | Eigen::AutoAlign> >
00482 {};
00483 
00484 } // namespace internal
00485 } // namespace Eigen
00488 #endif  // ACADO_TOOLKIT_MATRIX_HPP


acado
Author(s): Milan Vukov, Rien Quirynen
autogenerated on Thu Aug 27 2015 11:59:10