ExpressionParser.cpp
Go to the documentation of this file.
00001 /***************************************************************************
00002   tag: Peter Soetens  Mon May 10 19:10:37 CEST 2004  ExpressionParser.cxx
00003 
00004                         ExpressionParser.cxx -  description
00005                            -------------------
00006     begin                : Mon May 10 2004
00007     copyright            : (C) 2004 Peter Soetens
00008     email                : peter.soetens@mech.kuleuven.ac.be
00009 
00010  ***************************************************************************
00011  *   This library is free software; you can redistribute it and/or         *
00012  *   modify it under the terms of the GNU Lesser General Public            *
00013  *   License as published by the Free Software Foundation; either          *
00014  *   version 2.1 of the License, or (at your option) any later version.    *
00015  *                                                                         *
00016  *   This library is distributed in the hope that it will be useful,       *
00017  *   but WITHOUT ANY WARRANTY; without even the implied warranty of        *
00018  *   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU     *
00019  *   Lesser General Public License for more details.                       *
00020  *                                                                         *
00021  *   You should have received a copy of the GNU Lesser General Public      *
00022  *   License along with this library; if not, write to the Free Software   *
00023  *   Foundation, Inc., 59 Temple Place,                                    *
00024  *   Suite 330, Boston, MA  02111-1307  USA                                *
00025  *                                                                         *
00026  ***************************************************************************/
00027 
00028 #include "parser-debug.hpp"
00029 #include "parse_exception.hpp"
00030 
00031 #ifdef ORO_PRAGMA_INTERFACE
00032 #pragma implementation
00033 #endif
00034 #include "ExpressionParser.hpp"
00035 //#include "DumpObject.hpp"
00036 
00037 #include "ArgumentsParser.hpp"
00038 #include "../types/Operators.hpp"
00039 #include "DataSourceCondition.hpp"
00040 #include "../internal/DataSourceCommand.hpp"
00041 #include "../internal/GlobalService.hpp"
00042 
00043 #include "DataSourceTime.hpp"
00044 #include "../TaskContext.hpp"
00045 #include "PeerParser.hpp"
00046 #include "../types/Types.hpp"
00047 #include "SendHandleAlias.hpp"
00048 
00049 #include <boost/lambda/lambda.hpp>
00050 
00051 #include <boost/bind.hpp>
00052 #include <boost/ref.hpp>
00053 #include "rtt-scripting-config.h"
00054 #include <iostream>
00055 
00056 namespace RTT
00057 {
00058     using boost::bind;
00059     using boost::ref;
00060 
00061     using namespace detail;
00062     using namespace std;
00063 
00064     namespace {
00065         boost::spirit::classic::assertion<std::string> expect_open("Open brace expected.");
00066         boost::spirit::classic::assertion<std::string> expect_close("Closing brace expected ( or could not find out what this line means ).");
00067         boost::spirit::classic::assertion<std::string> expect_type("Unknown type. Please specify a type.");
00068         boost::spirit::classic::assertion<std::string> expect_expr("Expected a valid expression.");
00069         boost::spirit::classic::assertion<std::string> expect_ident("Expected a valid identifier.");
00070         boost::spirit::classic::assertion<std::string> expect_init("Expected an initialisation value of the value.");
00071         boost::spirit::classic::assertion<std::string> expect_comma("Expected the ',' separator after expression.");
00072         boost::spirit::classic::assertion<std::string> expect_timespec("Expected a time specification (e.g. > 10s or > varname ) after 'time' .");
00073 
00074         guard<std::string> my_guard;
00075     }
00076 
00077 
00078 
00079   DataCallParser::DataCallParser( ExpressionParser& p, CommonParser& cp, TaskContext* c, ExecutionEngine* caller )
00080       : mcaller( caller ? caller : c->engine()), mis_send(false), commonparser(cp), expressionparser( p ),
00081         peerparser( c, cp, false ) // accept partial paths
00082   {
00083     BOOST_SPIRIT_DEBUG_RULE( datacall );
00084     BOOST_SPIRIT_DEBUG_RULE( arguments );
00085     BOOST_SPIRIT_DEBUG_RULE( peerpath );
00086     BOOST_SPIRIT_DEBUG_RULE( object );
00087     BOOST_SPIRIT_DEBUG_RULE( method );
00088 
00089     // this parser uses a neat boost.spirit trick to avoid keeping
00090     // loads of stacks for all parsing data ( this parser needs to be
00091     // reentrant because it can be called while parsing an argument of
00092     // a datacall, which has itself been called while parsing an
00093     // argument of a datacall... ).  Boost.Spirit allows you to change
00094     // the parser that a rule points to at runtime, so we only create
00095     // the parser just before it's going to be used, when we know what
00096     // arguments we want..  See the ArgumentsParser doc for more
00097     // details..
00098     peerpath = peerparser.locator();
00099     object= (commonparser.identifier >> ".")[boost::bind(&DataCallParser::seenobjectname, this, _1, _2)];
00100     method= ( commonparser.keyword | expect_ident(commonparser.tidentifier))[boost::bind( &DataCallParser::seenmethodname, this, _1, _2 ) ]; // may be send, call or method name.
00101     datacall =
00102         ( peerpath >> !object >> method[ boost::bind( &DataCallParser::seendataname, this ) ] >> !arguments)[ boost::bind( &DataCallParser::seendatacall, this ) ];
00103   }
00104 
00105   void DataCallParser::seensend() {
00106       mis_send = true;
00107   }
00108 
00109   void DataCallParser::seenobjectname( iter_t begin, iter_t end )
00110     {
00111       std::string name( begin, end );
00112       mobject = name.substr(0, name.length() - 1);
00113     };
00114 
00115   void DataCallParser::seenmethodname( iter_t begin, iter_t end )
00116     {
00117       std::string name( begin, end );
00118       if ( name == "send") {
00119           mis_send = true;
00120           mmethod = mobject;
00121           mobject.clear();
00122       } else {
00123           mis_send = false;
00124           mmethod = name;
00125       }
00126 //      cout << "seenmethodname "<< mobject << "." << mmethod<<endl;
00127     };
00128 
00129   void DataCallParser::seendataname()
00130   {
00131       // re-init mobject, might have been cleared during parsing of send().
00132       mobject =  peerparser.object();
00133       TaskContext* peer = peerparser.peer();
00134       Service::shared_ptr ops  = peerparser.taskObject();
00135       peerparser.reset();
00136 //      cout << "seendataname "<< mobject << "." << mmethod<<endl;
00137       if (true) {
00138           // it ain't...
00139           // set the proper object name again in case of a send()
00140           if (mis_send && ops)
00141               mobject = ops->getName();
00142 //          cout << "DCP saw method "<< mmethod <<" of object "<<mobject<<" of peer "<<peer->getName()<<endl;
00143           // Check sanity of what we parsed:
00144           if (mmethod != "collect" && mmethod != "collectIfDone" ) {
00145               if ( ops == 0 || (mobject != "this" && ops->getName() != mobject ) ) {
00146                   throw parse_exception_no_such_component( peer->getName(), mobject);
00147               }
00148               // Check if method exists on current object:
00149               if ( ops->hasMember(mmethod) == false ) {
00150                   // Check if it is a method of the global service:
00151                   if ( ops == peerparser.taskObject() && GlobalService::Instance()->hasMember(mmethod) ) {
00152                       mobject = "GlobalService";
00153                       ops = GlobalService::Instance();
00154                   } else {
00155                       if ( ops == peerparser.taskObject() && ops->hasService("scripting") && ops->provides("scripting")->hasMember(mmethod) ) {
00156                           mobject = "scripting";
00157                           ops = ops->provides("scripting");
00158                       } else {
00159                       //DumpObject( peer );
00160                       if ( mobject != "this" )
00161                           throw parse_exception_no_such_method_on_component( mobject, mmethod );
00162                       else
00163                           throw parse_exception_no_such_method_on_component( peer->getName(), mmethod );
00164                       }
00165                   }
00166               }
00167           }
00168       }
00169 
00170       // create an argument parser for the call..
00171       // Store everything in the ArgumentsParser ! This DataCallParser instance is recursively called !
00172       ArgumentsParser* argspar =
00173           new ArgumentsParser( expressionparser, peer, ops,
00174                                mobject, mmethod );
00175       // we no longer need these two..
00176       mobject.clear();
00177       mmethod.clear();
00178 
00179       // keep hold of the argspar, we're still going to need it after
00180       // it's done its work..  ( in seendatacall(), that is.. )
00181       argparsers.push( argspar );
00182 
00183       // set the arguments parser to the parser provided by the
00184       // ArgumentsParser we just created..
00185       arguments = argspar->parser();
00186   }
00187 
00188   void DataCallParser::seendatacall()
00189   {
00190     ArgumentsParser* argspar = argparsers.top();
00191     argparsers.pop();
00192     std::string obj = argspar->objectname();
00193     std::string meth = argspar->methodname();
00194     std::vector<DataSourceBase::shared_ptr> args = argspar->result();
00195     Service::shared_ptr peer = argspar->object();
00196     delete argspar;
00197     assert(peer && "peer may never be null.");
00198 //    cout << "seendatacall "<< mobject << "." << mmethod<<endl;
00199 
00200     if ( true ) {
00201         // plain method or collect/collectIfDone
00202 
00203         Service::shared_ptr ops = peer;
00204         // we already checked for the existence of this object and method
00205         // in seendataname()..
00206         peerparser.reset();
00207 
00208         try {
00209             if ( (meth == "collect" || meth == "collectIfDone") && !ops->hasMember(mmethod) ) {
00210                 if ( ops->hasAttribute(obj) ) {
00211                     SendHandleAlias* sha = dynamic_cast<SendHandleAlias*>( peer->getValue(obj) );
00212                     if (sha) {
00213                         // add SendHandle DS for Collect:
00214                         args.insert( args.begin(), sha->getDataSource() );
00215                         if (meth == "collect")
00216                             ret = sha->getFactory()->produceCollect(args, new ValueDataSource<bool>(true) );// blocking
00217                         else
00218                             ret = sha->getFactory()->produceCollect(args, new ValueDataSource<bool>(false) );// non-blocking
00219                         return;
00220                     }
00221                 }
00222                 throw parse_exception_fatal_semantic_error( obj + "."+meth +": "+ obj +" is not a valid SendHandle object.");
00223             }
00224             if (!mis_send) {
00225                 ret = ops->produce( meth, args, mcaller );
00226                 mhandle.reset();
00227             } else {
00228                 ret = ops->produceSend( meth, args, mcaller );
00229                 mhandle.reset( new SendHandleAlias( meth, ops->produceHandle(meth), ops->getPart(meth)) );
00230             }
00231         }
00232         catch( const wrong_number_of_args_exception& e )
00233             {
00234                 throw parse_exception_wrong_number_of_arguments
00235                     (obj, meth, e.wanted, e.received );
00236             }
00237         catch( const wrong_types_of_args_exception& e )
00238             {
00239                 throw parse_exception_wrong_type_of_argument
00240                     (obj, meth, e.whicharg, e.expected_, e.received_ );
00241             }
00242         catch( const std::exception& e)
00243         {
00244             throw parse_exception_fatal_semantic_error("While calling "+obj+"."+meth+": "+e.what());
00245         }
00246     }
00247     assert( ret.get() );
00248   }
00249 
00250   DataCallParser::~DataCallParser()
00251   {
00252     // if argparsers is not empty, then something went wrong during
00253     // the parsing ( someone threw an exception ), and we're
00254     // responsible for cleaning up the argparsers we created..
00255     while ( ! argparsers.empty() )
00256     {
00257       delete argparsers.top();
00258       argparsers.pop();
00259     };
00260   }
00261 
00262   ConstructorParser::ConstructorParser( ExpressionParser& p, CommonParser& cp)
00263       : commonparser(cp), expressionparser( p )
00264   {
00265     BOOST_SPIRIT_DEBUG_RULE( type_name );
00266     BOOST_SPIRIT_DEBUG_RULE( arguments );
00267 
00268     type_name =
00269         ( commonparser.type_name[ boost::bind( &ConstructorParser::seen_type_name, this, _1, _2 ) ] >> !arguments)[ boost::bind( &ConstructorParser::seen_constructor, this ) ];
00270   }
00271 
00272   ConstructorParser::~ConstructorParser()
00273   {
00274     // if argparsers is not empty, then something went wrong during
00275     // the parsing ( someone threw an exception ), and we're
00276     // responsible for cleaning up the argparsers we created..
00277     while ( ! argparsers.empty() )
00278     {
00279       delete argparsers.top();
00280       argparsers.pop();
00281     };
00282   }
00283 
00284 
00285   void ConstructorParser::seen_type_name( iter_t begin, iter_t end )
00286   {
00287       std::string name( begin, end );
00288       TypeInfo* type = Types()->type( name );
00289       if ( type == 0 )
00290           throw_(iter_t(), "\"" + name + "\" is an unknown type...");
00291 
00292       ArgumentsParser* argspar =
00293           new ArgumentsParser( expressionparser, 0, Service::shared_ptr(), name, "" );
00294 
00295       // keep hold of the argspar, we're still going to need it after
00296       // it's done its work..  ( in seen_constructor(), that is.. )
00297       argparsers.push( argspar );
00298 
00299       // set the arguments parser to the parser provided by the
00300       // ArgumentsParser we just created..
00301       arguments = argspar->parser();
00302 
00303   }
00304 
00305   void ConstructorParser::seen_constructor( void )
00306   {
00307     ArgumentsParser* argspar = argparsers.top();
00308     argparsers.pop();
00309     std::string obj = argspar->objectname();
00310     std::vector<DataSourceBase::shared_ptr> args = argspar->result();
00311     delete argspar;
00312 
00313     ret = TypeInfoRepository::Instance()->type( obj )->construct( args );
00314 
00315     if (!ret) {
00316         throw parse_exception_no_such_constructor( obj, args );
00317     }
00318 
00319   }
00320 
00322     static void abort_rule(const string& reason) {
00323         throw_(iter_t(), reason);
00324     }
00325 
00326     static error_status<> fail_rule(scanner_t const& scan, parser_error<std::string, iter_t>&e )
00327     {
00328         return error_status<>( error_status<>::fail );
00329     }
00332   ExpressionParser::ExpressionParser( TaskContext* pc, ExecutionEngine* caller, CommonParser& cp )
00333       : datacallparser( *this, cp, pc, caller ),
00334         constrparser(*this, cp),
00335         commonparser( cp ),
00336         valueparser( pc, cp ),
00337         _invert_time(false),
00338         opreg( OperatorRepository::Instance() ),
00339         context(pc)
00340   {
00341     BOOST_SPIRIT_DEBUG_RULE( expression );
00342     BOOST_SPIRIT_DEBUG_RULE( unarynotexp );
00343     BOOST_SPIRIT_DEBUG_RULE( unaryminusexp );
00344     BOOST_SPIRIT_DEBUG_RULE( unaryplusexp );
00345     BOOST_SPIRIT_DEBUG_RULE( div_or_mul );
00346     BOOST_SPIRIT_DEBUG_RULE( modexp );
00347     BOOST_SPIRIT_DEBUG_RULE( plus_or_min );
00348     BOOST_SPIRIT_DEBUG_RULE( smallereqexp );
00349     BOOST_SPIRIT_DEBUG_RULE( smallerexp );
00350     BOOST_SPIRIT_DEBUG_RULE( greatereqexp );
00351     BOOST_SPIRIT_DEBUG_RULE( greaterexp );
00352     BOOST_SPIRIT_DEBUG_RULE( equalexp );
00353     BOOST_SPIRIT_DEBUG_RULE( notequalexp );
00354     BOOST_SPIRIT_DEBUG_RULE( orexp );
00355     BOOST_SPIRIT_DEBUG_RULE( andexp );
00356     BOOST_SPIRIT_DEBUG_RULE( ifthenelseexp );
00357     BOOST_SPIRIT_DEBUG_RULE( groupexp );
00358     BOOST_SPIRIT_DEBUG_RULE( dotexp );
00359     BOOST_SPIRIT_DEBUG_RULE( atomicexpression );
00360     BOOST_SPIRIT_DEBUG_RULE( time_expression );
00361     BOOST_SPIRIT_DEBUG_RULE( time_spec );
00362     BOOST_SPIRIT_DEBUG_RULE( indexexp );
00363     BOOST_SPIRIT_DEBUG_RULE( comma );
00364     BOOST_SPIRIT_DEBUG_RULE( close_brace );
00365     BOOST_SPIRIT_DEBUG_RULE( value_expression );
00366     BOOST_SPIRIT_DEBUG_RULE( call_expression );
00367     BOOST_SPIRIT_DEBUG_RULE( constructor_expression );
00368 
00369     comma = expect_comma( ch_p(',') );
00370     close_brace = expect_close( ch_p(')') );
00371     expression = assignexp;
00372 
00373     // We parse expressions without regard of the types.  First we
00374     // parse the expressions, then we worry about whether what the
00375     // user says is actually valid.  You can try to add up two
00376     // booleans, and the parser will parse it, but it will notice
00377     // you're writing bogus when it tries to pass it to an operator
00378     // structure from Operators.hpp
00379 
00380     // TODO: implement the ifthenelse operator ?
00381     assignexp = andexp >> *( ch_p( '=' ) >> eps_p(~ch_p( '=' ))  // prevent parsing first '=' of "=="
00382             >> assignexp)[ bind( &ExpressionParser::seen_assign, this)];
00383     andexp =
00384       orexp >> *( ( str_p( "&&" ) ) >> orexp[
00385                     boost::bind( &ExpressionParser::seen_binary, this, "&&" ) ] );
00386     orexp =
00387       notequalexp >> *( ( str_p( "||" ) ) >> notequalexp[
00388                         boost::bind( &ExpressionParser::seen_binary, this, "||" ) ] );
00389     notequalexp =
00390       equalexp >> *( "!=" >> equalexp[
00391                        boost::bind( &ExpressionParser::seen_binary, this, "!=" ) ] );
00392     equalexp =
00393          greatereqexp
00394       >> *( "==" >> greatereqexp[
00395               boost::bind( &ExpressionParser::seen_binary, this, "==" ) ] );
00396     greatereqexp =
00397          greaterexp
00398       >> *( ">=" >> greaterexp[
00399               boost::bind( &ExpressionParser::seen_binary, this, ">=" ) ] );
00400     greaterexp =
00401          smallereqexp
00402       >> *( '>' >> smallereqexp[
00403               boost::bind( &ExpressionParser::seen_binary, this, ">" ) ] );
00404     smallereqexp =
00405          smallerexp
00406       >> *( "<=" >> smallerexp[
00407               boost::bind( &ExpressionParser::seen_binary, this, "<=" ) ] );
00408     smallerexp =
00409       plus_or_min >> *( '<' >> plus_or_min[
00410                        boost::bind( &ExpressionParser::seen_binary, this, "<" ) ] );
00411 
00412     plus_or_min =
00413               modexp >> *( ('-' >> modexp[
00414                     boost::bind( &ExpressionParser::seen_binary, this, "-" ) ] )
00415                | ('+' >> modexp[
00416                     boost::bind( &ExpressionParser::seen_binary, this, "+" ) ] ) );
00417 
00418     modexp =
00419       div_or_mul >> *( '%' >> div_or_mul[
00420                      boost::bind( &ExpressionParser::seen_binary, this, "%" ) ] );
00421     div_or_mul =
00422       unaryplusexp >> *( ('/' >> unaryplusexp[
00423             boost::bind( &ExpressionParser::seen_binary, this, "/" ) ] )
00424        | ('*' >> unaryplusexp[
00425             boost::bind( &ExpressionParser::seen_binary, this, "*" ) ] ) );
00426 
00427     unaryplusexp =
00428         '+' >> unaryminusexp[
00429           boost::bind( &ExpressionParser::seen_unary, this, "+" ) ]
00430       | unaryminusexp;
00431     unaryminusexp =
00432         '-' >> unarynotexp[
00433           boost::bind( &ExpressionParser::seen_unary, this, "-" ) ]
00434       | unarynotexp;
00435     unarynotexp =
00436         ch_p('!') >> atomicexpression[
00437             boost::bind( &ExpressionParser::seen_unary, this, "!" ) ]
00438         | atomicexpression;
00439 
00440     // note the order is important: commonparser.identifier throws a
00441     // useful "cannot use x as identifier" error if it fails, so we
00442     // must first show all non-identifier rules.
00443     atomicexpression = (
00444         // A parenthesis group.
00445       groupexp
00446         // or a time expression
00447       | time_expression
00448         // or a constant or user-defined value..
00449       | value_expression
00450       | constructor_expression
00451       | call_expression
00452         // or an index or dot expression
00453         ) >> *( dotexp | indexexp);
00454 
00455     constructor_expression = my_guard( constrparser.parser()[ boost::bind(&ExpressionParser::seenconstructor, this)])[&fail_rule];
00456 
00457     // if it's value.keyword then pass it on to the call_expression.
00458     value_expression = my_guard( valueparser.parser() >> !('.' >> commonparser.keyword[boost::bind(&abort_rule,"Rule must be handled by datacallparser.")]))[ &fail_rule ]
00459                                                         [ bind( &ExpressionParser::seenvalue, this ) ];
00460     call_expression  = my_guard( datacallparser.parser() )[&fail_rule]
00461                                 [bind( &ExpressionParser::seendatacall, this ) ];
00462     // take index of an atomicexpression
00463     indexexp =
00464         (ch_p('[') >> expression[bind(&ExpressionParser::seen_index, this)] >> expect_close( ch_p( ']') ) );
00465 
00466     dotexp =
00467         ( ch_p('.') >> commonparser.identifier[ boost::bind(&ExpressionParser::seen_dotmember, this, _1, _2)]);
00468 
00469     // needs no semantic action, its result is already on top of
00470     // the stack, where it should be..
00471     groupexp = '(' >> expression >> close_brace;
00472 
00473     // the day i find a clean way to temporarily disable 'eol' skipping, a lot of
00474     // grammar will look better...
00475     time_expression =
00476         (str_p("time")>>eps_p(~commonparser.identchar | eol_p | end_p ))[bind(&ExpressionParser::seentimeexpr, this)]
00477         |
00478         ( (eps_p[boost::lambda::var(commonparser.skipeol) = false] >> uint_p[ bind( &ExpressionParser::seentimespec, this, _1 ) ]
00479            >> (str_p( "s" ) | "ms" | "us" | "ns" )[boost::lambda::var(commonparser.skipeol) = true][boost::bind( &ExpressionParser::seentimeunit, this, _1, _2 ) ])
00480           | (eps_p[boost::lambda::var(commonparser.skipeol) = true] >> nothing_p) // eps_p succeeds always, then fail.
00481           )
00482           ; // enable skipeol.
00483 
00484 //         >> expect_timespec( (( str_p( ">=" ) | ">" )
00485 //                             |
00486 //                             (str_p("<=") | "<")[bind( &ExpressionParser::inverttime, this)])
00487 //         >> time_spec);
00488 
00489 //     time_spec =
00490 //         ( uint_p[ bind( &ExpressionParser::seentimespec, this, _1 ) ]
00491 //         >>
00492 //       ( str_p( "s" ) | "ms" | "us" | "ns" )[
00493 //         bind( &ExpressionParser::seentimeunit, this, _1, _2 ) ] ) | expression[bind(&ExpressionParser::seentimeexpr, this)];
00494 
00495   };
00496 
00497     void ExpressionParser::inverttime()
00498     {
00499         _invert_time = true;
00500     }
00501 
00502     void ExpressionParser::seentimeexpr()
00503     {
00504         parsestack.push( new DataSourceTime() );
00505 
00506 //         DataSourceBase::shared_ptr res = parsestack.top();
00507 //         parsestack.pop();
00508 //         DataSource<double>::shared_ptr dres = dynamic_cast<DataSource<double>*>( res.get() );
00509 //         if ( !dres )
00510 //             throw parse_exception_semantic_error("Expected time in seconds but expression is not a floating point number.");
00511 //         DataSourceBase::shared_ptr dsb( new DataSourceCondition( new ConditionDSDuration( dres, _invert_time ) ) );
00512 //         _invert_time = false;
00513 //         parsestack.push( dsb );
00514     }
00515 
00516   void ExpressionParser::seentimeunit( iter_t begin, iter_t end)
00517   {
00518     // the string starting at begin, ending at end is either ms, us,
00519     // ns or s, so we only need to check the first letter...
00520       // Convert to seconds...
00521       TimeService::Seconds total = 0;
00522     switch( *begin )
00523     {
00524     case 's': total = TimeService::Seconds(tsecs);
00525         break;
00526     case 'm': total = tsecs / 1000.0;
00527         break;
00528     case 'u': total = tsecs / 1000000.0;
00529         break;
00530     case 'n': total = tsecs / 1000000000.0;
00531         break;
00532     default:
00533         std::string arg(begin, end);
00534         throw parse_exception_semantic_error("Expected time expression 's', 'ms', 'us' or 'ns' after integer value, got "+arg);
00535     };
00536 
00537     parsestack.push( new ConstantDataSource<double>( total ) );
00538 
00539 //     DataSourceBase::shared_ptr dsb( new DataSourceCondition(
00540 //       new ConditionDuration( total, _invert_time ) ) );
00541 //     _invert_time = false;
00542 //     parsestack.push( dsb );
00543   }
00544 
00545   void ExpressionParser::seentimespec( int n )
00546   {
00547     tsecs = n;
00548   }
00549 
00550   void ExpressionParser::seenvalue()
00551   {
00552     DataSourceBase::shared_ptr ds = valueparser.lastParsed();
00553     parsestack.push( ds );
00554   }
00555 
00556   void ExpressionParser::seendatacall()
00557   {
00558       DataSourceBase::shared_ptr n( datacallparser.getParseResult() );
00559       parsestack.push( n );
00560       mhandle = datacallparser.getParseHandle();
00561   }
00562 
00563   void ExpressionParser::seenconstructor()
00564   {
00565       DataSourceBase::shared_ptr n( constrparser.getParseResult() );
00566       parsestack.push( n );
00567   }
00568 
00569   ExpressionParser::~ExpressionParser()
00570   {
00571       // if parsestack is not empty, then something went wrong, someone
00572       // threw an exception, so we clean up..
00573       while ( !parsestack.empty() )
00574           parsestack.pop();
00575   }
00576 
00577   rule_t& ExpressionParser::parser()
00578   {
00579     return expression;
00580   }
00581 
00582   DataSourceBase::shared_ptr ExpressionParser::getResult()
00583   {
00584     assert( !parsestack.empty() );
00585     return parsestack.top();
00586   }
00587 
00588   boost::shared_ptr<AttributeBase> ExpressionParser::getHandle()
00589   {
00590     assert( !parsestack.empty() );
00591     return mhandle;
00592   }
00593 
00594   void ExpressionParser::seen_unary( const std::string& op )
00595   {
00596     DataSourceBase::shared_ptr arg( parsestack.top() );
00597     parsestack.pop();
00598     DataSourceBase::shared_ptr ret =
00599         opreg->applyUnary( op, arg.get() );
00600     if ( ! ret )
00601         throw parse_exception_fatal_semantic_error( "Cannot apply unary operator \"" + op +
00602                                                     "\" to " + arg->getType() +"." );
00603     parsestack.push( ret );
00604   }
00605 
00606   void ExpressionParser::seen_dotmember( iter_t s, iter_t f )
00607   {
00608       std::string member(s,f);
00609       // inspirired on seen_unary
00610     DataSourceBase::shared_ptr arg( parsestack.top() );
00611     parsestack.pop();
00612     DataSourceBase::shared_ptr ret = arg->getMember(member);
00613     if ( ! ret )
00614       throw parse_exception_fatal_semantic_error( arg->getType() + " does not have member \"" + member +
00615                                             "\"." );
00616     parsestack.push( ret );
00617   }
00618 
00619   void ExpressionParser::seen_binary( const std::string& op )
00620   {
00621     DataSourceBase::shared_ptr arg1( parsestack.top() );
00622     parsestack.pop();
00623     DataSourceBase::shared_ptr arg2( parsestack.top() );
00624     parsestack.pop();
00625 
00626     // Arg2 is the first (!) argument, as it was pushed on the stack
00627     // first.
00628     DataSourceBase::shared_ptr ret =
00629       opreg->applyBinary( op, arg2.get(), arg1.get() );
00630     if ( ! ret )
00631       throw parse_exception_fatal_semantic_error( "Cannot apply binary operation "+ arg2->getType() +" " + op +
00632                                             " "+arg1->getType() +"." );
00633     parsestack.push( ret );
00634   }
00635 
00636   void ExpressionParser::seen_assign()
00637   {
00638     DataSourceBase::shared_ptr arg1( parsestack.top() );
00639     parsestack.pop(); // right hand side
00640     DataSourceBase::shared_ptr arg2( parsestack.top() );
00641     parsestack.pop(); // left hand side
00642 
00643     // hack to drop-in a new instance of SendHandle:
00644     if (arg2->getTypeName() == "SendHandle" && mhandle) {
00645 //        cout << "Trying to replace SendHandle/..."<<endl;
00646         ConfigurationInterface::AttributeObjects attrs = context->attributes()->getValues();
00647         for( ConfigurationInterface::AttributeObjects::iterator it = attrs.begin(); it != attrs.end(); ++it) {
00648             if ( (*it)->getDataSource() == arg2 ) { // since the parsestack only saves the DSB, we need to do lookup by DSB and not by name :-(
00649 //                cout << "Found !"<<endl;
00650                 string name = (*it)->getName();
00651                 context->attributes()->removeAttribute(name);
00652                 AttributeBase* var = mhandle->clone();
00653                 var->setName( name ); // fill in the final handle name.
00654                 context->attributes()->setValue( var );
00655                 arg2 = var->getDataSource(); // frees up dummy and puts real one in place.
00656                 break;
00657             }
00658         }
00659     }
00660 
00661     DataSourceBase::shared_ptr ret;
00662     ActionInterface* act = 0;
00663     try {
00664         act = arg2->updateAction( arg1.get() );
00665     } catch(...) { // bad assignment
00666         throw parse_exception_fatal_semantic_error( "Incompatible types. Cannot assign: "+ arg2->getType() +" = " +
00667                 " "+arg1->getType() +"." );
00668     }
00669     if (!act)
00670         throw parse_exception_fatal_semantic_error( "2:Cannot assign constant (or returned) variable of types: "+ arg2->getType() +" = " +
00671                 " "+arg1->getType() );
00672     // only try this if not unknown_t.
00673     if (arg2->getTypeInfo()->getTypeName() != "unknown_t")
00674         ret = arg2->getTypeInfo()->buildActionAlias(act, arg2);
00675     if (!ret) { // no type info !
00676         ret = new DataSourceCommand( act ); // fall back into the old behavior of returning a boolean.
00677     }
00678     parsestack.push( ret );
00679   }
00680 
00681   void ExpressionParser::seen_index()
00682   {
00683     DataSourceBase::shared_ptr arg1( parsestack.top() );
00684     parsestack.pop();
00685     DataSourceBase::shared_ptr arg2( parsestack.top() );
00686     parsestack.pop();
00687 
00688     // Arg2 is the first (!) argument, as it was pushed on the stack
00689     // first.
00690     DataSourceBase::shared_ptr ret = arg2->getMember( arg1, 0 );
00691     if ( ! ret )
00692       throw parse_exception_fatal_semantic_error( "Illegal use of []: "+ arg2->getType() +"[ "
00693                                                 +arg1->getType() +" ]." );
00694     parsestack.push( ret );
00695   }
00696 
00697   void ExpressionParser::dropResult()
00698   {
00699     parsestack.pop();
00700   }
00701 }


rtt
Author(s): RTT Developers
autogenerated on Sat Jun 8 2019 18:46:09