00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00035 #include <acado/utils/acado_utils.hpp>
00036 #include <acado/symbolic_operator/symbolic_operator.hpp>
00037
00038
00039 BEGIN_NAMESPACE_ACADO
00040
00041
00042 UnaryOperator::UnaryOperator() : SmoothOperator( )
00043 {
00044 fcn = 0;
00045 dfcn = 0;
00046 ddfcn = 0;
00047 nCount = 0;
00048
00049 derivative = 0;
00050 derivative2 = 0;
00051 }
00052
00053 UnaryOperator::UnaryOperator( Operator *_argument ) : SmoothOperator( )
00054 {
00055 fcn = 0;
00056 dfcn = 0;
00057 ddfcn = 0;
00058
00059 argument = _argument ;
00060 dargument = NULL ;
00061 argument_result = (double*)calloc(1,sizeof(double));
00062 dargument_result = (double*)calloc(1,sizeof(double));
00063 bufferSize = 1 ;
00064 curvature = CT_UNKNOWN ;
00065 monotonicity = MT_UNKNOWN ;
00066
00067 nCount = 0;
00068
00069 derivative = 0;
00070 derivative2 = 0;
00071 }
00072
00073
00074 UnaryOperator::UnaryOperator( const UnaryOperator &arg ){
00075
00076 int run1;
00077
00078 fcn = 0;
00079 dfcn = 0;
00080 ddfcn = 0;
00081
00082 bufferSize = arg.bufferSize;
00083
00084 argument = arg.argument->clone();
00085 derivative = 0;
00086 derivative2 = 0;
00087 if( arg.derivative != 0 ) derivative = arg.derivative->clone();
00088 if( arg.derivative2 != 0 ) derivative2 = arg.derivative2->clone();
00089
00090
00091
00092
00093 if( arg.dargument == 0 ) dargument = 0;
00094 else dargument = arg.dargument->clone();
00095
00096 argument_result = (double*)calloc(bufferSize,sizeof(double));
00097 dargument_result = (double*)calloc(bufferSize,sizeof(double));
00098
00099 for( run1 = 0; run1 < bufferSize; run1++ ){
00100
00101 argument_result[run1] = arg.argument_result[run1];
00102 dargument_result[run1] = arg.dargument_result[run1];
00103 }
00104
00105 curvature = arg.curvature ;
00106 monotonicity = arg.monotonicity;
00107 cName = arg.cName ;
00108
00109 nCount = 0;
00110 }
00111
00112
00113 UnaryOperator::~UnaryOperator(){
00114
00115
00116
00117 if( argument != 0 ){
00118
00119 if( argument->nCount == 0 ){
00120 delete argument;
00121 argument = 0;
00122 }
00123 else{
00124 argument->nCount--;
00125 }
00126 }
00127 if( derivative != 0 ){
00128
00129 if( derivative2 == derivative ) derivative2 = 0;
00130 delete derivative;
00131 derivative = 0;
00132 }
00133 if( derivative2 != 0 ){
00134
00135 delete derivative2;
00136 derivative2 = 0;
00137 }
00138 if( dargument != 0 ) delete dargument;
00139
00140 free( argument_result );
00141 free( dargument_result );
00142 }
00143
00144
00145 UnaryOperator& UnaryOperator::operator=( const UnaryOperator &arg ){
00146
00147 if( this != &arg ){
00148
00149
00150
00151
00152
00153 if( argument != 0 ){
00154
00155 if( argument->nCount == 0 ){
00156 delete argument;
00157 argument = 0;
00158 }
00159 else{
00160 argument->nCount--;
00161 }
00162 }
00163 if( derivative != 0 ){
00164
00165 if( derivative2 == derivative ) derivative2 = 0;
00166 delete derivative;
00167 derivative = 0;
00168 }
00169 if( derivative2 != 0 ){
00170
00171 delete derivative2;
00172 derivative2 = 0;
00173 }
00174 if( dargument != 0 ) delete dargument;
00175
00176 free( argument_result );
00177 free( dargument_result );
00178
00179 argument = arg.argument->clone();
00180 if( arg.derivative != 0 ) derivative = arg.derivative->clone();
00181 if( arg.derivative2 != 0 ) derivative2 = arg.derivative2->clone();
00182
00183
00184
00185
00186 dargument = NULL ;
00187 bufferSize = arg.bufferSize ;
00188 argument_result = (double*)calloc(bufferSize,sizeof(double)) ;
00189 dargument_result = (double*)calloc(bufferSize,sizeof(double)) ;
00190
00191 curvature = arg.curvature ;
00192 monotonicity = arg.monotonicity;
00193 cName = arg.cName ;
00194
00195 nCount = 0;
00196 }
00197 return *this;
00198 }
00199
00200
00201 returnValue UnaryOperator::evaluate( int number, double *x, double *result ){
00202
00203 if( number >= bufferSize ){
00204 bufferSize += number;
00205 argument_result = (double*)realloc( argument_result,bufferSize*sizeof(double));
00206 dargument_result = (double*)realloc(dargument_result,bufferSize*sizeof(double));
00207 }
00208 argument->evaluate( number, x , &argument_result[number] );
00209 result[0] = (*fcn)( argument_result[number] );
00210 return SUCCESSFUL_RETURN;
00211
00212 }
00213
00214
00215 Operator* UnaryOperator::AD_forward( int dim ,
00216 VariableType *varType ,
00217 int *component,
00218 Operator **seed ,
00219 int &nNewIS ,
00220 TreeProjection ***newIS ){
00221
00222 return ADforwardProtected( dim, varType, component, seed, nNewIS, newIS );
00223 }
00224
00225
00226 returnValue UnaryOperator::AD_backward( int dim ,
00227 VariableType *varType ,
00228 int *component,
00229 Operator *seed ,
00230 Operator **df ,
00231 int &nNewIS ,
00232 TreeProjection ***newIS ){
00233
00234 return ADbackwardProtected( dim, varType, component, seed, df, nNewIS, newIS );
00235 }
00236
00237
00238
00239 returnValue UnaryOperator::AD_symmetric( int dim ,
00240 VariableType *varType ,
00241 int *component ,
00242 Operator *l ,
00243 Operator **S ,
00244 int dimS ,
00245 Operator **dfS ,
00246 Operator **ldf ,
00247 Operator **H ,
00248 int &nNewLIS ,
00249 TreeProjection ***newLIS ,
00250 int &nNewSIS ,
00251 TreeProjection ***newSIS ,
00252 int &nNewHIS ,
00253 TreeProjection ***newHIS ){
00254
00255 return ADsymmetricProtected( dim, varType, component, l, S, dimS, dfS, ldf, H, nNewLIS, newLIS, nNewSIS, newSIS, nNewHIS, newHIS );
00256 }
00257
00258
00259
00260
00261 NeutralElement UnaryOperator::isOneOrZero() const{ return NE_NEITHER_ONE_NOR_ZERO; }
00262
00263
00264 BooleanType UnaryOperator::isDependingOn( VariableType var ) const{
00265
00266 return argument->isDependingOn(var);
00267 }
00268
00269
00270 BooleanType UnaryOperator::isDependingOn( int dim,
00271 VariableType *varType,
00272 int *component,
00273 BooleanType *implicit_dep ){
00274
00275 return argument->isDependingOn( dim, varType, component, implicit_dep );
00276
00277 }
00278
00279
00280 BooleanType UnaryOperator::isLinearIn( int dim,
00281 VariableType *varType,
00282 int *component,
00283 BooleanType *implicit_dep ){
00284
00285 if( argument->isDependingOn( dim, varType, component, implicit_dep ) == BT_TRUE ){
00286 return BT_FALSE;
00287 }
00288
00289 return BT_TRUE;
00290 }
00291
00292
00293 BooleanType UnaryOperator::isPolynomialIn( int dim,
00294 VariableType *varType,
00295 int *component,
00296 BooleanType *implicit_dep ){
00297
00298 if( argument->isDependingOn( dim, varType, component, implicit_dep ) == BT_TRUE ){
00299 return BT_FALSE;
00300 }
00301
00302 return BT_TRUE;
00303 }
00304
00305
00306 BooleanType UnaryOperator::isRationalIn( int dim,
00307 VariableType *varType,
00308 int *component,
00309 BooleanType *implicit_dep ){
00310
00311 if( argument->isDependingOn( dim, varType, component, implicit_dep ) == BT_TRUE ){
00312 return BT_FALSE;
00313 }
00314
00315 return BT_TRUE;
00316 }
00317
00318
00319 MonotonicityType UnaryOperator::getMonotonicity( ){
00320
00321 if( monotonicity != MT_UNKNOWN ) return monotonicity;
00322 if( argument->getMonotonicity() == MT_CONSTANT ) return MT_CONSTANT ;
00323
00324 return MT_NONMONOTONIC;
00325 }
00326
00327
00328 CurvatureType UnaryOperator::getCurvature( ){
00329
00330 if( curvature != CT_UNKNOWN ) return curvature ;
00331 if( argument->getCurvature() == CT_CONSTANT ) return CT_CONSTANT;
00332
00333 return CT_NEITHER_CONVEX_NOR_CONCAVE;
00334 }
00335
00336
00337 returnValue UnaryOperator::setMonotonicity( MonotonicityType monotonicity_ ){
00338
00339 monotonicity = monotonicity_;
00340 return SUCCESSFUL_RETURN;
00341 }
00342
00343
00344 returnValue UnaryOperator::setCurvature( CurvatureType curvature_ ){
00345
00346 curvature = curvature_;
00347 return SUCCESSFUL_RETURN;
00348 }
00349
00350
00351 returnValue UnaryOperator::AD_forward( int number, double *x, double *seed,
00352 double *f, double *df ){
00353
00354 if( number >= bufferSize ){
00355 bufferSize += number;
00356 argument_result = (double*)realloc( argument_result,bufferSize*sizeof(double));
00357 dargument_result = (double*)realloc(dargument_result,bufferSize*sizeof(double));
00358 }
00359 argument->AD_forward( number, x, seed, &argument_result[number],
00360 &dargument_result[number] );
00361
00362 f[0] = (*fcn)( argument_result[number] );
00363 df[0] = (*dfcn)(argument_result[number])*dargument_result[number];
00364
00365 return SUCCESSFUL_RETURN;
00366 }
00367
00368
00369
00370 returnValue UnaryOperator::AD_forward( int number, double *seed, double *df ){
00371
00372
00373 argument->AD_forward( number, seed, &dargument_result[number] );
00374
00375 df[0] = (*dfcn)(argument_result[number])*dargument_result[number];
00376
00377 return SUCCESSFUL_RETURN;
00378 }
00379
00380
00381 returnValue UnaryOperator::AD_backward( int number, double seed, double *df ){
00382 return argument->AD_backward( number, (*dfcn)(argument_result[number])*seed, df );
00383 }
00384
00385
00386 returnValue UnaryOperator::AD_forward2( int number, double *seed, double *dseed,
00387 double *df, double *ddf ){
00388
00389 double ddargument_result;
00390 double dargument_result2;
00391
00392 argument->AD_forward2( number, seed, dseed,
00393 &dargument_result2, &ddargument_result);
00394
00395 const double nn = (*dfcn)(argument_result[number]);
00396
00397 df[0] = nn*dargument_result2;
00398 ddf[0] = nn*ddargument_result
00399 +(*ddfcn)( argument_result[number] )
00400 *dargument_result2*dargument_result[number];
00401
00402 return SUCCESSFUL_RETURN;
00403 }
00404
00405
00406 returnValue UnaryOperator::AD_backward2( int number, double seed1, double seed2,
00407 double *df, double *ddf ){
00408
00409 const double nn = (*dfcn)(argument_result[number]);
00410
00411 argument->AD_backward2( number ,
00412 seed1*nn ,
00413 seed2*nn +
00414 seed1*(*ddfcn)(argument_result[number])*dargument_result[number],
00415 df, ddf );
00416
00417 return SUCCESSFUL_RETURN;
00418 }
00419
00420
00421 std::ostream& UnaryOperator::print( std::ostream &stream ) const{
00422
00423 return stream << "(" << cName << "(" << *argument << "))";
00424 }
00425
00426
00427 BooleanType UnaryOperator::isVariable( VariableType &varType, int &component ) const
00428 {
00429 return BT_FALSE;
00430 }
00431
00432 returnValue UnaryOperator::clearBuffer(){
00433
00434 if( bufferSize > 1 ){
00435 bufferSize = 1;
00436 argument_result = (double*)realloc( argument_result,bufferSize*sizeof(double));
00437 dargument_result = (double*)realloc(dargument_result,bufferSize*sizeof(double));
00438 }
00439
00440 return SUCCESSFUL_RETURN;
00441 }
00442
00443
00444
00445 returnValue UnaryOperator::enumerateVariables( SymbolicIndexList *indexList ){
00446
00447 return argument->enumerateVariables( indexList );
00448 }
00449
00450
00451
00452
00453
00454
00455
00456 OperatorName UnaryOperator::getName(){
00457
00458 return operatorName;
00459 }
00460
00461
00462 returnValue UnaryOperator::loadIndices( SymbolicIndexList *indexList ){
00463
00464 return argument->loadIndices( indexList );
00465 }
00466
00467
00468 BooleanType UnaryOperator::isSymbolic() const{
00469
00470 if( argument->isSymbolic() == BT_FALSE ) return BT_FALSE;
00471 return BT_TRUE;
00472 }
00473
00474
00475 returnValue UnaryOperator::setVariableExportName( const VariableType &_type,
00476 const std::vector< std::string >& _name
00477 )
00478 {
00479 argument->setVariableExportName(_type, _name);
00480
00481 return Operator::setVariableExportName(_type, _name);
00482 }
00483
00484
00485 Operator* UnaryOperator::differentiate( int index ){
00486
00487 dargument = argument->differentiate( index );
00488 return myProd( dargument, derivative );
00489 }
00490
00491
00492 Operator* UnaryOperator::ADforwardProtected( int dim,
00493 VariableType *varType,
00494 int *component,
00495 Operator **seed,
00496 int &nNewIS,
00497 TreeProjection ***newIS ){
00498
00499 if( dargument != 0 )
00500 delete dargument;
00501
00502 dargument = argument->AD_forward(dim,varType,component,seed,nNewIS,newIS);
00503
00504 return myProd( dargument, derivative );
00505 }
00506
00507
00508
00509 returnValue UnaryOperator::ADbackwardProtected( int dim ,
00510 VariableType *varType ,
00511 int *component,
00512 Operator *seed ,
00513 Operator **df ,
00514 int &nNewIS ,
00515 TreeProjection ***newIS ){
00516
00517 argument->AD_backward( dim,
00518 varType,
00519 component,
00520 myProd( seed, derivative ),
00521 df, nNewIS, newIS
00522 );
00523
00524 delete seed;
00525 return SUCCESSFUL_RETURN;
00526 }
00527
00528
00529 returnValue UnaryOperator::ADsymmetricProtected( int dim ,
00530 VariableType *varType ,
00531 int *component ,
00532 Operator *l ,
00533 Operator **S ,
00534 int dimS ,
00535 Operator **dfS ,
00536 Operator **ldf ,
00537 Operator **H ,
00538 int &nNewLIS ,
00539 TreeProjection ***newLIS ,
00540 int &nNewSIS ,
00541 TreeProjection ***newSIS ,
00542 int &nNewHIS ,
00543 TreeProjection ***newHIS ){
00544
00545 TreeProjection dx, ddx;
00546 dx = *derivative;
00547 ddx = *derivative2;
00548
00549 return ADsymCommon( argument, dx, ddx, dim, varType, component, l, S, dimS, dfS,
00550 ldf, H, nNewLIS, newLIS, nNewSIS, newSIS, nNewHIS, newHIS );
00551 }
00552
00553
00554
00555
00556 CLOSE_NAMESPACE_ACADO
00557
00558