ProgramGraphParser.cpp
Go to the documentation of this file.
00001 /***************************************************************************
00002   tag: Peter Soetens  Mon May 10 19:10:37 CEST 2004  ProgramGraphParser.cxx
00003 
00004                         ProgramGraphParser.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 #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       // putting the code in setup() works around a GCC 4.1 bug.
00101       this->setup();
00102       this->setup2();
00103   }
00104 
00105   ProgramGraphParser::~ProgramGraphParser() {
00106       // necessary in case we were used outside of our parse() methods.
00107       // we also try to remove the service, because the user will call programParserResult()
00108       // to do cleanup himself, in which case this becomes a no-op.
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     //newline = ch_p( '\n' );
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     // program is the production rule of this grammar.  The
00156     // production rule is the rule that the entire input should be
00157     // matched by...  This line basically means that we're finished
00158     // ;)
00159     // Zero or n functions can precede the program.
00160     production = *( program | function )[boost::bind(&ProgramGraphParser::programtext,this, _1, _2)] >> expect_eof(end_p) ;
00161 
00162     // a function is very similar to a program, but it also has a name
00163     function = (
00164             // optional visibility qualifiers:
00165        !( keyword_p( "export" )[boost::bind(&ProgramGraphParser::exportdef, this)] | keyword_p( "global" )[boost::bind(&ProgramGraphParser::globaldef, this)] | keyword_p("local") )
00166        >> (keyword_p( "function" ) | commonparser.notassertingidentifier[boost::bind( &ProgramGraphParser::seenreturntype, this, _1, _2)])
00167        >> expect_ident( commonparser.identifier[ 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     // the function's definition args :
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     // a program looks like "program { content }".
00181     program =
00182         keyword_p( "program" )
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     // the content of a program can be any number of lines
00189     content = *line;
00190 
00191     // a line can be empty or contain a statement. Empty is
00192     // necessary, because comment's are skipped, but newline's
00193     // aren't.  So a line like "/* very interesting comment
00194     // */\n" will reach us as simply "\n"..
00195     //line = !( statement ) >> eol_p;
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     // take into account deprecated 'do' and 'set'
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     // a try statement: "try xxx catch { stuff to do once on any error} "
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         // content is the bodyparser of a program or function
00235         return content;
00236     }
00237 
00238     rule_t& ProgramGraphParser::statementParser() {
00239         // line is the statement parser of a program or function
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         // set the program text in each program :
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         // store the variables in the program's taskcontext object.
00259         valuechangeparser.store( context );
00260         valuechangeparser.reset();
00261 
00262         // Fake a 'return' statement at the last line.
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 //    ProgramInterfacePtr ProgramGraphParser::statementParserResult() {
00269 //
00270 //        // Fake a 'return' statement at the last line.
00271 //        program_builder->returnFunction( new ConditionTrue, mpositer.get_position().line - ln_offset );
00272 //        program_builder->proceedToNext( mpositer.get_position().line - ln_offset);
00273 //        return program_builder->getFunction();
00274 //    }
00275 
00276     void ProgramGraphParser::setStack(Service::shared_ptr st) {
00277         context = st;
00278         valuechangeparser.load(context);
00279     }
00280 
00281     void ProgramGraphParser::clearParseState() {
00282         exportf = false;
00283         rettype.clear();
00284     }
00285 
00286     void ProgramGraphParser::startofprogram()
00287     {
00288     }
00289 
00290   void ProgramGraphParser::programdef( iter_t begin, iter_t end )
00291   {
00292       // Now that we got the name, set everything up:
00293 
00294       std::string def(begin, end);
00295 
00296       if ( rootc->provides()->hasService( def ) )
00297           throw parse_exception_semantic_error("Service with name '" + def + "' already present in task '"+rootc->getName()+"'.");
00298 
00299       FunctionGraphPtr pi(program_builder->startFunction( def ));
00300       // ptsk becomes the owner of pi.
00301       ProgramServicePtr ptsk(new ProgramService( pi, rootc ));
00302       pi->setProgramService(ptsk);
00303       pi->setUnloadOnStop( false ); // since we assign a service, set this to false.
00304       context = ptsk;
00305       rootc->provides()->addService( ptsk );
00306   }
00307 
00308   void ProgramGraphParser::programtext( iter_t begin, iter_t end )
00309   {
00310       // we set it in the parse() function. It is set to the whole script such that line numbers are correct.
00311       //program_text = std::string(begin, end);
00312   }
00313 
00314   void ProgramGraphParser::exportdef()
00315   {
00316       exportf = true;
00317   }
00318 
00319   void ProgramGraphParser::globaldef()
00320   {
00321       globalf = true;
00322   }
00323 
00324   void ProgramGraphParser::seenreturntype( iter_t begin, iter_t end )
00325   {
00326       rettype = std::string(begin, end);
00327   }
00328   void ProgramGraphParser::functiondef( iter_t begin, iter_t end )
00329   {
00330       // store the function in our map for later
00331       // referencing.
00332       std::string funcdef(begin, end);
00333       // store the function in the TaskContext current.__functions
00334 //       TaskContext* __f = rootc->getPeer("__functions");
00335 //       if ( __f == 0 ) {
00336 //           // install the __functions if not yet present.
00337 //           __f = new TaskContext("__functions", rootc->engine() );
00338 //           rootc->connectPeers( __f );
00339 //       }
00340 
00341 //       if ( __f->hasPeer( funcdef ) )
00342       // only redefining a function twice in the same file is an error. If the function
00343       // was already added to the scripting or component interface before, we replace it
00344       // and warn about it in seenfunctionend():
00345       if ( mfuncs.count( funcdef ) )
00346           throw parse_exception_semantic_error("function " + funcdef + " redefined.");
00347 
00348       AttributeBase* retarg = 0;
00349       if ( !rettype.empty() && rettype != "void") {
00350           TypeInfo* type = TypeInfoRepository::Instance()->type( rettype );
00351           if ( type == 0 )
00352               throw_( iter_t(), "Return type '" + rettype + "' for function '"+ funcdef +"' is an unknown type." );
00353           retarg = type->buildAttribute("result");
00354       }
00355 
00356       mfuncs[funcdef] = program_builder->startFunction( funcdef );
00357       program_builder->getFunction()->setResult( retarg );
00358 
00359       rettype.clear();
00360 
00361       // Connect the new function to the relevant contexts.
00362       // 'fun' acts as a stack for storing variables.
00363       fcontext = new TaskContext(funcdef, rootc->engine() );
00364       context = fcontext->provides();
00365   }
00366 
00367   void ProgramGraphParser::seenfunctionarg()
00368   {
00369       // the ValueChangeParser stores each variable in the
00370       // current stack's repository, but we need to inform the
00371       // FunctionGraph itself about its arguments.
00372       program_builder->getFunction()->addArgument( valuechangeparser.lastDefinedValue()->clone() );
00373       valuechangeparser.clear();
00374   }
00375 
00376   void ProgramGraphParser::seenfunctionend()
00377   {
00378       // Fake a 'return' statement at the last line.
00379       program_builder->returnFunction( new ConditionTrue, mpositer.get_position().line - ln_offset );
00380       program_builder->proceedToNext( mpositer.get_position().line - ln_offset );
00381       boost::shared_ptr<ProgramInterface> mfunc = program_builder->endFunction( mpositer.get_position().line - ln_offset );
00382 
00383       // export the function in the context's interface.
00384       if (exportf) {
00385           std::map<const DataSourceBase*, DataSourceBase*> dummy;
00386           FunctionFactory* cfi = new FunctionFactory(ProgramInterfacePtr(mfunc->copy(dummy)), rootc->engine() ); // execute in the processor which has the command.
00387           if (rootc->provides()->hasMember( mfunc->getName() ) )
00388               log(Warning) << "Redefining function '"<< rootc->getName() << "." << mfunc->getName() << "': only new programs will use this new function." <<endlog();
00389           rootc->provides()->add(mfunc->getName(), cfi );
00390           Logger::log() << Logger::Info << "Exported Function '" << mfunc->getName() << "' added to task '"<< rootc->getName() << "'" <<Logger::endl;
00391       }
00392       // attach the function to the global service interface.
00393       else if (globalf){
00394           std::map<const DataSourceBase*, DataSourceBase*> dummy;
00395           FunctionFactory* cfi = new FunctionFactory(ProgramInterfacePtr(mfunc->copy(dummy)), rootc->engine() ); // execute in the processor which has the command.
00396           if (GlobalService::Instance()->provides()->hasMember( mfunc->getName() ) )
00397               log(Warning) << "Redefining function '"<< GlobalService::Instance()->getName() << "."<< mfunc->getName() << "': only new programs will use this new function." <<endlog();
00398           GlobalService::Instance()->provides()->add(mfunc->getName(), cfi );
00399           Logger::log() << Logger::Debug << "Seen Function '" << mfunc->getName() << "' for Global Service." <<Logger::endl;
00400       } else {
00401           std::map<const DataSourceBase*, DataSourceBase*> dummy;
00402           FunctionFactory* cfi = new FunctionFactory(ProgramInterfacePtr(mfunc->copy(dummy)), rootc->engine() ); // execute in the processor which has the command.
00403           if (rootc->provides("scripting")->hasMember( mfunc->getName() ) )
00404               log(Warning) << "Redefining function '"<< rootc->getName() << ".scripting."<< mfunc->getName() << "': only new programs will use this new function." <<endlog();
00405           rootc->provides("scripting")->add(mfunc->getName(), cfi );
00406           Logger::log() << Logger::Debug << "Seen Function '" << mfunc->getName() << "' for scripting service of '"<< rootc->getName() << "'" <<Logger::endl;
00407       }
00408 
00409 
00410       delete fcontext;
00411       fcontext = 0;
00412       context.reset();
00413 
00414       // reset
00415       exportf = false; globalf = false;
00416 
00417       valuechangeparser.reset();
00418   }
00419 
00420   void ProgramGraphParser::seencondition()
00421   {
00422        mcondition = conditionparser.getParseResult();
00423        assert( mcondition );
00424 
00425        // leaves the condition in the parser, if we want to use
00426        // getParseResultAsCommand();
00427        // mcondition is only used with seen*label statements,
00428        // when the command and condition are associated,
00429        // not in the branching where the evaluation of the
00430        // condition is the command.
00431   }
00432 
00433   void ProgramGraphParser::seenreturnstatement()
00434   {
00435       // return statement can happen in program and in a function
00436       program_builder->returnFunction( new ConditionTrue, mpositer.get_position().line - ln_offset );
00437       program_builder->proceedToNext(  mpositer.get_position().line - ln_offset );
00438   }
00439 
00440   void ProgramGraphParser::seenreturnvalue()
00441   {
00442       AttributeBase* ar =program_builder->getFunction()->getResult();
00443       if ( ar == 0) {
00444           throw parse_exception_syntactic_error("Returning a value in a function returning (void).");
00445       }
00446       DataSourceBase::shared_ptr expr  = expressionparser.getResult().get();
00447       expressionparser.dropResult();
00448       try {
00449           ActionInterface* assigncomm = ar->getDataSource()->updateAction( expr.get() );
00450           // assign the return value to the return argument.
00451           program_builder->setCommand( assigncomm );
00452           program_builder->proceedToNext( new ConditionTrue(), mpositer.get_position().line - ln_offset );
00453       }
00454       catch(...) {
00455           // catch exception from updateAction.
00456           throw parse_exception_syntactic_error("Could not convert '" + expr->getType() + "' to '"+ ar->getDataSource()->getType() +"' in return statement.");
00457       }
00458   }
00459 
00460   void ProgramGraphParser::seenbreakstatement()
00461   {
00462       if ( program_builder->inLoop() ) {
00463           program_builder->breakLoop();
00464           program_builder->proceedToNext( mpositer.get_position().line - ln_offset );
00465       } else
00466           throw parse_exception_syntactic_error("Illegal use of 'break'. Can only be used within for and while loops.");
00467   }
00468 
00469   void ProgramGraphParser::seenfuncidentifier( iter_t begin, iter_t end )
00470   {
00471       // store the part after 'call'
00472       std::string fname(begin, end);
00473       if ( mfuncs.count(fname) == 0 )
00474           throw parse_exception_semantic_error("calling function " + fname + " but it is not defined ( remove the 'call' keyword ).");
00475       if ( fname == program_builder->getFunction()->getName() )
00476           throw parse_exception_semantic_error("calling function " + fname + " recursively is not allowed.");
00477 
00478       mcallfunc = mfuncs[ fname ];
00479 
00480       // Parse the function's args in the programs context.
00481       argsparser = new ArgumentsParser( expressionparser, rootc, rootc->provides(),
00482                                         "this", fname );
00483       arguments = argsparser->parser();
00484 
00485   }
00486 
00487   void ProgramGraphParser::seencallfuncargs()
00488   {
00489       callfnargs = argsparser->result();
00490   }
00491 
00492   void ProgramGraphParser::seencallfuncstatement()
00493   {
00494       log(Warning) << " 'call' has been deprecated. Please remove this keyword." << endlog();
00495       // This function is called if the 'call func' is outside
00496       // a termination clause.
00497 
00498       // add it to the main program line of execution.
00499       assert( mcallfunc );
00500         try
00501             {
00502                 program_builder->setFunction( mcallfunc, callfnargs );
00503                 // only delete parser, when the args are used.
00504                 delete argsparser;
00505                 argsparser = 0;
00506                 callfnargs.clear();
00507             }
00508         catch( const wrong_number_of_args_exception& e )
00509             {
00510                 throw parse_exception_wrong_number_of_arguments
00511                     ( rootc->getName(), mcallfunc->getName(), e.wanted, e.received );
00512             }
00513         catch( const wrong_types_of_args_exception& e )
00514             {
00515                 throw parse_exception_wrong_type_of_argument
00516                     ( rootc->getName(), mcallfunc->getName(), e.whicharg, e.expected_, e.received_ );
00517             }
00518         catch( ... )
00519             {
00520                 assert( false );
00521             }
00522 
00523       // The exit node of the function is already connected
00524       // to program->nextNode().
00525       program_builder->proceedToNext(mpositer.get_position().line - ln_offset);
00526   }
00527 
00528     void ProgramGraphParser::skip_eol() {
00529         commonparser.skipeol = true;
00530     }
00531 
00532     void ProgramGraphParser::noskip_eol() {
00533         commonparser.skipeol = false;
00534     }
00535 
00536     void ProgramGraphParser::startcatchpart() {
00537         // we saved the try_cond in the previous try statement,
00538         // now process like it said if ( try_cond ) then {...}
00539         assert( try_cond );
00540         program_builder->startIfStatement( try_cond, mpositer.get_position().line - ln_offset );
00541         try_cond = 0;
00542     }
00543 
00544     void ProgramGraphParser::seencatchpart() {
00545         this->endifblock();
00546         this->endifstatement(); // there is no 'else' part, so close the statement
00547     }
00548 
00549     void ProgramGraphParser::seenifstatement() {
00550         assert(mcondition);
00551         // transform the evaluation in a command, and pass the result
00552         // as a condition
00553         std::pair<ActionInterface*, ConditionInterface*> comcon;
00554         comcon = conditionparser.getParseResultAsCommand();
00555         program_builder->setCommand( comcon.first );
00556         program_builder->startIfStatement( comcon.second, mpositer.get_position().line - ln_offset );
00557 
00558         // we did not need this.
00559         delete mcondition;
00560         mcondition = 0;
00561     }
00562 
00563     void ProgramGraphParser::endifblock() {
00564         program_builder->endIfBlock(mpositer.get_position().line - ln_offset);
00565     }
00566 
00567 
00568     void ProgramGraphParser::endifstatement() {
00569         program_builder->endElseBlock(mpositer.get_position().line - ln_offset);
00570     }
00571 
00572     void ProgramGraphParser::seenwhilestatement() {
00573         // analogous to seenifstatement
00574         // the evaluation is a command.
00575         assert(mcondition);
00576         std::pair<ActionInterface*, ConditionInterface*> comcon;
00577         comcon = conditionparser.getParseResultAsCommand();
00578         program_builder->setCommand( comcon.first );
00579         program_builder->startWhileStatement( comcon.second, mpositer.get_position().line - ln_offset );
00580 
00581         delete mcondition;
00582         mcondition = 0;
00583     }
00584 
00585     void ProgramGraphParser::endwhilestatement() {
00586         program_builder->endWhileBlock(mpositer.get_position().line - ln_offset);
00587     }
00588 
00589 
00590     void ProgramGraphParser::seenforinit()
00591     {
00592         // the for loop is different from the while and if branch
00593         // structures in that it places an init command before the loop.
00594       ActionInterface* ac = 0;
00595       std::vector<ActionInterface*> acv = valuechangeparser.assignCommands();
00596       // and not forget to reset()..
00597       valuechangeparser.clear();
00598       if ( acv.size() == 1) {
00599           ac = acv.front();
00600       }
00601       else if (acv.size() > 1) {
00602           ac = new CommandComposite( acv );
00603       }
00604       for_init_command = ac;
00605     }
00606 
00607     void ProgramGraphParser::seenforinit_expr()
00608     {
00609         DataSourceBase::shared_ptr expr = expressionparser.getResult();
00610         expressionparser.dropResult();
00611         for_init_command = new CommandDataSource( expr );
00612     }
00613 
00614     void ProgramGraphParser::seenforincr()
00615     {
00616         DataSourceBase::shared_ptr expr = expressionparser.getResult();
00617         expressionparser.dropResult();
00618         for_incr_command.push( new CommandDataSource( expr ) );
00619     }
00620 
00621     void ProgramGraphParser::seenemptyforincr()
00622     {
00623         for_incr_command.push( 0 );
00624     }
00625 
00626     void ProgramGraphParser::seenforstatement() {
00627         assert( mcondition );
00628 
00629         // first insert the initialisation command.
00630         if ( for_init_command )
00631             {
00632                 program_builder->setCommand( for_init_command );
00633                 program_builder->proceedToNext( new ConditionTrue, mpositer.get_position().line - ln_offset );
00634             }
00635         for_init_command = 0;
00636 
00637         // A for is nothing more than a while loop...
00638         std::pair<ActionInterface*, ConditionInterface*> comcon;
00639         comcon = conditionparser.getParseResultAsCommand();
00640         program_builder->setCommand( comcon.first );
00641         program_builder->startWhileStatement( comcon.second, mpositer.get_position().line - ln_offset );
00642         delete mcondition;
00643         mcondition = 0;
00644     }
00645 
00646     void ProgramGraphParser::endforstatement() {
00647         // the last statement is a _conditional_ increment of the 'counter'
00648         ActionInterface* incr = for_incr_command.top();
00649         for_incr_command.pop();
00650         // is null or an action to increment
00651         if ( incr )
00652             {
00653                 program_builder->setCommand( incr );
00654                 // Since a valuechange does not add edges, we use this variant
00655                 // to create one.
00656                 program_builder->proceedToNext( new ConditionTrue, mpositer.get_position().line - ln_offset );
00657             }
00658         program_builder->endWhileBlock(mpositer.get_position().line - ln_offset);
00659     }
00660 
00661   void ProgramGraphParser::seenprogramend()
00662   {
00663       // Fake a 'return' statement at the last line.
00664       program_builder->returnFunction( new ConditionTrue, mpositer.get_position().line - ln_offset );
00665       program_builder->proceedToNext( mpositer.get_position().line - ln_offset );
00666       program_list.push_back(program_builder->endFunction( mpositer.get_position().line - ln_offset ) );
00667 
00668       // store the variables in the program's taskcontext object.
00669       valuechangeparser.store( context );
00670       valuechangeparser.reset();
00671   }
00672 
00673   std::vector< ProgramInterfacePtr > ProgramGraphParser::parse( iter_t& begin, iter_t end )
00674   {
00675       // end is not used !
00676     iter_t begin_copy = begin;
00677     //skip_parser_t skip_parser = SKIP_PARSER;
00678     //iter_pol_t iter_policy( skip_parser );
00679     iter_pol_t iter_policy( ( comment_p( "#" ) | comment_p( "//" ) | comment_p( "/*", "*/" ) | (space_p - eol_p) | commonparser.skipper  ) );
00680     scanner_pol_t policies( iter_policy );
00681     scanner_t scanner( begin, end, policies );
00682     program_list.clear();
00683 
00684     // todo :Add a universal collect/collectIfDone/ret(sendh, args) operationfactoryparts.
00685     //rootc->add("collect",&ProgramGraphParser::collectHandler, this)
00686 
00687     try {
00688       if ( ! production.parse( scanner ) )
00689       {
00690           // This gets shown if we didn't even get the chance to throw an exception :
00691         cleanup(true);
00692         throw file_parse_exception(new parse_exception_syntactic_error( " no valid input found." ),
00693                                    mpositer.get_position().file, mpositer.get_position().line,
00694                                    mpositer.get_position().column );
00695       }
00696       program_text = std::string( begin_copy, begin ); // begin is by reference.
00697       // set the program text in each program :
00698       for (std::vector<FunctionGraphPtr>::iterator it= program_list.begin();it!=program_list.end();++it)
00699           (*it)->setText( program_text );
00700       this->cleanup(false);
00701       std::vector<ProgramInterfacePtr> result;
00702       for (std::vector<FunctionGraphPtr>::iterator it= program_list.begin();it!=program_list.end();++it)
00703           result.push_back( *it );
00704       program_list.clear();
00705       return result;
00706     }
00707     catch( const parser_error<std::string, iter_t>& e )
00708         {
00709             cleanup(true);
00710             program_list.clear();
00711             throw file_parse_exception(
00712                 new parse_exception_syntactic_error( e.descriptor ),
00713                 mpositer.get_position().file, mpositer.get_position().line,
00714                 mpositer.get_position().column );
00715 
00716         }
00717     // Catch our Orocos exceptions
00718     catch( const parse_exception& e )
00719     {
00720         cleanup(true);
00721       program_list.clear();
00722       throw file_parse_exception(
00723                 e.copy(), mpositer.get_position().file,
00724                 mpositer.get_position().line, mpositer.get_position().column );
00725     }
00726   }
00727 
00728   std::vector< ProgramInterfacePtr > ProgramGraphParser::parseFunction( iter_t& begin, iter_t end )
00729   {
00730       // end is not used !
00731     iter_t begin_copy = begin;
00732     //skip_parser_t skip_parser = SKIP_PARSER;
00733     //iter_pol_t iter_policy( skip_parser );
00734     iter_pol_t iter_policy( ( comment_p( "#" ) | comment_p( "//" ) | comment_p( "/*", "*/" ) | (space_p - eol_p) | commonparser.skipper  ) );
00735     scanner_pol_t policies( iter_policy );
00736     scanner_t scanner( begin, end, policies );
00737 
00738     std::vector< ProgramInterfacePtr > function_list;
00739 
00740     try {
00741       if ( ! functions.parse( scanner ) )
00742       {
00743           // This gets shown if we didn't even get the chance to throw an exception :
00744         cleanup(false);
00745         throw file_parse_exception(new parse_exception_syntactic_error( " no valid input found." ),
00746                                    mpositer.get_position().file, mpositer.get_position().line,
00747                                    mpositer.get_position().column );
00748       }
00749       program_text = std::string( begin_copy, begin ); // begin is by reference.
00750       // set the program text in each function :
00751       for (funcmap::iterator it= mfuncs.begin();it!=mfuncs.end();++it) {
00752           it->second->setText( program_text );      // set text.
00753           function_list.push_back( it->second );
00754       }
00755 
00756       this->cleanup(false);
00757       return function_list;
00758     }
00759     // Catch Boost::Spirit exceptions
00760     catch( const parser_error<std::string, iter_t>& e )
00761         {
00762             cleanup(false);
00763             throw file_parse_exception(
00764                 new parse_exception_syntactic_error( e.descriptor ),
00765                 mpositer.get_position().file, mpositer.get_position().line,
00766                 mpositer.get_position().column );
00767 
00768         }
00769     // Catch our Orocos exceptions
00770     catch( const parse_exception& e )
00771     {
00772         cleanup(false);
00773         throw file_parse_exception(
00774                 e.copy(), mpositer.get_position().file,
00775                 mpositer.get_position().line, mpositer.get_position().column );
00776     }
00777   }
00778 
00779   void ProgramGraphParser::cleanup(bool unload_service)
00780   {
00781       if (unload_service && rootc && context)
00782           rootc->provides()->removeService( context->getName() );
00783       // after an exception, we can be in any state, so cleanup
00784       // all temp objects.
00785       delete argsparser;
00786       argsparser = 0;
00787       delete implcond;
00788       implcond = 0;
00789       delete mcondition;
00790       mcondition = 0;
00791       delete try_cond;
00792       try_cond = 0;
00793       delete for_init_command;
00794       for_init_command = 0;
00795       while (!for_incr_command.empty() ) {
00796           delete for_incr_command.top();
00797           for_incr_command.pop();
00798       }
00799       // cleanup all functions :
00800       delete fcontext;
00801       fcontext = 0;
00802       exportf = false; globalf = false;
00803       rettype.clear();
00804       if ( rootc == 0)
00805           return;
00806 //       TaskContext* __f = rootc->getPeer("__functions");
00807 //       if ( __f != 0 ) {
00808 //           // first remove rootc from __f itself
00809 //           rootc->disconnectPeers( __f->getName() );
00810 //           delete __f;
00811 //       }
00812       while ( ! mfuncs.empty() ) {
00813           mfuncs.erase( mfuncs.begin() );
00814       }
00815       context.reset();
00816 
00817       valuechangeparser.reset();
00818       conditionparser.reset();
00819       peerparser.reset();
00820   }
00821 
00822   void ProgramGraphParser::seentrystatement()
00823   {
00824       // a try expression/method call.
00825       ActionInterface*   command;
00826       DataSourceBase::shared_ptr expr  = expressionparser.getResult().get();
00827       expressionparser.dropResult();
00828       DataSource<bool>* bexpr = dynamic_cast<DataSource<bool>*>(expr.get());
00829       if (bexpr == 0) {
00830           // if not returning a bool, the try is useless.
00831           command = new CommandDataSource( expr );
00832           try_cond = new ConditionFalse(); // never execute catch part.
00833           program_builder->setCommand(command);
00834       } else {
00835           command = new CommandDataSourceBool( bexpr );
00836 
00837           // try-wrap the asyn or dispatch command, store the result in try_cond.
00838           TryCommand* trycommand =  new TryCommand( command );
00839           // returns true if failure :
00840           TryCommandResult* tryresult = new TryCommandResult( trycommand->result(), true );
00841           program_builder->setCommand( trycommand );
00842           try_cond = tryresult; // save try_cond for catch part (ie true if failure)
00843       }
00844       if ( program_builder->buildEdges() == 0 )
00845           program_builder->proceedToNext( new ConditionTrue(), mpositer.get_position().line - ln_offset );
00846       else
00847           program_builder->proceedToNext( mpositer.get_position().line - ln_offset );      // we get the data from commandparser
00848   }
00849 
00850   void ProgramGraphParser::seenstatement()
00851   {
00852       // an expression/method call (former do).
00853       DataSourceBase::shared_ptr expr  = expressionparser.getResult().get();
00854       expressionparser.dropResult();
00855       DataSource<bool>* bexpr = dynamic_cast<DataSource<bool>*>(expr.get());
00856       if (bexpr)
00857           program_builder->setCommand( new CommandDataSourceBool( bexpr ) );
00858       else
00859           program_builder->setCommand( new CommandDataSource( expr ) );
00860       if ( program_builder->buildEdges() == 0 )
00861           program_builder->proceedToNext( new ConditionTrue(), mpositer.get_position().line - ln_offset );
00862       else
00863           program_builder->proceedToNext( mpositer.get_position().line - ln_offset );
00864   }
00865 
00866   void ProgramGraphParser::seenyield()
00867   {
00868       // a yield branch
00869       program_builder->setCommand( new CommandNOP );
00870       program_builder->proceedToNext( new ConditionOnce(false), mpositer.get_position().line - ln_offset );
00871   }
00872 
00873   void ProgramGraphParser::seenvaluechange()
00874   {
00875     // some value changes generate a command, we need to add it to
00876     // the program.
00877       ActionInterface* ac = 0;
00878       std::vector<ActionInterface*> acv = valuechangeparser.assignCommands();
00879       // and not forget to reset()..
00880       valuechangeparser.clear();
00881       if ( acv.size() == 1) {
00882           ac = acv.front();
00883       }
00884       else if (acv.size() > 1) {
00885           ac = new CommandComposite(acv);
00886       }
00887       if (ac) {
00888           program_builder->setCommand( ac );
00889           // Since a valuechange does not add edges, we use this variant
00890           // to create one.
00891           program_builder->proceedToNext( new ConditionTrue, mpositer.get_position().line - ln_offset );
00892       }
00893   }
00894 
00895     void ProgramGraphParser::seencallfunclabel( iter_t begin, iter_t end )
00896     {
00897           // Used for "call xyz"
00898           // lookup mcallfunc
00899           seenfuncidentifier( begin, end );
00900 
00901           assert( mcondition );
00902           assert( mcallfunc );
00903           program_builder->appendFunction( mcondition, mcallfunc, callfnargs);
00904           mcondition = 0;
00905 
00906     }
00907 
00908     void ProgramGraphParser::seencontinue( )
00909     {
00910         // @todo complete the impl for for/while loops.
00911         // Used for "continue"
00912         assert ( mcondition );
00913 
00914         // connect to next node under given condition.
00915         program_builder->addConditionEdge( mcondition, program_builder->nextNode() );
00916 
00917         mcondition = 0;
00918       }
00919 }


rtt
Author(s): RTT Developers
autogenerated on Thu Jan 2 2014 11:35:23