vector.cpp
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 
00033 #include <acado/matrix_vector/vector.hpp>
00034 #include <acado/matrix_vector/acado_mat_file.hpp>
00035 #include <iomanip>
00036 
00037 using namespace std;
00038 
00039 BEGIN_NAMESPACE_ACADO
00040 
00041 template<typename T>
00042 GenericVector< T >& GenericVector<T>::append(   const GenericVector<T>& _arg
00043 )
00044 {
00045         unsigned oldDim = Base::rows();
00046         unsigned argDim = _arg.rows();
00047 
00048         Base::conservativeResize(oldDim + argDim);
00049         Base::block(oldDim, 0, argDim, 1) = _arg;
00050 
00051         return *this;
00052 }
00053 
00054 template<typename T>
00055 GenericVector<T>& GenericVector< T >::setUnitVector(    unsigned _idx
00056 )
00057 {
00058         ASSERT( _idx < Base::rows() );
00059 
00060         Base::setZero( );
00061         Base::operator()( _idx ) = T( 1 );
00062 
00063         return *this;
00064 }
00065 
00066 template<typename T>
00067 T GenericVector< T >::getNorm(VectorNorm _norm ) const
00068 {
00069         GenericVector scale( getDim() );
00070         scale.setOnes();
00071         return getNorm(_norm, scale);
00072 }
00073 
00074 template<typename T>
00075 T GenericVector< T >::getNorm(  VectorNorm _norm,
00076                                                                 const GenericVector< T >& _scale ) const
00077 {
00078         switch( _norm )
00079         {
00080         case VN_L1:
00081                 return GenericVector<T>(this->cwiseQuotient( _scale )).getAbsolute().sum();
00082 
00083         case VN_L2:
00084                 return Base::norm();
00085 
00086         case VN_LINF:
00087                 return GenericVector<T>(this->cwiseQuotient(_scale)).getAbsolute().getMax();
00088 
00089         default:
00090                 return T( -1 );
00091         }
00092 
00093         return T( -1 );
00094 }
00095 
00096 template<typename T>
00097 returnValue GenericVector<T>::print(    std::ostream& stream,
00098                                                                                 const std::string& name,
00099                                                                                 const std::string& startString,
00100                                                                                 const std::string& endString,
00101                                                                                 uint width,
00102                                                                                 uint precision,
00103                                                                                 const std::string& colSeparator,
00104                                                                                 const std::string& rowSeparator
00105                                                                                 ) const
00106 {
00107         if (name.size())
00108                 stream << name << " = ";
00109 
00110         stream << startString;
00111 
00112         for (unsigned i = 0; i < getDim(); ++i)
00113         {
00114                 stream << Base::operator()( i );
00115 
00116                 if (i < (getDim() - 1))
00117                         stream << rowSeparator;
00118         }
00119         stream << endString;
00120 
00121         return SUCCESSFUL_RETURN;
00122 }
00123 
00124 template<>
00125 returnValue GenericVector< double >::print(     std::ostream& stream,
00126                                                                                         const std::string& name,
00127                                                                                         const std::string& startString,
00128                                                                                         const std::string& endString,
00129                                                                                         uint width,
00130                                                                                         uint precision,
00131                                                                                         const std::string& colSeparator,
00132                                                                                         const std::string& rowSeparator
00133                                                                                         ) const
00134 {
00135         IoFormatter iof( stream );
00136 
00137         if (name.size())
00138                 stream << name << " = ";
00139 
00140         stream << startString;
00141 
00142         iof.set(precision > 0 ? precision : iof.precision,
00143                         width,
00144                         precision > 0 ? ios::scientific | ios::right : ios::fixed);
00145 
00146         for (unsigned i = 0; i < getDim(); ++i)
00147         {
00148                 stream << Base::operator()( i );
00149 
00150                 if (i < (getDim() - 1))
00151                         stream << rowSeparator;
00152         }
00153         stream << endString;
00154 
00155         iof.reset();
00156 
00157         return SUCCESSFUL_RETURN;
00158 }
00159 
00160 template<typename T>
00161 returnValue GenericVector<T>::print(    const std::string& filename,
00162                                                                                 const std::string& name,
00163                                                                                 const std::string& startString,
00164                                                                                 const std::string& endString,
00165                                                                                 uint width,
00166                                                                                 uint precision,
00167                                                                                 const std::string& colSeparator,
00168                                                                                 const std::string& rowSeparator
00169                                                                                 ) const
00170 {
00171         ofstream stream( filename.c_str() );
00172 
00173         if ( stream.is_open() )
00174                 return print(stream, name, startString, endString, width, precision,
00175                                 colSeparator, rowSeparator);
00176         else
00177                 return ACADOERROR( RET_FILE_CAN_NOT_BE_OPENED );
00178 
00179         stream.close();
00180 
00181         return SUCCESSFUL_RETURN;
00182 }
00183 
00184 template<typename T>
00185 returnValue GenericVector<T>::print(    std::ostream& stream,
00186                                                                                 const std::string& name,
00187                                                                                 PrintScheme printScheme
00188                                                                                 ) const
00189 {
00190         MatFile<T>* matFile = 0;
00191 
00192         switch ( printScheme )
00193         {
00194         case PS_MATLAB_BINARY:
00195                 matFile = new MatFile<T>;
00196 
00197                 matFile->write(stream, *this, name.c_str());
00198 
00199                 delete matFile;
00200 
00201                 return SUCCESSFUL_RETURN;
00202 
00203         default:
00204 
00205                 char* startString = 0;
00206                 char* endString = 0;
00207                 uint width = 0;
00208                 uint precision = 0;
00209                 char* colSeparator = 0;
00210                 char* rowSeparator = 0;
00211 
00212                 returnValue ret = getGlobalStringDefinitions(printScheme, &startString,
00213                                 &endString, width, precision, &colSeparator, &rowSeparator);
00214                 if (ret != SUCCESSFUL_RETURN)
00215                         return ret;
00216 
00217                 returnValue status = print(stream, name, startString, endString, width,
00218                                 precision, colSeparator, rowSeparator);
00219 
00220                 if ( startString != 0 )   delete[] startString;
00221                 if ( endString != 0 )     delete[] endString;
00222                 if ( colSeparator != 0 )  delete[] colSeparator;
00223                 if ( rowSeparator != 0 )  delete[] rowSeparator;
00224 
00225                 return status;
00226         }
00227 
00228         return SUCCESSFUL_RETURN;
00229 }
00230 
00231 template<typename T>
00232 returnValue GenericVector<T>::print(    const std::string& filename,
00233                                                                                 const std::string& name,
00234                                                                                 PrintScheme printScheme
00235                                                                                 ) const
00236 {
00237         ofstream stream( filename.c_str() );
00238         returnValue status;
00239 
00240         if ( stream.is_open() )
00241                 status = print(stream, name, printScheme);
00242         else
00243                 return ACADOERROR( RET_FILE_CAN_NOT_BE_OPENED );
00244 
00245         stream.close();
00246 
00247         return status;
00248 }
00249 
00250 template<typename T>
00251 returnValue GenericVector<T>::read( std::istream& stream )
00252 {
00253         vector< T > tmp;
00254         stream >> tmp;
00255 
00256         Base::_set(GenericVector<T>( tmp ));
00257 
00258         return SUCCESSFUL_RETURN;
00259 }
00260 
00261 template<typename T>
00262 returnValue GenericVector<T>::read(     const std::string& filename
00263                                                                         )
00264 {
00265         ifstream stream( filename.c_str() );
00266         returnValue status;
00267 
00268         if (stream.is_open())
00269                 status = read( stream );
00270         else
00271                 return ACADOERROR( RET_FILE_CAN_NOT_BE_OPENED );
00272 
00273         stream.close();
00274 
00275         return status;
00276 }
00277 
00278 //
00279 // Explicit instantiation of templates
00280 //
00281 template class GenericVector<double>;
00282 template class GenericVector<int>;
00283 template class GenericVector<bool>;
00284 
00285 CLOSE_NAMESPACE_ACADO


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