vector.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 
00026 
00035 #ifndef ACADO_TOOLKIT_VECTOR_HPP
00036 #define ACADO_TOOLKIT_VECTOR_HPP
00037 
00038 #include <acado/utils/acado_utils.hpp>
00039 #include <acado/matrix_vector/matrix_vector_tools.hpp>
00040 
00041 BEGIN_NAMESPACE_ACADO
00042 
00044 enum VectorNorm
00045 {
00046     VN_L1,
00047     VN_L2,
00048     VN_LINF
00049 };
00050 
00052 template<typename T>
00053 class GenericVector : public Eigen::Matrix<T, Eigen::Dynamic, 1>
00054 {
00055 public:
00056 
00063         typedef Eigen::Matrix<T, Eigen::Dynamic, 1> Base;
00064 
00066         template<typename OtherDerived>
00067         inline GenericVector(const Eigen::MatrixBase<OtherDerived>& other) : Base( other ) {}
00068 
00070         template<typename OtherDerived>
00071         inline GenericVector(const Eigen::ReturnByValue<OtherDerived>& other) : Base( other ) {}
00072 
00074         template<typename OtherDerived>
00075         inline GenericVector(const Eigen::EigenBase<OtherDerived>& other) : Base( other ) {}
00076 
00085         GenericVector() : Base() {}
00086 
00088         GenericVector(  unsigned _dim ) : Base( _dim ) { Base::setZero(); }
00089 
00091         GenericVector(  unsigned _dim,
00092                                         const T* const _values
00093                                         )
00094                 : Base( _dim )
00095         { std::copy(_values, _values + _dim, Base::data()); }
00096 
00098         GenericVector(  std::vector< T > _values
00099                                         )
00100                 : Base( _values.size() )
00101         { std::copy(_values.begin(), _values.end(), Base::data()); }
00102 
00106         virtual ~GenericVector()
00107         {}
00108 
00110         bool operator==(const GenericVector& _arg) const
00111         {
00112                 if (Base::rows() != _arg.rows())
00113                         return false;
00114                 return Base::isApprox(_arg, EQUALITY_EPS);
00115         }
00116 
00118         bool operator!=(const GenericVector& _arg) const
00119         {
00120                 return (operator==( _arg ) == false);
00121         }
00122 
00123         bool operator<=(const GenericVector& _arg) const
00124         {
00125                 if (Base::rows() != _arg.rows())
00126                         return false;
00127                 for (unsigned el = 0; el < Base::rows(); ++el)
00128                         if (Base::data()[ el ] > _arg.data()[ el ])
00129                                 return false;
00130                 return true;
00131         }
00132 
00133         bool operator>=(const GenericVector& _arg) const
00134         {
00135                 if (Base::rows() != _arg.rows())
00136                         return false;
00137                 for (unsigned el = 0; el < Base::rows(); ++el)
00138                         if (Base::data()[ el ] < _arg.data()[ el ])
00139                                 return false;
00140                 return true;
00141         }
00142 
00143         bool operator>(const GenericVector& _arg) const
00144         {
00145                 return operator<=( _arg ) == false;
00146         }
00147 
00148         bool operator<(const GenericVector& _arg) const
00149         {
00150                 return operator>=( _arg ) == false;
00151         }
00152 
00154         void init(      unsigned _dim = 0
00155                                 )
00156         { Base::_set(GenericVector< T >( _dim )); }
00157 
00159         void setAll( const T& _value)
00160         { Base::setConstant( _value ); }
00161 
00163         GenericVector& append(  const GenericVector& _arg
00164                                                         );
00165 
00167         GenericVector& setUnitVector(   unsigned _idx
00168                                                                         );
00169 
00171         unsigned getDim( ) const
00172         { return Base::rows(); }
00173 
00175         bool isEmpty( ) const
00176         { return Base::rows() == 0; }
00177 
00179         T getMax( ) const
00180         { return Base::maxCoeff(); }
00181 
00183         T getMin( ) const
00184         { return Base::minCoeff(); }
00185 
00187         T getMean( ) const
00188         { return Base::mean(); }
00189 
00191         GenericVector getAbsolute() const
00192         { return Base::cwiseAbs(); }
00193 
00198         T getNorm(      VectorNorm _norm
00199                                 ) const;
00200 
00206         T getNorm(      VectorNorm _norm,
00207                                 const GenericVector& _scale
00208                                 ) const;
00209 
00226         virtual returnValue print(      std::ostream& stream            = std::cout,
00227                                                                 const std::string& name         = DEFAULT_LABEL,
00228                                                                 const std::string& startString  = DEFAULT_START_STRING,
00229                                                                 const std::string& endString    = DEFAULT_END_STRING,
00230                                                                 uint width                      = DEFAULT_WIDTH,
00231                                                                 uint precision                  = DEFAULT_PRECISION,
00232                                                                 const std::string& colSeparator = DEFAULT_COL_SEPARATOR,
00233                                                                 const std::string& rowSeparator = DEFAULT_ROW_SEPARATOR
00234                                                                 ) const;
00235 
00252         virtual returnValue print(      const std::string& filename,
00253                                                                 const std::string& name         = DEFAULT_LABEL,
00254                                                                 const std::string& startString  = DEFAULT_START_STRING,
00255                                                                 const std::string& endString    = DEFAULT_END_STRING,
00256                                                                 uint width                      = DEFAULT_WIDTH,
00257                                                                 uint precision                  = DEFAULT_PRECISION,
00258                                                                 const std::string& colSeparator = DEFAULT_COL_SEPARATOR,
00259                                                                 const std::string& rowSeparator = DEFAULT_ROW_SEPARATOR
00260                                                                 ) const;
00261 
00273         virtual returnValue print(      std::ostream& stream,
00274                                                                 const std::string& name,
00275                                                                 PrintScheme printScheme
00276                                                                 ) const;
00277 
00289         virtual returnValue print(      const std::string& filename,
00290                                                                 const std::string& name,
00291                                                                 PrintScheme printScheme
00292                                                                 ) const;
00293 
00295         virtual returnValue read(       std::istream& stream
00296                                                                 );
00297 
00299         virtual returnValue read(       const std::string& filename
00300                                                                 );
00301 };
00302 
00304 template<typename T>
00305 std::ostream& operator<<(       std::ostream& _stream,
00306                                                         const GenericVector< T >& _arg
00307                                                         )
00308 {
00309         if (_arg.print( _stream ) != SUCCESSFUL_RETURN)
00310                 ACADOERRORTEXT(RET_INVALID_ARGUMENTS, "Cannot write to output stream.");
00311 
00312         return _stream;
00313 }
00314 
00316 template<typename T>
00317 std::istream& operator>>(       std::istream& _stream,
00318                                                         GenericVector< T >& _arg
00319 )
00320 {
00321         if (_arg.read( _stream ) != SUCCESSFUL_RETURN )
00322                 ACADOERRORTEXT(RET_INVALID_ARGUMENTS, "Cannot read from input stream.");
00323 
00324         return _stream;
00325 }
00326 
00328 typedef GenericVector< double > DVector;
00330 typedef GenericVector< int > IVector;
00332 typedef GenericVector< bool > BVector;
00333 
00334 static       DVector emptyVector;
00335 static const DVector emptyConstVector;
00336 
00337 CLOSE_NAMESPACE_ACADO
00338 
00339 #endif  // ACADO_TOOLKIT_VECTOR_HPP


acado
Author(s): Milan Vukov, Rien Quirynen
autogenerated on Thu Aug 27 2015 12:01:31