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 
00028 #include "parser-debug.hpp"
00029 #include "parse_exception.hpp"
00030 #include "ProgramGraphParser.hpp"
00031 #include "ArgumentsParser.hpp"
00032 
00033 #include "CommandNOP.hpp"
00034 #include "CommandDataSource.hpp"
00035 #include "ConditionTrue.hpp"
00036 #include "../Logger.hpp"
00037 #include "DataSourceCondition.hpp"
00038 
00039 #include "ConditionComposite.hpp"
00040 #include "ConditionFalse.hpp"
00041 #include "ConditionOnce.hpp"
00042 #include "CommandComposite.hpp"
00043 #include "CommandBinary.hpp"
00044 
00045 #include "TryCommand.hpp"
00046 #include "FunctionFactory.hpp"
00047 #include "../TaskContext.hpp"
00048 #include "../internal/GlobalService.hpp"
00049 
00050 #include <iostream>
00051 #include <boost/bind.hpp>
00052 #include <boost/lambda/lambda.hpp>
00053 
00054 #ifdef WIN32
00055     #ifdef NDEBUG
00056         #pragma optimize( "", off)
00057     #endif
00058 #endif
00059 
00060 namespace RTT
00061 {
00062   using namespace boost;
00063   using namespace detail;
00064 
00065 
00066 
00067     namespace {
00068         boost::spirit::classic::assertion<std::string> expect_opencurly("Open curly brace '{' expected.");
00069         boost::spirit::classic::assertion<std::string> expect_closecurly("Closing curly brace '}' expected in statement block (or could not find out what this line means).");
00070         boost::spirit::classic::assertion<std::string> expect_closefunction("Closing curly brace '}' expected at end of program or function (or could not find out what this line means).");
00071         boost::spirit::classic::assertion<std::string> expect_open("Open brace '(' expected.");
00072         boost::spirit::classic::assertion<std::string> expect_close("Closing brace ')' expected.");
00073         boost::spirit::classic::assertion<std::string> expect_comma("Expected a comma separator.");
00074         boost::spirit::classic::assertion<std::string> expect_ident("Expected a valid identifier.");
00075         boost::spirit::classic::assertion<std::string> expect_semicolon("Semicolon ';' expected after statement.");
00076         boost::spirit::classic::assertion<std::string> expect_condition("Expected a boolean expression ( a condition ).");
00077         boost::spirit::classic::assertion<std::string> expect_expression("Expected an expression.");
00078         boost::spirit::classic::assertion<std::string> expect_command("Expected a command after 'do'.");
00079         boost::spirit::classic::assertion<std::string> expect_nl("Expected a newline after statement.");
00080         boost::spirit::classic::assertion<std::string> expect_eof("Invalid input in file.");
00081         boost::spirit::classic::assertion<std::string> expect_term("No valid termination claues found in do ... until { } block.");
00082     }
00083 
00084 
00085   ProgramGraphParser::ProgramGraphParser( iter_t& positer, TaskContext* t, ExecutionEngine* caller, CommonParser& cp)
00086       : rootc( t ),context(), fcontext(0), mpositer( positer ),
00087         mcallfunc(),
00088         implcond(0), mcondition(0), try_cond(0),
00089         commonparser(cp),
00090         conditionparser( rootc, caller, cp ),
00091         valuechangeparser( rootc, cp, t->provides(), caller ),
00092         expressionparser( rootc, caller, cp ),
00093         argsparser(0),
00094         peerparser(rootc, commonparser),
00095         program_builder( new FunctionGraphBuilder() ),
00096         for_init_command(0),
00097         exportf(false),globalf(false),
00098         ln_offset(0)
00099   {
00100       
00101       this->setup();
00102       this->setup2();
00103   }
00104 
00105   ProgramGraphParser::~ProgramGraphParser() {
00106       
00107       
00108       
00109       cleanup(true);
00110   }
00111 
00112   void ProgramGraphParser::setup() {
00113     BOOST_SPIRIT_DEBUG_RULE( newline );
00114     BOOST_SPIRIT_DEBUG_RULE( openbrace );
00115     BOOST_SPIRIT_DEBUG_RULE( closebrace );
00116     BOOST_SPIRIT_DEBUG_RULE( opencurly );
00117     BOOST_SPIRIT_DEBUG_RULE( closecurly );
00118     BOOST_SPIRIT_DEBUG_RULE( semicolon );
00119     BOOST_SPIRIT_DEBUG_RULE( condition );
00120     BOOST_SPIRIT_DEBUG_RULE( terminationclause );
00121     BOOST_SPIRIT_DEBUG_RULE( jumpdestination );
00122     BOOST_SPIRIT_DEBUG_RULE( terminationpart );
00123     BOOST_SPIRIT_DEBUG_RULE( dostatement );
00124     BOOST_SPIRIT_DEBUG_RULE( trystatement );
00125     BOOST_SPIRIT_DEBUG_RULE( catchpart );
00126     BOOST_SPIRIT_DEBUG_RULE( statement );
00127     BOOST_SPIRIT_DEBUG_RULE( line );
00128     BOOST_SPIRIT_DEBUG_RULE( content );
00129     BOOST_SPIRIT_DEBUG_RULE( program );
00130     BOOST_SPIRIT_DEBUG_RULE( production );
00131     BOOST_SPIRIT_DEBUG_RULE( valuechange );
00132     BOOST_SPIRIT_DEBUG_RULE( function );
00133     BOOST_SPIRIT_DEBUG_RULE( functions );
00134     BOOST_SPIRIT_DEBUG_RULE( arguments );
00135     BOOST_SPIRIT_DEBUG_RULE( returnstatement );
00136     BOOST_SPIRIT_DEBUG_RULE( funcstatement );
00137     BOOST_SPIRIT_DEBUG_RULE( continuepart );
00138     BOOST_SPIRIT_DEBUG_RULE( callpart );
00139     BOOST_SPIRIT_DEBUG_RULE( returnpart );
00140     BOOST_SPIRIT_DEBUG_RULE( ifstatement );
00141     BOOST_SPIRIT_DEBUG_RULE( whilestatement );
00142     BOOST_SPIRIT_DEBUG_RULE( forstatement );
00143     BOOST_SPIRIT_DEBUG_RULE( breakstatement );
00144     BOOST_SPIRIT_DEBUG_RULE( ifblock );
00145     BOOST_SPIRIT_DEBUG_RULE( funcargs );
00146 
00147     
00148     openbrace = expect_open( ch_p('(') );
00149     closebrace = expect_close( ch_p(')') );
00150     opencurly = expect_opencurly( ch_p('{') );
00151     closecurly = expect_closecurly( ch_p('}') );
00152     semicolon = expect_semicolon( ch_p(';') );
00153     condition = expect_condition( conditionparser.parser()[ boost::bind(&ProgramGraphParser::seencondition, this) ] );
00154 
00155     
00156     
00157     
00158     
00159     
00160     production = *( program | function )[boost::bind(&ProgramGraphParser::programtext,this, _1, _2)] >> expect_eof(end_p) ;
00161 
00162     
00163     function = (
00164             
00165        !( keyword_p( "export" )[boost::bind(&ProgramGraphParser::exportdef, this)] | keyword_p( "global" )[boost::bind(&ProgramGraphParser::globaldef, this)] | keyword_p("local") )[boost::bind(&ProgramGraphParser::seenvalidinput, this)]
00166        >> (keyword_p( "function" )[boost::bind(&ProgramGraphParser::seenvalidinput, this)] | commonparser.notassertingidentifier[boost::bind( &ProgramGraphParser::seenreturntype, this, _1, _2)] )
00167        >> expect_ident( commonparser.identifier[boost::bind(&ProgramGraphParser::seenvalidinput, this)][ boost::bind( &ProgramGraphParser::functiondef, this, _1, _2 ) ] )
00168        >> !funcargs
00169        >> opencurly
00170        >> content
00171        >> expect_closefunction( ch_p('}') )[ boost::bind( &ProgramGraphParser::seenfunctionend, this ) ]
00172        );
00173 
00174     
00175     funcargs = ch_p('(') >> ( !str_p("void") >> ch_p(')') | ((
00176          valuechangeparser.bareDefinitionParser()[boost::bind(&ProgramGraphParser::seenfunctionarg, this)]
00177              >> *(ch_p(',')>> valuechangeparser.bareDefinitionParser()[boost::bind(&ProgramGraphParser::seenfunctionarg, this)]) )
00178         >> closebrace ));
00179 
00180     
00181     program =
00182         keyword_p( "program" )[boost::bind(&ProgramGraphParser::seenvalidinput, this)]
00183       >> expect_ident( commonparser.identifier[ boost::bind( &ProgramGraphParser::programdef, this, _1, _2 ) ] )
00184       >> opencurly
00185       >> content
00186       >> expect_closefunction( ch_p('}') )[ boost::bind( &ProgramGraphParser::seenprogramend, this ) ];
00187 
00188     
00189     content = *line;
00190 
00191     
00192     
00193     
00194     
00195     
00196     line = statement[boost::bind(&ProgramGraphParser::noskip_eol, this )] >> commonparser.eos[boost::bind(&ProgramGraphParser::skip_eol, this )];
00197 
00198     statement = valuechange | trystatement | funcstatement | returnstatement | ifstatement | whilestatement | forstatement | breakstatement | dostatement;
00199 
00200     valuechange = valuechangeparser.parser()[ boost::bind( &ProgramGraphParser::seenvaluechange, this ) ];
00201 
00202     
00203     dostatement = !keyword_p("do") >> !keyword_p("set") >> !keyword_p("call") >>
00204             (
00205              ( keyword_p("yield") | keyword_p("nothing"))[boost::bind(&ProgramGraphParser::seenyield,this)]
00206             | expressionparser.parser()[ boost::bind(&ProgramGraphParser::seenstatement,this) ]
00207             );
00208 
00209     
00210     trystatement =
00211         keyword_p("try")
00212          >> expect_command ( expressionparser.parser()[ boost::bind( &ProgramGraphParser::seentrystatement, this ) ] )
00213          >> !catchpart;
00214 
00215   }
00216 
00217     void ProgramGraphParser::initBodyParser(const std::string& name, Service::shared_ptr stck, int offset) {
00218         ln_offset = offset;
00219         assert(program_builder != 0 );
00220         program_builder->startFunction(name);
00221         this->setStack( stck );
00222         this->clearParseState();
00223     }
00224 
00225     rule_t& ProgramGraphParser::programParser() {
00226         return program;
00227     }
00228 
00229     rule_t& ProgramGraphParser::functionParser() {
00230         return function;
00231     }
00232 
00233     rule_t& ProgramGraphParser::bodyParser() {
00234         
00235         return content;
00236     }
00237 
00238     rule_t& ProgramGraphParser::statementParser() {
00239         
00240         return line;
00241     }
00242 
00243     ProgramInterfacePtr ProgramGraphParser::programParserResult() {
00244         ProgramInterfacePtr result;
00245         if (program_list.empty())
00246             return result;
00247         program_text = "Bug: Program Text to be set by Parser.";
00248         
00249         program_list.front()->setText( program_text );
00250         result=program_list.front();
00251         this->cleanup(false);
00252         program_list.clear();
00253         return result;
00254     }
00255 
00256     ProgramInterfacePtr ProgramGraphParser::bodyParserResult() {
00257 
00258         
00259         valuechangeparser.store( context );
00260         valuechangeparser.reset();
00261 
00262         
00263         program_builder->returnFunction( new ConditionTrue, mpositer.get_position().line - ln_offset );
00264         program_builder->proceedToNext( mpositer.get_position().line - ln_offset);
00265         return program_builder->endFunction( mpositer.get_position().line - ln_offset );
00266     }
00267 
00268 
00269 
00270 
00271 
00272 
00273 
00274 
00275 
00276     bool ProgramGraphParser::parserUsed() const {
00277         return parserused;
00278     }
00279 
00280     void ProgramGraphParser::setStack(Service::shared_ptr st) {
00281         context = st;
00282         valuechangeparser.load(context);
00283     }
00284 
00285     void ProgramGraphParser::clearParseState() {
00286         exportf = false;
00287         parserused = false;
00288         rettype.clear();
00289     }
00290 
00291     void ProgramGraphParser::startofprogram()
00292     {
00293     }
00294 
00295   void ProgramGraphParser::programdef( iter_t begin, iter_t end )
00296   {
00297       
00298 
00299       std::string def(begin, end);
00300 
00301       if ( rootc->provides()->hasService( def ) )
00302           throw parse_exception_semantic_error("Service with name '" + def + "' already present in task '"+rootc->getName()+"'.");
00303 
00304       FunctionGraphPtr pi(program_builder->startFunction( def ));
00305       
00306       ProgramServicePtr ptsk(new ProgramService( pi, rootc ));
00307       pi->setProgramService(ptsk);
00308       pi->setUnloadOnStop( false ); 
00309       context = ptsk;
00310       rootc->provides()->addService( ptsk );
00311   }
00312 
00313   void ProgramGraphParser::programtext( iter_t begin, iter_t end )
00314   {
00315       
00316       
00317   }
00318 
00319   void ProgramGraphParser::exportdef()
00320   {
00321       exportf = true;
00322   }
00323 
00324   void ProgramGraphParser::globaldef()
00325   {
00326       globalf = true;
00327   }
00328 
00329   void ProgramGraphParser::seenreturntype( iter_t begin, iter_t end )
00330   {
00331       rettype = std::string(begin, end);
00332   }
00333   void ProgramGraphParser::functiondef( iter_t begin, iter_t end )
00334   {
00335       
00336       
00337       std::string funcdef(begin, end);
00338       
00339 
00340 
00341 
00342 
00343 
00344 
00345 
00346 
00347       
00348       
00349       
00350       if ( mfuncs.count( funcdef ) )
00351           throw parse_exception_semantic_error("function " + funcdef + " redefined.");
00352 
00353       AttributeBase* retarg = 0;
00354       if ( !rettype.empty() && rettype != "void") {
00355           TypeInfo* type = TypeInfoRepository::Instance()->type( rettype );
00356           if ( type == 0 )
00357               throw_( iter_t(), "Return type '" + rettype + "' for function '"+ funcdef +"' is an unknown type." );
00358           retarg = type->buildAttribute("result");
00359       }
00360 
00361       mfuncs[funcdef] = program_builder->startFunction( funcdef );
00362       program_builder->getFunction()->setResult( retarg );
00363 
00364       rettype.clear();
00365 
00366       
00367       
00368       fcontext = new TaskContext(funcdef, rootc->engine() );
00369       context = fcontext->provides();
00370   }
00371 
00372   void ProgramGraphParser::seenfunctionarg()
00373   {
00374       
00375       
00376       
00377       program_builder->getFunction()->addArgument( valuechangeparser.lastDefinedValue()->clone() );
00378       valuechangeparser.clear();
00379   }
00380 
00381   void ProgramGraphParser::seenfunctionend()
00382   {
00383       
00384       program_builder->returnFunction( new ConditionTrue, mpositer.get_position().line - ln_offset );
00385       program_builder->proceedToNext( mpositer.get_position().line - ln_offset );
00386       boost::shared_ptr<ProgramInterface> mfunc = program_builder->endFunction( mpositer.get_position().line - ln_offset );
00387 
00388       
00389       if (exportf) {
00390           std::map<const DataSourceBase*, DataSourceBase*> dummy;
00391           FunctionFactory* cfi = new FunctionFactory(ProgramInterfacePtr(mfunc->copy(dummy)), rootc->engine() ); 
00392           if (rootc->provides()->hasMember( mfunc->getName() ) )
00393               log(Warning) << "Redefining function '"<< rootc->getName() << "." << mfunc->getName() << "': only new programs will use this new function." <<endlog();
00394           rootc->provides()->add(mfunc->getName(), cfi );
00395           Logger::log() << Logger::Info << "Exported Function '" << mfunc->getName() << "' added to task '"<< rootc->getName() << "'" <<Logger::endl;
00396       }
00397       
00398       else if (globalf){
00399           std::map<const DataSourceBase*, DataSourceBase*> dummy;
00400           FunctionFactory* cfi = new FunctionFactory(ProgramInterfacePtr(mfunc->copy(dummy)), rootc->engine() ); 
00401           if (GlobalService::Instance()->provides()->hasMember( mfunc->getName() ) )
00402               log(Warning) << "Redefining function '"<< GlobalService::Instance()->getName() << "."<< mfunc->getName() << "': only new programs will use this new function." <<endlog();
00403           GlobalService::Instance()->provides()->add(mfunc->getName(), cfi );
00404           Logger::log() << Logger::Debug << "Seen Function '" << mfunc->getName() << "' for Global Service." <<Logger::endl;
00405       } else {
00406           std::map<const DataSourceBase*, DataSourceBase*> dummy;
00407           FunctionFactory* cfi = new FunctionFactory(ProgramInterfacePtr(mfunc->copy(dummy)), rootc->engine() ); 
00408           if (rootc->provides("scripting")->hasMember( mfunc->getName() ) )
00409               log(Warning) << "Redefining function '"<< rootc->getName() << ".scripting."<< mfunc->getName() << "': only new programs will use this new function." <<endlog();
00410           rootc->provides("scripting")->add(mfunc->getName(), cfi );
00411           Logger::log() << Logger::Debug << "Seen Function '" << mfunc->getName() << "' for scripting service of '"<< rootc->getName() << "'" <<Logger::endl;
00412       }
00413 
00414 
00415       delete fcontext;
00416       fcontext = 0;
00417       context.reset();
00418 
00419       
00420       exportf = false; globalf = false;
00421 
00422       valuechangeparser.reset();
00423   }
00424 
00425   void ProgramGraphParser::seenvalidinput() {
00426       parserused = true;
00427   }
00428 
00429   void ProgramGraphParser::seencondition()
00430   {
00431        mcondition = conditionparser.getParseResult();
00432        assert( mcondition );
00433 
00434        
00435        
00436        
00437        
00438        
00439        
00440   }
00441 
00442   void ProgramGraphParser::seenreturnstatement()
00443   {
00444       
00445       program_builder->returnFunction( new ConditionTrue, mpositer.get_position().line - ln_offset );
00446       program_builder->proceedToNext(  mpositer.get_position().line - ln_offset );
00447   }
00448 
00449   void ProgramGraphParser::seenreturnvalue()
00450   {
00451       AttributeBase* ar =program_builder->getFunction()->getResult();
00452       if ( ar == 0) {
00453           throw parse_exception_syntactic_error("Returning a value in a function returning (void).");
00454       }
00455       DataSourceBase::shared_ptr expr  = expressionparser.getResult().get();
00456       expressionparser.dropResult();
00457       try {
00458           ActionInterface* assigncomm = ar->getDataSource()->updateAction( expr.get() );
00459           
00460           program_builder->setCommand( assigncomm );
00461           program_builder->proceedToNext( new ConditionTrue(), mpositer.get_position().line - ln_offset );
00462       }
00463       catch(...) {
00464           
00465           throw parse_exception_syntactic_error("Could not convert '" + expr->getType() + "' to '"+ ar->getDataSource()->getType() +"' in return statement.");
00466       }
00467   }
00468 
00469   void ProgramGraphParser::seenbreakstatement()
00470   {
00471       if ( program_builder->inLoop() ) {
00472           program_builder->breakLoop();
00473           program_builder->proceedToNext( mpositer.get_position().line - ln_offset );
00474       } else
00475           throw parse_exception_syntactic_error("Illegal use of 'break'. Can only be used within for and while loops.");
00476   }
00477 
00478   void ProgramGraphParser::seenfuncidentifier( iter_t begin, iter_t end )
00479   {
00480       
00481       std::string fname(begin, end);
00482       if ( mfuncs.count(fname) == 0 )
00483           throw parse_exception_semantic_error("calling function " + fname + " but it is not defined ( remove the 'call' keyword ).");
00484       if ( fname == program_builder->getFunction()->getName() )
00485           throw parse_exception_semantic_error("calling function " + fname + " recursively is not allowed.");
00486 
00487       mcallfunc = mfuncs[ fname ];
00488 
00489       
00490       argsparser = new ArgumentsParser( expressionparser, rootc, rootc->provides(),
00491                                         "this", fname );
00492       arguments = argsparser->parser();
00493 
00494   }
00495 
00496   void ProgramGraphParser::seencallfuncargs()
00497   {
00498       callfnargs = argsparser->result();
00499   }
00500 
00501   void ProgramGraphParser::seencallfuncstatement()
00502   {
00503       log(Warning) << " 'call' has been deprecated. Please remove this keyword." << endlog();
00504       
00505       
00506 
00507       
00508       assert( mcallfunc );
00509         try
00510             {
00511                 program_builder->setFunction( mcallfunc, callfnargs );
00512                 
00513                 delete argsparser;
00514                 argsparser = 0;
00515                 callfnargs.clear();
00516             }
00517         catch( const wrong_number_of_args_exception& e )
00518             {
00519                 throw parse_exception_wrong_number_of_arguments
00520                     ( rootc->getName(), mcallfunc->getName(), e.wanted, e.received );
00521             }
00522         catch( const wrong_types_of_args_exception& e )
00523             {
00524                 throw parse_exception_wrong_type_of_argument
00525                     ( rootc->getName(), mcallfunc->getName(), e.whicharg, e.expected_, e.received_ );
00526             }
00527         catch( ... )
00528             {
00529                 assert( false );
00530             }
00531 
00532       
00533       
00534       program_builder->proceedToNext(mpositer.get_position().line - ln_offset);
00535   }
00536 
00537     void ProgramGraphParser::skip_eol() {
00538         commonparser.skipeol = true;
00539     }
00540 
00541     void ProgramGraphParser::noskip_eol() {
00542         commonparser.skipeol = false;
00543     }
00544 
00545     void ProgramGraphParser::startcatchpart() {
00546         
00547         
00548         assert( try_cond );
00549         program_builder->startIfStatement( try_cond, mpositer.get_position().line - ln_offset );
00550         try_cond = 0;
00551     }
00552 
00553     void ProgramGraphParser::seencatchpart() {
00554         this->endifblock();
00555         this->endifstatement(); 
00556     }
00557 
00558     void ProgramGraphParser::seenifstatement() {
00559         assert(mcondition);
00560         
00561         
00562         std::pair<ActionInterface*, ConditionInterface*> comcon;
00563         comcon = conditionparser.getParseResultAsCommand();
00564         program_builder->setCommand( comcon.first );
00565         program_builder->startIfStatement( comcon.second, mpositer.get_position().line - ln_offset );
00566 
00567         
00568         delete mcondition;
00569         mcondition = 0;
00570     }
00571 
00572     void ProgramGraphParser::endifblock() {
00573         program_builder->endIfBlock(mpositer.get_position().line - ln_offset);
00574     }
00575 
00576 
00577     void ProgramGraphParser::endifstatement() {
00578         program_builder->endElseBlock(mpositer.get_position().line - ln_offset);
00579     }
00580 
00581     void ProgramGraphParser::seenwhilestatement() {
00582         
00583         
00584         assert(mcondition);
00585         std::pair<ActionInterface*, ConditionInterface*> comcon;
00586         comcon = conditionparser.getParseResultAsCommand();
00587         program_builder->setCommand( comcon.first );
00588         program_builder->startWhileStatement( comcon.second, mpositer.get_position().line - ln_offset );
00589 
00590         delete mcondition;
00591         mcondition = 0;
00592     }
00593 
00594     void ProgramGraphParser::endwhilestatement() {
00595         program_builder->endWhileBlock(mpositer.get_position().line - ln_offset);
00596     }
00597 
00598 
00599     void ProgramGraphParser::seenforinit()
00600     {
00601         
00602         
00603       ActionInterface* ac = 0;
00604       std::vector<ActionInterface*> acv = valuechangeparser.assignCommands();
00605       
00606       valuechangeparser.clear();
00607       if ( acv.size() == 1) {
00608           ac = acv.front();
00609       }
00610       else if (acv.size() > 1) {
00611           ac = new CommandComposite( acv );
00612       }
00613       for_init_command = ac;
00614     }
00615 
00616     void ProgramGraphParser::seenforinit_expr()
00617     {
00618         DataSourceBase::shared_ptr expr = expressionparser.getResult();
00619         expressionparser.dropResult();
00620         for_init_command = new CommandDataSource( expr );
00621     }
00622 
00623     void ProgramGraphParser::seenforincr()
00624     {
00625         DataSourceBase::shared_ptr expr = expressionparser.getResult();
00626         expressionparser.dropResult();
00627         for_incr_command.push( new CommandDataSource( expr ) );
00628     }
00629 
00630     void ProgramGraphParser::seenemptyforincr()
00631     {
00632         for_incr_command.push( 0 );
00633     }
00634 
00635     void ProgramGraphParser::seenforstatement() {
00636         assert( mcondition );
00637 
00638         
00639         if ( for_init_command )
00640             {
00641                 program_builder->setCommand( for_init_command );
00642                 program_builder->proceedToNext( new ConditionTrue, mpositer.get_position().line - ln_offset );
00643             }
00644         for_init_command = 0;
00645 
00646         
00647         std::pair<ActionInterface*, ConditionInterface*> comcon;
00648         comcon = conditionparser.getParseResultAsCommand();
00649         program_builder->setCommand( comcon.first );
00650         program_builder->startWhileStatement( comcon.second, mpositer.get_position().line - ln_offset );
00651         delete mcondition;
00652         mcondition = 0;
00653     }
00654 
00655     void ProgramGraphParser::endforstatement() {
00656         
00657         ActionInterface* incr = for_incr_command.top();
00658         for_incr_command.pop();
00659         
00660         if ( incr )
00661             {
00662                 program_builder->setCommand( incr );
00663                 
00664                 
00665                 program_builder->proceedToNext( new ConditionTrue, mpositer.get_position().line - ln_offset );
00666             }
00667         program_builder->endWhileBlock(mpositer.get_position().line - ln_offset);
00668     }
00669 
00670   void ProgramGraphParser::seenprogramend()
00671   {
00672       
00673       program_builder->returnFunction( new ConditionTrue, mpositer.get_position().line - ln_offset );
00674       program_builder->proceedToNext( mpositer.get_position().line - ln_offset );
00675       program_list.push_back(program_builder->endFunction( mpositer.get_position().line - ln_offset ) );
00676 
00677       
00678       valuechangeparser.store( context );
00679       valuechangeparser.reset();
00680   }
00681 
00682   std::vector< ProgramInterfacePtr > ProgramGraphParser::parse( iter_t& begin, iter_t end )
00683   {
00684       
00685     iter_t begin_copy = begin;
00686     skip_parser_t skip_parser = comment_p( "#" ) | comment_p( "//" ) | comment_p( "/*", "*/" ) | (space_p - eol_p) | commonparser.skipper;
00687     iter_pol_t iter_policy( skip_parser );
00688     scanner_pol_t policies( iter_policy );
00689     scanner_t scanner( begin, end, policies );
00690     program_list.clear();
00691 
00692     
00693     
00694 
00695     try {
00696       if ( ! production.parse( scanner ) )
00697       {
00698           
00699         cleanup(true);
00700         throw file_parse_exception(new parse_exception_syntactic_error( " no valid input found." ),
00701                                    mpositer.get_position().file, mpositer.get_position().line,
00702                                    mpositer.get_position().column );
00703       }
00704       program_text = std::string( begin_copy, begin ); 
00705       
00706       for (std::vector<FunctionGraphPtr>::iterator it= program_list.begin();it!=program_list.end();++it)
00707           (*it)->setText( program_text );
00708       this->cleanup(false);
00709       std::vector<ProgramInterfacePtr> result;
00710       for (std::vector<FunctionGraphPtr>::iterator it= program_list.begin();it!=program_list.end();++it)
00711           result.push_back( *it );
00712       program_list.clear();
00713       return result;
00714     }
00715     catch( const parser_error<std::string, iter_t>& e )
00716         {
00717             cleanup(true);
00718             program_list.clear();
00719             throw file_parse_exception(
00720                 new parse_exception_syntactic_error( e.descriptor ),
00721                 mpositer.get_position().file, mpositer.get_position().line,
00722                 mpositer.get_position().column );
00723 
00724         }
00725     
00726     catch( const parse_exception& e )
00727     {
00728         cleanup(true);
00729       program_list.clear();
00730       throw file_parse_exception(
00731                 e.copy(), mpositer.get_position().file,
00732                 mpositer.get_position().line, mpositer.get_position().column );
00733     }
00734   }
00735 
00736   std::vector< ProgramInterfacePtr > ProgramGraphParser::parseFunction( iter_t& begin, iter_t end )
00737   {
00738       
00739     iter_t begin_copy = begin;
00740     
00741     
00742     iter_pol_t iter_policy( ( comment_p( "#" ) | comment_p( "//" ) | comment_p( "/*", "*/" ) | (space_p - eol_p) | commonparser.skipper  ) );
00743     scanner_pol_t policies( iter_policy );
00744     scanner_t scanner( begin, end, policies );
00745 
00746     std::vector< ProgramInterfacePtr > function_list;
00747 
00748     try {
00749       if ( ! functions.parse( scanner ) )
00750       {
00751           
00752         cleanup(false);
00753         throw file_parse_exception(new parse_exception_syntactic_error( " no valid input found." ),
00754                                    mpositer.get_position().file, mpositer.get_position().line,
00755                                    mpositer.get_position().column );
00756       }
00757       program_text = std::string( begin_copy, begin ); 
00758       
00759       for (funcmap::iterator it= mfuncs.begin();it!=mfuncs.end();++it) {
00760           it->second->setText( program_text );      
00761           function_list.push_back( it->second );
00762       }
00763 
00764       this->cleanup(false);
00765       return function_list;
00766     }
00767     
00768     catch( const parser_error<std::string, iter_t>& e )
00769         {
00770             cleanup(false);
00771             throw file_parse_exception(
00772                 new parse_exception_syntactic_error( e.descriptor ),
00773                 mpositer.get_position().file, mpositer.get_position().line,
00774                 mpositer.get_position().column );
00775 
00776         }
00777     
00778     catch( const parse_exception& e )
00779     {
00780         cleanup(false);
00781         throw file_parse_exception(
00782                 e.copy(), mpositer.get_position().file,
00783                 mpositer.get_position().line, mpositer.get_position().column );
00784     }
00785   }
00786 
00787   void ProgramGraphParser::cleanup(bool unload_service)
00788   {
00789       if (unload_service && rootc && context)
00790           rootc->provides()->removeService( context->getName() );
00791       
00792       
00793       delete argsparser;
00794       argsparser = 0;
00795       delete implcond;
00796       implcond = 0;
00797       delete mcondition;
00798       mcondition = 0;
00799       delete try_cond;
00800       try_cond = 0;
00801       delete for_init_command;
00802       for_init_command = 0;
00803       while (!for_incr_command.empty() ) {
00804           delete for_incr_command.top();
00805           for_incr_command.pop();
00806       }
00807       
00808       delete fcontext;
00809       fcontext = 0;
00810       exportf = false; globalf = false;
00811       rettype.clear();
00812       if ( rootc == 0)
00813           return;
00814 
00815 
00816 
00817 
00818 
00819 
00820       while ( ! mfuncs.empty() ) {
00821           mfuncs.erase( mfuncs.begin() );
00822       }
00823       context.reset();
00824 
00825       valuechangeparser.reset();
00826       conditionparser.reset();
00827       peerparser.reset();
00828   }
00829 
00830   void ProgramGraphParser::seentrystatement()
00831   {
00832       
00833       ActionInterface*   command;
00834       DataSourceBase::shared_ptr expr  = expressionparser.getResult().get();
00835       expressionparser.dropResult();
00836       DataSource<bool>* bexpr = dynamic_cast<DataSource<bool>*>(expr.get());
00837       if (bexpr == 0) {
00838           
00839           command = new CommandDataSource( expr );
00840           try_cond = new ConditionFalse(); 
00841           program_builder->setCommand(command);
00842       } else {
00843           command = new CommandDataSourceBool( bexpr );
00844 
00845           
00846           TryCommand* trycommand =  new TryCommand( command );
00847           
00848           TryCommandResult* tryresult = new TryCommandResult( trycommand->result(), true );
00849           program_builder->setCommand( trycommand );
00850           try_cond = tryresult; 
00851       }
00852       if ( program_builder->buildEdges() == 0 )
00853           program_builder->proceedToNext( new ConditionTrue(), mpositer.get_position().line - ln_offset );
00854       else
00855           program_builder->proceedToNext( mpositer.get_position().line - ln_offset );      
00856   }
00857 
00858   void ProgramGraphParser::seenstatement()
00859   {
00860       
00861       DataSourceBase::shared_ptr expr  = expressionparser.getResult().get();
00862       expressionparser.dropResult();
00863       DataSource<bool>* bexpr = dynamic_cast<DataSource<bool>*>(expr.get());
00864       if (bexpr)
00865           program_builder->setCommand( new CommandDataSourceBool( bexpr ) );
00866       else
00867           program_builder->setCommand( new CommandDataSource( expr ) );
00868       if ( program_builder->buildEdges() == 0 )
00869           program_builder->proceedToNext( new ConditionTrue(), mpositer.get_position().line - ln_offset );
00870       else
00871           program_builder->proceedToNext( mpositer.get_position().line - ln_offset );
00872   }
00873 
00874   void ProgramGraphParser::seenyield()
00875   {
00876       
00877       program_builder->setCommand( new CommandNOP );
00878       program_builder->proceedToNext( new ConditionOnce(false), mpositer.get_position().line - ln_offset );
00879   }
00880 
00881   void ProgramGraphParser::seenvaluechange()
00882   {
00883     
00884     
00885       ActionInterface* ac = 0;
00886       std::vector<ActionInterface*> acv = valuechangeparser.assignCommands();
00887       
00888       valuechangeparser.clear();
00889       if ( acv.size() == 1) {
00890           ac = acv.front();
00891       }
00892       else if (acv.size() > 1) {
00893           ac = new CommandComposite(acv);
00894       }
00895       if (ac) {
00896           program_builder->setCommand( ac );
00897           
00898           
00899           program_builder->proceedToNext( new ConditionTrue, mpositer.get_position().line - ln_offset );
00900       }
00901   }
00902 
00903     void ProgramGraphParser::seencallfunclabel( iter_t begin, iter_t end )
00904     {
00905           
00906           
00907           seenfuncidentifier( begin, end );
00908 
00909           assert( mcondition );
00910           assert( mcallfunc );
00911           program_builder->appendFunction( mcondition, mcallfunc, callfnargs);
00912           mcondition = 0;
00913 
00914     }
00915 
00916     void ProgramGraphParser::seencontinue( )
00917     {
00918         
00919         
00920         assert ( mcondition );
00921 
00922         
00923         program_builder->addConditionEdge( mcondition, program_builder->nextNode() );
00924 
00925         mcondition = 0;
00926       }
00927 }