function_.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_FUNCTION__HPP
00035 #define ACADO_TOOLKIT_FUNCTION__HPP
00036 
00037 
00038 #include <acado/function/function_evaluation_tree.hpp>
00039 
00040 
00041 BEGIN_NAMESPACE_ACADO
00042 
00043 
00044 class EvaluationPoint;
00045 template <typename T> class TevaluationPoint;
00046 
00047 
00059 class Function{
00060 
00061 //
00062 // PUBLIC MEMBER FUNCTIONS:
00063 //
00064 
00065 public:
00066 
00068     Function();
00069 
00071     Function( const Function& rhs );
00072 
00074     virtual ~Function( );
00075 
00077     Function& operator=( const Function& rhs );
00078 
00079 
00081     Function& operator<<( const Expression& arg );
00082 
00084     Function& operator<<( const double &arg );
00085 
00087     Function& operator<<( const DVector& arg );
00088 
00090     Function& operator<<( const DMatrix& arg );
00091 
00092         Function operator()(    uint idx
00093                                                         ) const;
00094 
00095 
00096     returnValue getExpression( Expression& expression ) const;
00097 
00098 
00099         returnValue reset( );
00100 
00101 
00105     inline int getDim () const;
00106 
00107 
00112     inline int getN   () const;
00113 
00117     int getN    (VariableType &variableType_) const;
00118 
00122     int getNX    () const;
00123 
00127     int getNXA   () const;
00128 
00133     int getNDX   () const;
00134 
00138     int getNU   () const;
00139 
00143     int getNUI  () const;
00144 
00148     int getNP   () const;
00149 
00153     int getNPI  () const;
00154 
00158     int getNW  () const;
00159 
00163     int getNT  () const;
00164 
00166     int getNOD() const;
00167 
00168 
00173     int index( VariableType variableType_, int index_ ) const;
00174 
00175 
00180     double scale( VariableType variableType_, int index_ ) const;
00181 
00182 
00186     int getNumberOfVariables() const;
00187 
00191     Operator* getExpression(    uint componentIdx
00192                                                                 ) const;
00193 
00194 
00202     DVector evaluate( const EvaluationPoint &x         ,
00203                      const int             &number = 0  );
00204 
00205 
00214     inline DVector operator()( const EvaluationPoint &x         ,
00215                               const int             &number = 0  );
00216 
00217 
00218 
00226     template <typename T> Tmatrix<T> evaluate( const TevaluationPoint<T> &x );
00227         
00228         
00229         
00236     returnValue evaluate( int     number    ,
00237                           double *x         ,
00238                           double *_result      );
00239 
00240 
00241 
00246      returnValue substitute( VariableType variableType_,
00247                              int index_      ,
00248                              double sub_      );
00249 
00250 
00251 
00258      NeutralElement isOneOrZero();
00259 
00260 
00261 
00268      BooleanType isDependingOn( const Expression     &variable );
00269 
00270 
00271 
00279      BooleanType isLinearIn( const Expression     &variable );
00280 
00281 
00282 
00289      BooleanType isPolynomialIn( const Expression     &variable );
00290 
00291 
00292 
00293 
00300      BooleanType isRationalIn( const Expression     &variable );
00301 
00302 
00303 
00309      BooleanType isNondecreasing();
00310 
00311 
00317      BooleanType isNonincreasing();
00318 
00320      BooleanType isConstant();
00321 
00327      BooleanType isAffine();
00328 
00329 
00335      BooleanType isConvex();
00336 
00337 
00343      BooleanType isConcave();
00344 
00345 
00346 
00354     DVector AD_forward( const EvaluationPoint &x         ,
00355                        const int             &number = 0  );
00356 
00357 
00358 
00365      returnValue AD_forward(  int     number  ,
00366                               double *seed    ,
00367                               double *df        );
00369 
00370 
00371 
00380      returnValue AD_backward( const    DVector &seed      ,
00381                               EvaluationPoint &df        ,
00382                               const    int    &number = 0  );
00383 
00384 
00390      returnValue AD_backward( int    number ,
00392                               double *seed  ,
00393                               double  *df     );
00395 
00396 
00397 
00405      returnValue AD_forward2( int    number  ,
00407                               double *seed1  ,
00408                               double *seed2  ,
00410                               double *df     ,
00412                               double *ddf    );
00414 
00415 
00416 
00424      returnValue AD_backward2( int    number  ,
00426                                double *seed1  ,
00427                                double *seed2  ,
00428                                double    *df  ,
00430                                double   *ddf     );
00432 
00433 
00440     returnValue jacobian(DMatrix &x);
00441     //returnValue jacobian(DMatrix &x,DMatrix &p=emptyMatrix,DMatrix &u=emptyMatrix,DMatrix &w=emptyMatrix);
00442 
00444     friend std::ostream& operator<<( std::ostream& stream, const Function &arg);
00445 
00456      returnValue print( std::ostream& stream,
00457                                                 const char *fcnName = "ACADOfcn",
00458                                                 const char *realString = "double"
00459                                                 ) const;
00460 
00461      returnValue exportForwardDeclarations(     std::ostream& stream,
00462                                                                                         const char *fcnName = "ACADOfcn",
00463                                                                                         const char *realString = "double"
00464                                                                                         ) const;
00465 
00466      returnValue exportCode(    std::ostream& stream,
00467                                                                 const char *fcnName = "ACADOfcn",
00468                                                                 const char *realString = "double",
00469                                                                 uint        _numX = 0,     
00470                                                                 uint        _numXA = 0,
00471                                                                 uint            _numU = 0,
00472                                                                 uint            _numP = 0,
00473                                                                 uint            _numDX = 0,
00474                                                                 uint            _numOD = 0,
00475                                                                 bool       allocateMemory = true,
00476                                                                 bool       staticMemory   = false
00477                                                                 ) const;
00478 
00483      returnValue clearBuffer();
00484 
00485 
00486 
00490      returnValue setScale( double *scale_ );
00491 
00492 
00497      inline BooleanType isSymbolic() const;
00498 
00499 
00500      inline BooleanType ADisSupported() const;
00501 
00502 
00503      inline returnValue setMemoryOffset( int memoryOffset_ );
00504 
00506      returnValue setGlobalExportVariableName(const std::string& var);
00507 
00509      std::string getGlobalExportVariableName( ) const;
00510 
00512      unsigned getGlobalExportVariableSize( ) const;
00513 
00514 // PROTECTED MEMBERS:
00515 // ------------------
00516 
00517 protected:
00518 
00519     FunctionEvaluationTree evaluationTree;
00520     int                    memoryOffset  ;
00521         
00522         double* result;
00523 };
00524 
00525 
00526 template <typename T> Tmatrix<T> Function::evaluate( const TevaluationPoint<T> &x ){
00527 
00528         Tmatrix<T> Tresult(getDim());
00529         evaluationTree.evaluate( x.getEvaluationPointer(), &Tresult );
00530         return Tresult;
00531 }
00532 
00533 
00534 CLOSE_NAMESPACE_ACADO
00535 
00536 
00537 
00538 #include <acado/function/function.ipp>
00539 
00540 
00541 #endif  // ACADO_TOOLKIT_FUNCTION__HPP
00542 
00543 /*
00544  *   end of file
00545  */


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