projection.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-2013 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 Projection::Projection()
00044            :SmoothOperator( ){
00045 
00046     scale          = 1.0           ;
00047     curvature      = CT_AFFINE     ;
00048     monotonicity = MT_NONDECREASING;
00049     operatorName = ON_VARIABLE     ;
00050 
00051     nCount = 0;
00052 }
00053 
00054 
00055 Projection::Projection( const std::string &name_ )
00056            :SmoothOperator( ){
00057 
00058     scale          = 1.0             ;
00059     curvature      = CT_AFFINE       ;
00060     monotonicity   = MT_NONDECREASING;
00061     operatorName   = ON_VARIABLE     ;
00062     name           = name_           ;
00063 
00064     nCount = 0;
00065 }
00066 
00067 
00068 Projection::Projection( VariableType variableType_, int vIndex_, const std::string &name_ ) :SmoothOperator( )
00069 {
00070     variableType   = variableType_ ;
00071     vIndex         = vIndex_       ;
00072     variableIndex  = vIndex        ;
00073 
00074     scale          = 1.0           ;
00075     curvature      = CT_AFFINE     ;
00076     monotonicity = MT_NONDECREASING;
00077     operatorName = ON_VARIABLE     ;
00078 
00079     std::stringstream ss;
00080     switch(variableType){
00081 
00082          case VT_DIFFERENTIAL_STATE:
00083               ss << "xd" << "[" << vIndex <<"]";
00084               break;
00085 
00086          case VT_ALGEBRAIC_STATE:
00087               ss << "xa" << "[" << vIndex <<"]";
00088               break;
00089 
00090          case VT_CONTROL:
00091               ss << "u" << "[" << vIndex <<"]";
00092               break;
00093 
00094          case VT_INTEGER_CONTROL:
00095               ss << "v" << "[" << vIndex <<"]";
00096               break;
00097 
00098          case VT_PARAMETER:
00099               ss << "p" << "[" << vIndex <<"]";
00100               break;
00101 
00102          case VT_ONLINE_DATA:
00103               ss << "od" << "[" << vIndex <<"]";
00104               break;
00105 
00106          case VT_INTEGER_PARAMETER:
00107               ss << "q" << "[" << vIndex <<"]";
00108               break;
00109 
00110          case VT_DISTURBANCE:
00111               ss << "w" << "[" << vIndex <<"]";
00112               break;
00113 
00114          case VT_TIME:
00115               ss << "t" << "[" << vIndex <<"]";
00116               break;
00117 
00118          case VT_INTERMEDIATE_STATE:
00119               ss << "a" << "[" << vIndex <<"]";
00120               break;
00121 
00122          case VT_DDIFFERENTIAL_STATE:
00123               ss << "dx" << "[" << vIndex <<"]";
00124               break;
00125 
00126          default: break;
00127     }
00128     name = ss.str();
00129     nCount = 0;
00130 }
00131 
00132 
00133 Projection::~Projection(){ }
00134 
00135 
00136 Projection::Projection( const Projection& arg ){
00137 
00138     copy( arg );
00139 }
00140 
00141 
00142 Operator* Projection::clone() const{
00143 
00144     return new Projection(*this);
00145 }
00146 
00147 
00148 void Projection::copy( const Projection &arg ){
00149 
00150     if( this != &arg ){
00151 
00152         variableType   = arg.variableType ;
00153         variableIndex  = arg.variableIndex;
00154         vIndex         = arg.vIndex       ;
00155         scale          = arg.scale        ;
00156         name           = arg.name         ;
00157         operatorName   = arg.operatorName ;
00158         curvature      = arg.curvature    ;
00159         monotonicity   = arg.monotonicity ;
00160 
00161         nCount = 0;
00162     }
00163 }
00164 
00165 
00166 returnValue Projection::evaluate( int number, double *x, double *result ){
00167 
00168     result[0] = x[variableIndex];
00169     return SUCCESSFUL_RETURN;
00170 }
00171 
00172 
00173 returnValue Projection::evaluate( EvaluationBase *x ){
00174 
00175     x->project(variableIndex);
00176     return SUCCESSFUL_RETURN;
00177 }
00178 
00179 
00180 Operator* Projection::differentiate( int index ){
00181 
00182     if( variableIndex == index ){
00183         return new DoubleConstant( 1.0 , NE_ONE );
00184     }
00185     else{
00186         return new DoubleConstant( 0.0 , NE_ZERO );
00187     }
00188 }
00189 
00190 
00191 Operator* Projection::AD_forward( int dim,
00192                                           VariableType *varType,
00193                                           int *component,
00194                                           Operator **seed,
00195                                           int &nNewIS,
00196                                           TreeProjection ***newIS ){
00197 
00198     return ADforwardProtected( dim, varType, component, seed, nNewIS, newIS );
00199 }
00200 
00201 
00202 
00203 returnValue Projection::AD_backward( int           dim      , 
00204                                         VariableType *varType  , 
00205                                         int          *component, 
00206                                         Operator     *seed     , 
00207                                         Operator    **df       , 
00208                                         int           &nNewIS  , 
00209                                         TreeProjection ***newIS   ){
00210 
00211     return ADbackwardProtected( dim, varType, component, seed, df, nNewIS, newIS );
00212 }
00213 
00214 
00215 returnValue Projection::AD_symmetric( int            dim       , 
00216                                         VariableType  *varType   , 
00217                                         int           *component , 
00218                                         Operator      *l         , 
00219                                         Operator     **S         , 
00220                                         int            dimS      , 
00221                                         Operator     **dfS       , 
00222                                         Operator     **ldf       , 
00223                                         Operator     **H         , 
00224                                         int            &nNewLIS  , 
00225                                         TreeProjection ***newLIS , 
00226                                         int            &nNewSIS  , 
00227                                         TreeProjection ***newSIS , 
00228                                         int            &nNewHIS  , 
00229                                         TreeProjection ***newHIS    ){
00230   
00231         return ADsymmetricProtected( dim, varType, component, l, S, dimS, dfS, ldf, H, nNewLIS, newLIS, nNewSIS, newSIS, nNewHIS, newHIS );
00232 }
00233 
00234 
00235 
00236 Operator* Projection::substitute( int index, const Operator *sub ){
00237 
00238     if( variableIndex == index ){
00239         return sub->clone();
00240     }
00241     else{
00242         return clone();
00243     }
00244 }
00245 
00246 
00247 
00248 NeutralElement Projection::isOneOrZero() const{
00249 
00250     return NE_NEITHER_ONE_NOR_ZERO;
00251 }
00252 
00253 
00254 
00255 
00256 BooleanType Projection::isDependingOn( VariableType var ) const{
00257 
00258     if( variableType == var )  return BT_TRUE;
00259     return BT_FALSE;
00260 }
00261 
00262 
00263 
00264 
00265 BooleanType Projection::isDependingOn( int dim,
00266                                                VariableType *varType,
00267                                                int *component,
00268                                                BooleanType   *implicit_dep ){
00269 
00270     int run1 = 0;
00271 
00272     while( run1 < dim ){
00273 
00274         if( varType[run1] == variableType && component[run1] == vIndex ){
00275             return BT_TRUE;
00276         }
00277         run1++;
00278     }
00279     return BT_FALSE;
00280 }
00281 
00282 
00283 BooleanType Projection::isLinearIn( int dim,
00284                                             VariableType *varType,
00285                                             int *component,
00286                                             BooleanType   *implicit_dep ){
00287 
00288     return BT_TRUE;
00289 }
00290 
00291 
00292 BooleanType Projection::isPolynomialIn( int dim,
00293                                                 VariableType *varType,
00294                                                 int *component,
00295                                                 BooleanType   *implicit_dep ){
00296 
00297     return BT_TRUE;
00298 }
00299 
00300 
00301 BooleanType Projection::isRationalIn( int dim,
00302                                               VariableType *varType,
00303                                               int *component,
00304                                               BooleanType   *implicit_dep ){
00305 
00306     return BT_TRUE;
00307 }
00308 
00309 
00310 MonotonicityType Projection::getMonotonicity( ){
00311 
00312     return monotonicity;
00313 }
00314 
00315 
00316 CurvatureType Projection::getCurvature( ){
00317 
00318     return curvature;
00319 }
00320 
00321 
00322 returnValue Projection::setMonotonicity( MonotonicityType monotonicity_ ){
00323 
00324     monotonicity = monotonicity_;
00325     return SUCCESSFUL_RETURN;
00326 }
00327 
00328 
00329 returnValue Projection::setCurvature( CurvatureType curvature_ ){
00330 
00331     curvature = curvature_;
00332     return SUCCESSFUL_RETURN;
00333 }
00334 
00335 
00336 returnValue Projection::AD_forward( int number, double *x, double *seed,
00337                                           double *f, double *df ){
00338 
00339       f[0] =  x[variableIndex];
00340      df[0] =  seed[variableIndex];
00341 
00342      return SUCCESSFUL_RETURN;
00343 }
00344 
00345 
00346 returnValue Projection::AD_forward( int number, double *seed, double *df ){
00347 
00348      df[0] =  seed[variableIndex];
00349      return SUCCESSFUL_RETURN;
00350 }
00351 
00352 
00353 returnValue Projection::AD_backward( int number, double seed, double *df ){
00354 
00355     df[variableIndex] = df[variableIndex] + seed;
00356     return SUCCESSFUL_RETURN;
00357 }
00358 
00359 
00360 returnValue Projection::AD_forward2( int number, double *seed, double *dseed,
00361                                            double *df, double *ddf ){
00362 
00363      df[0] = seed [variableIndex];
00364     ddf[0] = dseed[variableIndex];
00365     return SUCCESSFUL_RETURN;
00366 }
00367 
00368 returnValue Projection::AD_backward2( int number, double seed1, double seed2,
00369                                             double *df, double *ddf ){
00370 
00371      df[variableIndex] =  df[variableIndex] + seed1;
00372     ddf[variableIndex] = ddf[variableIndex] + seed2;
00373 
00374     return SUCCESSFUL_RETURN;
00375 }
00376 
00377 
00378 
00379 std::ostream& Projection::print( std::ostream &stream ) const{
00380 
00381     return stream << name;
00382 }
00383 
00384 
00385 returnValue Projection::clearBuffer(){
00386 
00387     return SUCCESSFUL_RETURN;
00388 }
00389 
00390 
00391 OperatorName Projection::getName(){
00392 
00393     return operatorName;
00394 }
00395 
00396 
00397 double Projection::getScale() const{
00398 
00399     return scale;
00400 }
00401 
00402 
00403 returnValue Projection::setScale( const double &scale_ ){
00404 
00405     scale = scale_;
00406     return SUCCESSFUL_RETURN;
00407 }
00408 
00409 
00410 BooleanType Projection::isVariable( VariableType &varType, int &component ) const
00411 {
00412   varType   = variableType;
00413   component = vIndex    ;
00414 
00415   return BT_TRUE;
00416 }
00417 
00418 returnValue Projection::enumerateVariables( SymbolicIndexList *indexList ){
00419 
00420   variableIndex = indexList->determineVariableIndex( variableType,
00421                                                      vIndex, scale         );
00422   return SUCCESSFUL_RETURN;
00423 }
00424 
00425 
00426 int Projection::getVariableIndex( ) const{
00427 
00428     return variableIndex;
00429 }
00430 
00431 
00432 int Projection::getGlobalIndex() const{
00433 
00434     return vIndex;
00435 }
00436 
00437 
00438 VariableType Projection::getType( ) const
00439 {
00440         return variableType;
00441 }
00442 
00443 
00444 returnValue Projection::loadIndices( SymbolicIndexList *indexList ){
00445 
00446     indexList->addNewElement( variableType, vIndex );
00447     return SUCCESSFUL_RETURN;
00448 }
00449 
00450 
00451 BooleanType Projection::isSymbolic() const{
00452 
00453     return BT_TRUE;
00454 }
00455 
00456 
00457 Operator* Projection::ADforwardProtected( int dim,
00458                                                   VariableType *varType,
00459                                                   int *component,
00460                                                   Operator **seed,
00461                                                   int &nNewIS,
00462                                                   TreeProjection ***newIS ){
00463 
00464     int run1 = 0;
00465 
00466     while( run1 < dim ){
00467 
00468         if( varType[run1] == variableType && component[run1] == vIndex ){
00469             return seed[run1]->clone();
00470         }
00471         run1++;
00472     }
00473 
00474     return new DoubleConstant( 0.0 , NE_ZERO );
00475 }
00476 
00477 
00478 
00479 returnValue Projection::ADbackwardProtected( int           dim      , 
00480                                         VariableType *varType  , 
00481                                         int          *component, 
00482                                         Operator     *seed     , 
00483                                         Operator    **df       , 
00484                                         int           &nNewIS  , 
00485                                         TreeProjection ***newIS   ){
00486 
00487     int run1 = 0;
00488 
00489     while( run1 < dim ){
00490 
00491         if( varType[run1] == variableType && component[run1] == vIndex ){
00492 
00493             if(   df[run1]->isOneOrZero() == NE_ZERO ){
00494                   delete df[run1];
00495                   df[run1] = seed->clone();
00496             }
00497             else{
00498 
00499                 if( seed-> isOneOrZero() != NE_ZERO ){
00500 
00501                     Operator *tmp = df[run1]->clone();
00502                     delete df[run1];
00503                     df[run1] = new Addition(tmp->clone(),seed->clone());
00504                     delete tmp;
00505                 }
00506             }
00507 
00508             break;
00509         }
00510         run1++;
00511     }
00512 
00513     delete seed;
00514     return SUCCESSFUL_RETURN;
00515 }
00516 
00517 
00518 returnValue Projection::ADsymmetricProtected( int            dim       , 
00519                                         VariableType  *varType   , 
00520                                         int           *component , 
00521                                         Operator      *l         , 
00522                                         Operator     **S         , 
00523                                         int            dimS      , 
00524                                         Operator     **dfS       , 
00525                                         Operator     **ldf       , 
00526                                         Operator     **H         , 
00527                                         int            &nNewLIS  , 
00528                                         TreeProjection ***newLIS , 
00529                                         int            &nNewSIS  , 
00530                                         TreeProjection ***newSIS , 
00531                                         int            &nNewHIS  , 
00532                                         TreeProjection ***newHIS    ){
00533 
00534         int run1 = 0;
00535 
00536         while( run1 < dim ){
00537 
00538                 if( varType[run1] == variableType && component[run1] == vIndex ){
00539 
00540                         int run2;
00541                         for( run2 = 0; run2 < dimS; run2++ ){
00542                                 delete dfS[run2];
00543                                 dfS[run2] = S[run1*dimS+run2]->clone();
00544                         }
00545 
00546                         if(   ldf[run1]->isOneOrZero() == NE_ZERO ){
00547                                 delete ldf[run1];
00548                                 ldf[run1] = l->clone();
00549                         }
00550                         else{
00551 
00552                                 if( l->isOneOrZero() != NE_ZERO ){
00553 
00554                                         Operator *tmp = ldf[run1]->clone();
00555                                         delete ldf[run1];
00556                                         ldf[run1] = new Addition(tmp->clone(),l->clone());
00557                                         delete tmp;
00558                                 }
00559                         }
00560                         break;
00561                 }
00562                 run1++;
00563         }
00564 
00565         delete l;
00566         return SUCCESSFUL_RETURN;
00567 }
00568 
00569 returnValue Projection::setVariableExportName( const VariableType &_type, const std::vector<std::string > &_name ){
00570 
00571         if (variableType == _type)
00572         {
00573                 this->name = _name[vIndex];
00574         }
00575         return Operator::setVariableExportName(_type, _name);
00576 }
00577 
00578 
00579 BooleanType Projection::isTrivial() const {
00580         return BT_TRUE;
00581 }
00582 
00583 
00584 CLOSE_NAMESPACE_ACADO
00585 
00586 // end of file.


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