t_evaluation_point.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 
00027 
00034 #ifndef ACADO_TOOLKIT_T_EVALUATION_POINT_HPP
00035 #define ACADO_TOOLKIT_T_EVALUATION_POINT_HPP
00036 
00037 #include <acado/function/ocp_iterate.hpp>
00038 #include <acado/function/function_evaluation_tree.hpp>
00039 
00040 BEGIN_NAMESPACE_ACADO
00041 
00042 
00056 template <typename T> class TevaluationPoint{
00057 
00058 friend class Function;
00059 
00060 //
00061 // PUBLIC MEMBER FUNCTIONS:
00062 //
00063 
00064 public:
00065 
00066 
00068     TevaluationPoint();
00069 
00070 
00072     TevaluationPoint( const Function &f,
00073                       uint  nx_ = 0,
00074                       uint  na_ = 0,
00075                       uint  nu_ = 0,
00076                       uint  np_ = 0,
00077                       uint  nw_ = 0,
00078                       uint  nd_ = 0,
00079                       uint  N_  = 0  );
00080 
00081 
00083     TevaluationPoint( const TevaluationPoint<T>& rhs );
00084 
00086     virtual ~TevaluationPoint( );
00087 
00089     TevaluationPoint<T>& operator=( const TevaluationPoint<T>& rhs );
00090 
00091 
00104     returnValue init( const Function &f,
00105                       uint  nx_ = 0,
00106                       uint  na_ = 0,
00107                       uint  np_ = 0,
00108                       uint  nu_ = 0,
00109                       uint  nw_ = 0,
00110                       uint  nd_ = 0,
00111                       uint  N_  = 0      );
00112 
00113 
00114     inline returnValue setT ( const Tmatrix<T> &t  );
00115     inline returnValue setX ( const Tmatrix<T> &x  );
00116     inline returnValue setXA( const Tmatrix<T> &xa );
00117     inline returnValue setP ( const Tmatrix<T> &p  );
00118     inline returnValue setU ( const Tmatrix<T> &u  );
00119     inline returnValue setW ( const Tmatrix<T> &w  );
00120     inline returnValue setDX( const Tmatrix<T> &dx );
00121 
00122     inline Tmatrix<T> getT () const;
00123     inline Tmatrix<T> getX () const;
00124     inline Tmatrix<T> getXA() const;
00125     inline Tmatrix<T> getP () const;
00126     inline Tmatrix<T> getU () const;
00127     inline Tmatrix<T> getW () const;
00128     inline Tmatrix<T> getDX() const;
00129 
00130 
00131 // PROTECTED MEMBER FUNCTIONS:
00132 // ---------------------------
00133 
00134 protected:
00135 
00136     inline returnValue copy( const int *order, const Tmatrix<T> &rhs );
00137 
00138     void copy( const TevaluationPoint &rhs );
00139     void deleteAll();
00140 
00141     void copyIdx( const uint &dim, const int *idx1, int **idx2 );
00142 
00143     inline Tmatrix<T> backCopy( const int *order, const uint &dim ) const;
00144 
00145     inline Tmatrix<T>* getEvaluationPointer() const;
00146 
00147 
00148 // PROTECTED MEMBERS:
00149 // ------------------
00150 
00151 protected:
00152 
00153     Tmatrix<T> *z;   
00154     int     **idx;   
00156     uint       nx;   
00157     uint       na;   
00158     uint       nu;   
00159     uint       np;   
00160     uint       nw;   
00161     uint       nd;   
00162     uint       N ;   
00163 };
00164 
00165 
00166 CLOSE_NAMESPACE_ACADO
00167 
00168 #include <acado/function/function_.hpp>
00169 
00170 BEGIN_NAMESPACE_ACADO
00171 
00172 
00173 template <typename T> TevaluationPoint<T>::TevaluationPoint( ){ idx = 0; z = 0; }
00174 template <typename T> TevaluationPoint<T>::TevaluationPoint( const TevaluationPoint<T>& rhs ){ copy(rhs); }
00175 template <typename T> TevaluationPoint<T>::~TevaluationPoint(){ deleteAll(); }
00176 
00177 template <typename T> TevaluationPoint<T>::TevaluationPoint( const Function &f ,
00178                                                              uint nx_, uint na_,
00179                                                              uint nu_, uint np_,
00180                                                              uint nw_, uint nd_, uint N_){
00181 
00182     idx = 0;
00183     z = 0;
00184     init(f,nx_,na_,nu_,np_,nw_,nd_,N_);
00185 }
00186 
00187 
00188 
00189 template <typename T> TevaluationPoint<T>& TevaluationPoint<T>::operator=( const TevaluationPoint<T>& rhs ){
00190 
00191     if( this != &rhs ){
00192         deleteAll();
00193         copy(rhs);
00194     }
00195     return *this;
00196 }
00197 
00198 
00199 template <typename T> returnValue TevaluationPoint<T>::init( const Function &f ,
00200                                                              uint nx_, uint na_, uint np_,
00201                                                              uint nu_, uint nw_, uint nd_,
00202                                                              uint N_                       ){
00203 
00204     uint run1;
00205     deleteAll();
00206 
00207     nx = acadoMax( nx_, f.getNX ()                 );
00208     na = acadoMax( na_, f.getNXA()                 );
00209     np = acadoMax( np_, f.getNP ()                 );
00210     nu = acadoMax( nu_, f.getNU ()                 );
00211     nw = acadoMax( nw_, f.getNW ()                 );
00212     nd = acadoMax( nd_, f.getNDX()                 );
00213     N  = acadoMax( N_ , f.getNumberOfVariables()+1 );
00214 
00215     z = new Tmatrix<T>(N);
00216 
00217     idx = new int*[7];
00218 
00219     idx[0] = new int [1 ];
00220     idx[1] = new int [nx];
00221     idx[2] = new int [na];
00222     idx[3] = new int [np];
00223     idx[4] = new int [nu];
00224     idx[5] = new int [nw];
00225     idx[6] = new int [nd];
00226 
00227     idx[0][0] = f.index( VT_TIME, 0 );
00228 
00229     for( run1 = 0; run1 < nx; run1++ )
00230         idx[1][run1] = f.index( VT_DIFFERENTIAL_STATE, run1 );
00231 
00232     for( run1 = 0; run1 < na; run1++ )
00233         idx[2][run1] = f.index( VT_ALGEBRAIC_STATE, run1 );
00234 
00235     for( run1 = 0; run1 < np; run1++ )
00236         idx[3][run1] = f.index( VT_PARAMETER, run1 );
00237 
00238     for( run1 = 0; run1 < nu; run1++ )
00239         idx[4][run1] = f.index( VT_CONTROL, run1 );
00240 
00241     for( run1 = 0; run1 < nw; run1++ )
00242         idx[5][run1] = f.index( VT_DISTURBANCE, run1 );
00243 
00244     for( run1 = 0; run1 < nd; run1++ )
00245         idx[6][run1] = f.index( VT_DDIFFERENTIAL_STATE, run1 );
00246 
00247     return SUCCESSFUL_RETURN;
00248 }
00249 
00250 
00251 
00252 //
00253 // PROTECTED MEMBER FUNCTIONS:
00254 //
00255 
00256 template <typename T> void TevaluationPoint<T>::copyIdx( const uint &dim, const int *idx1, int **idx2 ){
00257 
00258     uint i;
00259     *idx2 = new int[dim];
00260     for( i = 0; i < N; i++ )
00261         *idx2[i] = idx1[i];
00262 }
00263 
00264 
00265 template <typename T> void TevaluationPoint<T>::copy( const TevaluationPoint<T> &rhs ){
00266 
00267     nx = rhs.nx;
00268     na = rhs.na;
00269     np = rhs.np;
00270     nu = rhs.nu;
00271     nw = rhs.nw;
00272     nd = rhs.nd;
00273     N  = rhs.N ;
00274 
00275     if( rhs.z != 0 ){
00276         z = new Tmatrix<T>(*rhs.z);
00277     }
00278     else z = 0;
00279 
00280     if( rhs.idx != 0 ){
00281 
00282         idx = new int*[7];
00283         copyIdx(  1, rhs.idx[0], &idx[0] );
00284         copyIdx( nx, rhs.idx[1], &idx[1] );
00285         copyIdx( na, rhs.idx[2], &idx[2] );
00286         copyIdx( np, rhs.idx[3], &idx[3] );
00287         copyIdx( nu, rhs.idx[4], &idx[4] );
00288         copyIdx( nw, rhs.idx[5], &idx[5] );
00289         copyIdx( nd, rhs.idx[6], &idx[6] );
00290     }
00291     else idx = 0;
00292 }
00293 
00294 
00295 template <typename T> void TevaluationPoint<T>::deleteAll(){
00296 
00297     if( z != 0 ) delete z;
00298   
00299     if( idx != 0 ){
00300         uint i;
00301         for( i = 0; i < 7; i++ )
00302             delete[] idx[i];
00303         delete[] idx;
00304     }
00305 }
00306 
00307 CLOSE_NAMESPACE_ACADO
00308 
00309 
00310 
00311 #include <acado/function/t_evaluation_point.ipp>
00312 
00313 
00314 #endif  // ACADO_TOOLKIT_T_EVALUATION_POINT_HPP
00315 
00316 /*
00317  *   end of file
00318  */


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