addition.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 
00027 
00035 #include <acado/utils/acado_utils.hpp>
00036 #include <acado/symbolic_operator/symbolic_operator.hpp>
00037 
00038 
00039 
00040 BEGIN_NAMESPACE_ACADO
00041 
00042 
00043 
00044 
00045 Addition::Addition( )
00046          :BinaryOperator( ){}
00047 
00048 
00049 Addition::Addition( Operator *_argument1, Operator *_argument2 )
00050          :BinaryOperator( _argument1, _argument2 ){}
00051 
00052 
00053 Addition::Addition( const Addition &arg )
00054          :BinaryOperator( arg ){}
00055 
00056 
00057 Addition::~Addition(){}
00058 
00059 
00060 Addition& Addition::operator=( const Addition &arg ){
00061 
00062     if( this != &arg ){
00063 
00064         BinaryOperator::operator=( arg );
00065     }
00066     return *this;
00067 }
00068 
00069 
00070 returnValue Addition::evaluate( int number, double *x, double *result ){
00071 
00072     if( number >= bufferSize ){
00073         bufferSize += number;
00074         argument1_result  = (double*)realloc( argument1_result,bufferSize*sizeof(double));
00075         argument2_result  = (double*)realloc( argument2_result,bufferSize*sizeof(double));
00076         dargument1_result = (double*)realloc(dargument1_result,bufferSize*sizeof(double));
00077         dargument2_result = (double*)realloc(dargument2_result,bufferSize*sizeof(double));
00078     }
00079 
00080     argument1->evaluate( number, x , &argument1_result[number] );
00081     argument2->evaluate( number, x , &argument2_result[number] );
00082 
00083     result[0] = argument1_result[number] + argument2_result[number];
00084 
00085     return SUCCESSFUL_RETURN;
00086 }
00087 
00088 
00089 returnValue Addition::evaluate( EvaluationBase *x ){
00090 
00091     x->addition(*argument1,*argument2);
00092     return SUCCESSFUL_RETURN;
00093 }
00094 
00095 
00096 Operator* Addition::differentiate( int index ){
00097 
00098   dargument1 = argument1->differentiate( index );
00099   dargument2 = argument2->differentiate( index );
00100 
00101   return myAdd( dargument1, dargument2 );
00102 
00103 }
00104 
00105 
00106 
00107 Operator* Addition::AD_forward( int dim,
00108                                   VariableType *varType,
00109                                   int *component,
00110                                   Operator **seed,
00111                                   int &nNewIS,
00112                                   TreeProjection ***newIS ){
00113 
00114     if( dargument1 != 0 )
00115         delete dargument1;
00116 
00117     if( dargument2 != 0 )
00118         delete dargument2;
00119 
00120     dargument1 = argument1->AD_forward(dim,varType,component,seed,nNewIS,newIS);
00121     dargument2 = argument2->AD_forward(dim,varType,component,seed,nNewIS,newIS);
00122 
00123     return myAdd( dargument1, dargument2 );
00124 }
00125 
00126 
00127 returnValue Addition::AD_backward( int           dim      , 
00128                                         VariableType *varType  , 
00129                                         int          *component, 
00130                                         Operator     *seed     , 
00131                                         Operator    **df       , 
00132                                         int           &nNewIS  , 
00133                                         TreeProjection ***newIS   ){
00134 
00135     TreeProjection tmp;
00136     tmp = *seed;
00137 
00138     argument1->AD_backward( dim, varType, component, tmp.clone(), df, nNewIS, newIS );
00139     argument2->AD_backward( dim, varType, component, tmp.clone(), df, nNewIS, newIS );
00140 
00141     delete seed;
00142 
00143     return SUCCESSFUL_RETURN;
00144 }
00145 
00146 
00147 
00148 returnValue Addition::AD_symmetric( int            dim       , 
00149                                         VariableType  *varType   , 
00150                                         int           *component , 
00151                                         Operator      *l         , 
00152                                         Operator     **S         , 
00153                                         int            dimS      , 
00154                                         Operator     **dfS       , 
00155                                         Operator     **ldf       , 
00156                                         Operator     **H         , 
00157                                       int            &nNewLIS  , 
00158                                       TreeProjection ***newLIS , 
00159                                       int            &nNewSIS  , 
00160                                       TreeProjection ***newSIS , 
00161                                       int            &nNewHIS  , 
00162                                       TreeProjection ***newHIS    ){
00163   
00164     TreeProjection dx,dy,dxx,dxy,dyy;
00165     
00166     dx  = DoubleConstant(1.0,NE_ONE );
00167     dy  = DoubleConstant(1.0,NE_ONE );
00168     dxx = DoubleConstant(0.0,NE_ZERO);
00169     dxy = DoubleConstant(0.0,NE_ZERO);
00170     dyy = DoubleConstant(0.0,NE_ZERO);
00171     
00172     return ADsymCommon2( argument1,argument2,dx,dy,dxx,dxy,dyy, dim, varType, component, l, S, dimS, dfS,
00173                           ldf, H, nNewLIS, newLIS, nNewSIS, newSIS, nNewHIS, newHIS );
00174 }
00175 
00176 
00177 
00178 Operator* Addition::substitute( int index, const Operator *sub ){
00179 
00180     return new Addition( argument1->substitute( index , sub ),
00181                          argument2->substitute( index , sub ) );
00182 
00183 }
00184 
00185 
00186 BooleanType Addition::isLinearIn( int dim,
00187                                     VariableType *varType,
00188                                     int *component,
00189                                     BooleanType   *implicit_dep ){
00190 
00191     if( argument1->isLinearIn( dim, varType, component, implicit_dep )  == BT_TRUE &&
00192         argument2->isLinearIn( dim, varType, component, implicit_dep )  == BT_TRUE ){
00193         return BT_TRUE;
00194     }
00195 
00196     return BT_FALSE;
00197 }
00198 
00199 
00200 BooleanType Addition::isPolynomialIn( int dim,
00201                                         VariableType *varType,
00202                                         int *component,
00203                                         BooleanType   *implicit_dep ){
00204 
00205     if( argument1->isPolynomialIn( dim, varType, component, implicit_dep ) == BT_TRUE &&
00206         argument2->isPolynomialIn( dim, varType, component, implicit_dep ) == BT_TRUE ){
00207         return BT_TRUE;
00208     }
00209 
00210     return BT_FALSE;
00211 }
00212 
00213 
00214 BooleanType Addition::isRationalIn( int dim,
00215                                       VariableType *varType,
00216                                       int *component,
00217                                       BooleanType   *implicit_dep ){
00218 
00219     if( argument1->isRationalIn( dim, varType, component, implicit_dep ) == BT_TRUE &&
00220         argument2->isRationalIn( dim, varType, component, implicit_dep ) == BT_TRUE ){
00221         return BT_TRUE;
00222     }
00223 
00224     return BT_FALSE;
00225 }
00226 
00227 
00228 MonotonicityType Addition::getMonotonicity( ){
00229 
00230     if( monotonicity != MT_UNKNOWN )  return monotonicity;
00231 
00232     MonotonicityType m1, m2;
00233 
00234     m1 = argument1->getMonotonicity();
00235     m2 = argument2->getMonotonicity();
00236 
00237     if( m1 == MT_CONSTANT ){
00238 
00239         if( m2 == MT_CONSTANT      )  return MT_CONSTANT     ;
00240         if( m2 == MT_NONDECREASING )  return MT_NONDECREASING;
00241         if( m2 == MT_NONINCREASING )  return MT_NONINCREASING;
00242 
00243         return MT_NONMONOTONIC;
00244     }
00245 
00246     if( m1 == MT_NONDECREASING ){
00247 
00248         if( m2 == MT_CONSTANT      )  return MT_NONDECREASING;
00249         if( m2 == MT_NONDECREASING )  return MT_NONDECREASING;
00250 
00251         return MT_NONMONOTONIC;
00252     }
00253 
00254     if( m1 == MT_NONINCREASING ){
00255 
00256         if( m2 == MT_CONSTANT      )  return MT_NONINCREASING;
00257         if( m2 == MT_NONINCREASING )  return MT_NONINCREASING;
00258 
00259         return MT_NONMONOTONIC;
00260     }
00261 
00262     return MT_NONMONOTONIC;
00263 }
00264 
00265 
00266 CurvatureType Addition::getCurvature( ){
00267 
00268     if( curvature != CT_UNKNOWN )  return curvature;
00269 
00270     CurvatureType c1, c2;
00271 
00272     c1 = argument1->getCurvature();
00273     c2 = argument2->getCurvature();
00274 
00275     if( c1 == CT_CONSTANT )  return c2;
00276 
00277     if( c1 == CT_AFFINE ){
00278 
00279         if( c2 == CT_CONSTANT )  return CT_AFFINE  ;
00280         if( c2 == CT_AFFINE   )  return CT_AFFINE  ;
00281         if( c2 == CT_CONVEX   )  return CT_CONVEX  ;
00282         if( c2 == CT_CONCAVE  )  return CT_CONCAVE ;
00283     }
00284 
00285     if( c1 == CT_CONVEX ){
00286 
00287         if( c2 == CT_CONSTANT )  return CT_CONVEX  ;
00288         if( c2 == CT_AFFINE   )  return CT_CONVEX  ;
00289         if( c2 == CT_CONVEX   )  return CT_CONVEX  ;
00290 
00291         return CT_NEITHER_CONVEX_NOR_CONCAVE;
00292     }
00293 
00294     if( c1 == CT_CONCAVE ){
00295 
00296         if( c2 == CT_CONSTANT )  return CT_CONCAVE ;
00297         if( c2 == CT_AFFINE   )  return CT_CONCAVE ;
00298         if( c2 == CT_CONCAVE  )  return CT_CONCAVE ;
00299 
00300         return CT_NEITHER_CONVEX_NOR_CONCAVE;
00301     }
00302 
00303     return CT_NEITHER_CONVEX_NOR_CONCAVE;
00304 }
00305 
00306 
00307 double Addition::getValue() const
00308 { 
00309         if ( ( argument1 == 0 ) || ( argument2 == 0 ) )
00310                 return INFTY;
00311                 
00312         if ( ( acadoIsEqual( argument1->getValue(),INFTY ) == BT_TRUE ) ||
00313                  ( acadoIsEqual( argument2->getValue(),INFTY ) == BT_TRUE ) )
00314                 return INFTY;
00315                 
00316         return (argument1->getValue() + argument2->getValue());
00317 }
00318 
00319 
00320 returnValue Addition::AD_forward( int number, double *x, double *seed,
00321                                   double *f, double *df ){
00322 
00323     if( number >= bufferSize ){
00324         bufferSize += number;
00325         argument1_result  = (double*)realloc( argument1_result,bufferSize*sizeof(double));
00326         argument2_result  = (double*)realloc( argument2_result,bufferSize*sizeof(double));
00327         dargument1_result = (double*)realloc(dargument1_result,bufferSize*sizeof(double));
00328         dargument2_result = (double*)realloc(dargument2_result,bufferSize*sizeof(double));
00329     }
00330 
00331     argument1->AD_forward( number, x, seed, &argument1_result[number],
00332                            &dargument1_result[number] );
00333     argument2->AD_forward( number, x, seed, &argument2_result[number],
00334                            &dargument2_result[number] );
00335 
00336       f[0] =  argument1_result[number] +  argument2_result[number];
00337      df[0] = dargument1_result[number] + dargument2_result[number];
00338 
00339      return SUCCESSFUL_RETURN;
00340 }
00341 
00342 
00343 
00344 returnValue Addition::AD_forward( int number, double *seed, double *df ){
00345 
00346     argument1->AD_forward( number, seed, &dargument1_result[number] );
00347     argument2->AD_forward( number, seed, &dargument2_result[number] );
00348 
00349      df[0] = dargument1_result[number] + dargument2_result[number];
00350 
00351      return SUCCESSFUL_RETURN;
00352 }
00353 
00354 
00355 returnValue Addition::AD_backward( int number, double seed, double *df ){
00356 
00357     argument1->AD_backward( number, seed, df );
00358     argument2->AD_backward( number, seed, df );
00359 
00360     return SUCCESSFUL_RETURN;
00361 }
00362 
00363 
00364 returnValue Addition::AD_forward2( int number, double *seed, double *dseed,
00365                                    double *df, double *ddf ){
00366 
00367     double      ddargument1_result;
00368     double      ddargument2_result;
00369     double      dargument_result1;
00370     double      dargument_result2;
00371 
00372     argument1->AD_forward2( number, seed, dseed,
00373                             &dargument_result1, &ddargument1_result);
00374     argument2->AD_forward2( number, seed, dseed,
00375                             &dargument_result2, &ddargument2_result);
00376 
00377      df[0] =  dargument_result1  +  dargument_result2 ;
00378     ddf[0] = ddargument1_result  + ddargument2_result ;
00379 
00380     return SUCCESSFUL_RETURN;
00381 }
00382 
00383 
00384 returnValue Addition::AD_backward2( int number, double seed1, double seed2,
00385                                        double *df, double *ddf ){
00386 
00387     argument1->AD_backward2( number,  seed1,  seed2, df, ddf );
00388     argument2->AD_backward2( number,  seed1,  seed2, df, ddf );
00389 
00390     return SUCCESSFUL_RETURN;
00391 }
00392 
00393 
00394 std::ostream& Addition::print( std::ostream &stream ) const{
00395 
00396         if ( ( acadoIsFinite( argument1->getValue() ) == BT_FALSE ) ||
00397                  ( acadoIsFinite( argument2->getValue() ) == BT_FALSE ) )
00398         {
00399                 return stream << "(" << *argument1 << "+" << *argument2 << ")";
00400         }
00401         else
00402         {
00403                 return stream << "((real_t)(" << (argument1->getValue() + argument2->getValue()) << "))";
00404         }
00405 }
00406 
00407 
00408 Operator* Addition::clone() const{
00409 
00410     if( argument1 != 0 && argument2 != 0 ){
00411         if( argument1->isOneOrZero() == NE_ZERO ) return argument2->clone();
00412         if( argument2->isOneOrZero() == NE_ZERO ) return argument1->clone();
00413     }
00414 
00415     return new Addition(*this);
00416 }
00417 
00418 
00419 OperatorName Addition::getName(){
00420 
00421     return ON_ADDITION;
00422 
00423 }
00424 
00425 
00426 
00427 CLOSE_NAMESPACE_ACADO
00428 
00429 // end of file.


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