doubleconstant.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 DoubleConstant::DoubleConstant( ) : SmoothOperator( )
00046 {
00047         nCount = 0;
00048 
00049         value = 0;
00050         neutralElement = NE_ZERO;
00051 }
00052 
00053 DoubleConstant::DoubleConstant( double value_, NeutralElement neutralElement_ )
00054         : SmoothOperator( ), value( value_ ), neutralElement( neutralElement_ )
00055 {
00056         nCount = 0;
00057 
00058         // XXX: This should be revised!!!
00059     if (fabs( value ) < 10.0 * EPS)
00060     {
00061         neutralElement = NE_ZERO;
00062     }
00063     else if (fabs(1.0 - value) < 10.0 * EPS)
00064     {
00065         neutralElement = NE_ONE;
00066     }
00067 }
00068 
00069 
00070 DoubleConstant::DoubleConstant( const DoubleConstant &arg ){
00071 
00072     value           = arg.value          ;
00073     neutralElement  = arg.neutralElement ;
00074 
00075     nCount = 0;
00076 }
00077 
00078 
00079 DoubleConstant::~DoubleConstant(){
00080 
00081 }
00082 
00083 
00084 DoubleConstant& DoubleConstant::operator=( const DoubleConstant &arg ){
00085 
00086     if( this != &arg ){
00087 
00088         value           = arg.value          ;
00089         neutralElement  = arg.neutralElement ;
00090 
00091         nCount = 0;
00092     }
00093 
00094     return *this;
00095 }
00096 
00097 
00098 returnValue DoubleConstant::evaluate( int number, double *x, double *result ){
00099 
00100     result[0] = value;
00101     return SUCCESSFUL_RETURN;
00102 }
00103 
00104 
00105 returnValue DoubleConstant::evaluate( EvaluationBase *x ){
00106 
00107     x->set(value);
00108     return SUCCESSFUL_RETURN;
00109 }
00110 
00111 
00112 Operator* DoubleConstant::differentiate( int index ){
00113 
00114   return new DoubleConstant( 0.0 , NE_ZERO );
00115 }
00116 
00117 
00118 Operator* DoubleConstant::AD_forward( int dim,
00119                                         VariableType *varType,
00120                                         int *component,
00121                                         Operator **seed,
00122                                         int &nNewIS,
00123                                         TreeProjection ***newIS ){
00124 
00125     return new DoubleConstant( 0.0, NE_ZERO );
00126 }
00127 
00128 
00129 
00130 returnValue DoubleConstant::AD_backward( int           dim      , 
00131                                         VariableType *varType  , 
00132                                         int          *component, 
00133                                         Operator     *seed     , 
00134                                         Operator    **df       , 
00135                                         int           &nNewIS  , 
00136                                         TreeProjection ***newIS   ){
00137 
00138     delete seed;
00139     return SUCCESSFUL_RETURN;
00140 }
00141 
00142 
00143 returnValue DoubleConstant::AD_symmetric( int            dim       , 
00144                                         VariableType  *varType   , 
00145                                         int           *component , 
00146                                         Operator      *l         , 
00147                                         Operator     **S         , 
00148                                         int            dimS      , 
00149                                         Operator     **dfS       , 
00150                                         Operator     **ldf       , 
00151                                         Operator     **H         , 
00152                                       int            &nNewLIS  , 
00153                                       TreeProjection ***newLIS , 
00154                                       int            &nNewSIS  , 
00155                                       TreeProjection ***newSIS , 
00156                                       int            &nNewHIS  , 
00157                                       TreeProjection ***newHIS    ){
00158   
00159     delete l;
00160     return SUCCESSFUL_RETURN; 
00161 }
00162 
00163 
00164 Operator* DoubleConstant::substitute( int index, const Operator *sub ){
00165 
00166     return clone();
00167 }
00168 
00169 
00170 
00171 NeutralElement DoubleConstant::isOneOrZero() const{
00172 
00173     return neutralElement;
00174 }
00175 
00176 
00177 BooleanType DoubleConstant::isDependingOn( VariableType var ) const{
00178 
00179     return BT_FALSE;
00180 }
00181 
00182 
00183 BooleanType DoubleConstant::isDependingOn( int dim,
00184                                              VariableType *varType,
00185                                              int *component,
00186                                              BooleanType   *implicit_dep ){
00187 
00188     return BT_FALSE;
00189 }
00190 
00191 
00192 BooleanType DoubleConstant::isLinearIn( int dim,
00193                                           VariableType *varType,
00194                                           int *component,
00195                                           BooleanType   *implicit_dep ){
00196 
00197     return BT_TRUE;
00198 }
00199 
00200 
00201 BooleanType DoubleConstant::isPolynomialIn( int dim,
00202                                               VariableType *varType,
00203                                               int *component,
00204                                               BooleanType   *implicit_dep ){
00205 
00206     return BT_TRUE;
00207 }
00208 
00209 
00210 BooleanType DoubleConstant::isRationalIn( int dim,
00211                                             VariableType *varType,
00212                                             int *component,
00213                                             BooleanType   *implicit_dep ){
00214 
00215     return BT_TRUE;
00216 }
00217 
00218 
00219 MonotonicityType DoubleConstant::getMonotonicity( ){
00220 
00221     return MT_CONSTANT;
00222 }
00223 
00224 
00225 CurvatureType DoubleConstant::getCurvature( ){
00226 
00227     return CT_CONSTANT;
00228 }
00229 
00230 
00231 returnValue DoubleConstant::setMonotonicity( MonotonicityType monotonicity_ ){
00232 
00233     return SUCCESSFUL_RETURN;
00234 }
00235 
00236 
00237 returnValue DoubleConstant::setCurvature( CurvatureType curvature_ ){
00238 
00239     return SUCCESSFUL_RETURN;
00240 }
00241 
00242 
00243 returnValue DoubleConstant::AD_forward( int number, double *x, double *seed,
00244                                         double *f, double *df ){
00245 
00246       f[0] =  value;
00247      df[0] =  0.0;
00248 
00249      return SUCCESSFUL_RETURN;
00250 }
00251 
00252 
00253 
00254 returnValue DoubleConstant::AD_forward( int number, double *seed, double *df ){
00255 
00256      df[0] =  0.0;
00257      return SUCCESSFUL_RETURN;
00258 }
00259 
00260 
00261 returnValue DoubleConstant::AD_backward( int number, double seed, double *df ){
00262 
00263      return SUCCESSFUL_RETURN;
00264 }
00265 
00266 
00267 returnValue DoubleConstant::AD_forward2( int number, double *seed, double *dseed,
00268                                          double *df, double *ddf ){
00269 
00270      df[0] = 0.0;
00271     ddf[0] = 0.0;
00272 
00273     return SUCCESSFUL_RETURN;
00274 }
00275 
00276 
00277 returnValue DoubleConstant::AD_backward2( int number, double seed1, double seed2,
00278                                           double *df, double *ddf ){
00279 
00280     return SUCCESSFUL_RETURN;
00281 }
00282 
00283 
00284 
00285 std::ostream& DoubleConstant::print( std::ostream &stream ) const{
00286 
00287     return stream << "(real_t)(" << value << ")";
00288 }
00289 
00290 
00291 Operator* DoubleConstant::clone() const{
00292 
00293     return new DoubleConstant(*this);
00294 }
00295 
00296 
00297 returnValue DoubleConstant::clearBuffer(){
00298 
00299     return SUCCESSFUL_RETURN;
00300 }
00301 
00302 
00303 returnValue DoubleConstant::enumerateVariables( SymbolicIndexList *indexList ){
00304 
00305     return SUCCESSFUL_RETURN;
00306 }
00307 
00308 //
00309 // PROTECTED MEMBER FUNCTIONS:
00310 // ---------------------------
00311 
00312 OperatorName DoubleConstant::getName(){
00313 
00314     return ON_DOUBLE_CONSTANT;
00315 }
00316 
00317 BooleanType DoubleConstant::isVariable( VariableType &varType, int &component ) const
00318 {
00319     return BT_FALSE;
00320 }
00321 
00322 
00323 returnValue DoubleConstant::loadIndices( SymbolicIndexList *indexList ){
00324 
00325     return SUCCESSFUL_RETURN;
00326 }
00327 
00328 
00329 BooleanType DoubleConstant::isSymbolic() const{
00330 
00331     return BT_TRUE;
00332 }
00333 
00334 
00335 double DoubleConstant::getValue() const{
00336 
00337     return value;
00338 }
00339 
00340 
00341 CLOSE_NAMESPACE_ACADO
00342 
00343 // end of file.


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