expression.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 
00034 #ifndef ACADO_TOOLKIT_EXPRESSION_HPP
00035 #define ACADO_TOOLKIT_EXPRESSION_HPP
00036 
00037 #include <acado/utils/acado_utils.hpp>
00038 #include <acado/matrix_vector/matrix_vector.hpp>
00039 
00040 BEGIN_NAMESPACE_ACADO
00041 
00042 class Operator;
00043 
00056 class Expression
00057 {
00058         friend class COperator;
00059         friend class CFunction;
00060         friend class FunctionEvaluationTree;
00061 
00062 public:
00064         Expression( );
00065 
00067         Expression( const Operator &tree_ );
00068 
00070         explicit Expression(    const std::string& name_
00071                                                         );
00072 
00074         explicit Expression(    const std::string&  name_,                                                      
00075                                                         uint                    nRows_,                                                 
00076                                                         uint                    nCols_,                                                 
00077                                                         VariableType            variableType_  = VT_UNKNOWN,    
00078                                                         uint                    globalTypeID   = 0                              
00079                                                         );
00080 
00082         explicit Expression(    int          nRows_                     ,  
00083                                                         int          nCols_         = 1         ,  
00084                                                         VariableType variableType_  = VT_UNKNOWN,  
00085                                                         int          globalTypeID   = 0            
00086                                                         );
00087 
00089         explicit Expression(    uint         nRows_                     ,  
00090                                                         uint         nCols_         = 1         ,  
00091                                                         VariableType variableType_  = VT_UNKNOWN,  
00092                                                         uint         globalTypeID   = 0            
00093                                                         );
00094 
00096         Expression( const double& rhs );
00097         Expression( const DVector      & rhs );
00098         Expression( const DMatrix      & rhs );
00099         Expression( const Expression  & rhs );
00100 
00102         virtual ~Expression( );
00103 
00105         virtual Expression* clone() const
00106         { return new Expression( *this ); }
00107 
00109         Expression& operator=( const Expression& arg );
00110 
00112         Expression& operator<<( const Expression  & arg );
00113 
00120         Expression&  appendRows(const Expression& arg);
00121         
00128         Expression&  appendCols(const Expression& arg);
00129 
00130         Expression operator()( uint idx                 ) const;
00131         Expression operator()( uint rowIdx, uint colIdx ) const;
00132 
00133         Operator& operator()( uint idx                 );
00134         Operator& operator()( uint rowIdx, uint colIdx );
00135 
00136         friend Expression operator+( const Expression  & arg1, const Expression  & arg2 );
00137         friend Expression operator-( const Expression  & arg1, const Expression  & arg2 );
00138         Expression operator-( ) const;
00139         friend Expression operator*( const Expression  & arg1, const Expression  & arg2 );
00140         friend Expression operator/( const Expression  & arg1, const Expression  & arg2 );
00141 
00142         Expression& operator+=(const Expression &arg);
00143         Expression& operator-=(const Expression &arg);
00144         Expression& operator*=(const Expression &arg);
00145         Expression& operator/=(const Expression &arg);
00146 
00147         std::ostream& print( std::ostream &stream ) const;
00148         friend std::ostream& operator<<( std::ostream& stream, const Expression &arg );
00149 
00151         Expression getInverse( ) const;
00152         
00153         Expression getRow( const uint& rowIdx ) const;
00154         Expression getRows( const uint& rowIdx1, const uint& rowIdx2 ) const;
00155         Expression getCol( const uint& colIdx ) const;
00156         Expression getCols( const uint& colIdx1, const uint& colIdx2 ) const;
00157         Expression getSubMatrix( const uint& rowIdx1, const uint& rowIdx2, const uint& colIdx1, const uint& colIdx2 ) const;
00158         
00163         DMatrix getDependencyPattern( const Expression& arg ) const;
00164 
00165         DMatrix getSparsityPattern() const;
00166 
00167         Expression getSin    ( ) const;
00168         Expression getCos    ( ) const;
00169         Expression getTan    ( ) const;
00170         Expression getAsin   ( ) const;
00171         Expression getAcos   ( ) const;
00172         Expression getAtan   ( ) const;
00173         Expression getExp    ( ) const;
00174         Expression getSqrt   ( ) const;
00175         Expression getLn     ( ) const;
00176 
00177         Expression getPow   ( const Expression &arg ) const;
00178         Expression getPowInt( const int        &arg ) const;
00179 
00180         Expression getSumSquare    ( ) const;
00181         Expression getLogSumExp    ( ) const;
00182         Expression getEuclideanNorm( ) const;
00183         Expression getEntropy      ( ) const;
00184 
00185         Expression getDot          ( ) const;
00186         Expression getNext         ( ) const;
00187 
00188         Expression ADforward  ( const Expression &arg ) const;
00189         Expression ADforward  ( const VariableType &varType_, const int *arg, int nV ) const;
00190         Expression ADbackward ( const Expression &arg ) const;
00191         
00209         Expression ADsymmetric( const Expression &arg, 
00210                                                         const Expression &S  , 
00211                                                         const Expression &l  , 
00212                                                         Expression *dfS = 0,    
00213                                                         Expression *ldf = 0    
00214                                                         ) const;
00215         
00233         Expression ADsymmetric( const Expression &arg, 
00234                                                         const Expression &l  , 
00235                                                         Expression *dfS = 0,    
00236                                                         Expression *ldf = 0    
00237                                                         ) const;
00238         
00239         Expression getODEexpansion( const int &order, const int *arg ) const;
00240 
00241         Expression ADforward ( const Expression &arg, const Expression &seed ) const;
00242         Expression ADforward ( const VariableType &varType_, const int *arg, const Expression &seed ) const;
00243         Expression ADforward ( const VariableType *varType_, const int *arg, const Expression &seed ) const;
00244         Expression ADbackward( const Expression &arg, const Expression &seed ) const;
00245 
00248         Expression transpose( ) const;
00249 
00252         inline uint getDim( ) const;
00253 
00256         inline uint getNumRows( ) const;
00257 
00260         inline uint getNumCols( ) const;
00261 
00264         inline uint getComponent( const unsigned int idx ) const;
00265 
00268         inline BooleanType isVariable( ) const;
00269 
00272         Operator* getOperatorClone( uint idx ) const;
00273 
00276         inline VariableType getVariableType( ) const;
00277 
00278         BooleanType isDependingOn( VariableType type ) const;
00279         BooleanType isDependingOn(const  Expression &e ) const;
00280 
00282         returnValue substitute( int idx, const Expression &arg ) const;
00283 
00284 protected:
00285 
00286         Expression add(const Expression& arg) const;
00287         Expression sub(const Expression& arg) const;
00288         Expression mul(const Expression& arg) const;
00289         Expression div(const Expression& arg) const;
00290 
00292         void construct( VariableType  variableType_,  
00293                                         uint          globalTypeID_,  
00294                                         uint                 nRows_,  
00295                                         uint                 nCols_,  
00296                                         const std::string&   name_     );
00297 
00299         void copy( const Expression &rhs );
00300 
00302         void deleteAll( );
00303 
00306         Expression& assignmentSetup( const Expression &arg );
00307 
00309         Operator* product( const Operator *a, const Operator *b ) const;
00310 
00311         Operator**         element     ;   
00312         uint               dim         ;   
00313         uint               nRows, nCols;   
00314         VariableType       variableType;   
00315         uint               component   ;   
00316         std::string             name   ;   
00317 };
00318 
00319 CLOSE_NAMESPACE_ACADO
00320 
00321 #include <acado/symbolic_expression/expression.ipp>
00322 
00323 BEGIN_NAMESPACE_ACADO
00324 
00339 template<class Derived, VariableType Type, bool AllowCounter = true>
00340 class ExpressionType : public Expression
00341 {
00342 public:
00343 
00345         ExpressionType()
00346                 : Expression("", 1, 1, Type, AllowCounter ? count : 0)
00347         {
00348                 if (AllowCounter == true)
00349                         count++;
00350         }
00351 
00353         ExpressionType(const std::string& _name, unsigned _nRows, unsigned _nCols)
00354                 : Expression(_name, _nRows, _nCols, Type, AllowCounter ? count : 0)
00355         {
00356                 if (AllowCounter == true)
00357                         count += _nRows * _nCols;
00358         }
00359 
00361         ExpressionType(const Expression& _expression, unsigned _componentIdx = 0)
00362                 : Expression( _expression )
00363         {
00364                 variableType = Type;
00365                 component += _componentIdx;
00366                 if (AllowCounter == true)
00367                         count++;
00368         }
00369 
00371         ExpressionType( const double& _arg )
00372                 : Expression( _arg )
00373         {}
00374 
00376         ExpressionType( const DVector& _arg )
00377                 : Expression( _arg )
00378         {}
00379 
00381         ExpressionType( const DMatrix& _arg )
00382                 : Expression( _arg )
00383         {}
00384 
00386         ExpressionType( const Operator& _arg )
00387                 : Expression( _arg )
00388         {}
00389 
00391         virtual ~ExpressionType() {}
00392 
00394         virtual Expression* clone() const
00395         { return new Derived( static_cast< Derived const& >( *this ) ); }
00396 
00398         returnValue clearStaticCounters()
00399         { count = 0; return SUCCESSFUL_RETURN; }
00400 
00401 private:
00402         static unsigned count;
00403 };
00404 
00405 template<class Derived, VariableType Type, bool AllowCounter>
00406 unsigned ExpressionType<Derived, Type, AllowCounter>::count( 0 );
00407 
00408 CLOSE_NAMESPACE_ACADO
00409 
00410 #endif  // ACADO_TOOLKIT_EXPRESSION_HPP


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